forked from olliw42/storm32bgc
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
104 changed files
with
30,080 additions
and
0 deletions.
There are no files selected for viewing
Large diffs are not rendered by default.
Oops, something went wrong.
61 changes: 61 additions & 0 deletions
61
betacopter/betacopter34-v011r-dist/ArduCopter/APM_Config.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,61 @@ | ||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- | ||
|
||
// User specific config file. Any items listed in config.h can be overridden here. | ||
|
||
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer | ||
// valid! You should switch to using a HAL_BOARD flag in your local config.mk. | ||
|
||
//#define FRAME_CONFIG QUAD_FRAME | ||
/* options: | ||
* QUAD_FRAME | ||
* TRI_FRAME | ||
* HEXA_FRAME | ||
* Y6_FRAME | ||
* OCTA_FRAME | ||
* OCTA_QUAD_FRAME | ||
* HELI_FRAME | ||
* SINGLE_FRAME | ||
* COAX_FRAME | ||
*/ | ||
|
||
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) | ||
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space | ||
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space | ||
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash | ||
//#define AC_FENCE DISABLED // disable fence to save 2k of flash | ||
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash | ||
//#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash | ||
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash | ||
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally) | ||
//#define AC_TERRAIN DISABLED // disable terrain library | ||
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash | ||
//#define EPM_ENABLED DISABLED // disable epm cargo gripper to save 500bytes of flash | ||
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space | ||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands | ||
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space | ||
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry | ||
//#define ADSB_ENABLED DISABLED // disable ADSB support | ||
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor | ||
|
||
// features below are disabled by default on all boards | ||
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity) | ||
//#define GNDEFFECT_COMPENSATION ENABLED // enable ground effect compensation for barometer (if propwash interferes with the barometer on the ground) | ||
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes | ||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link | ||
|
||
// other settings | ||
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000) | ||
//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED // when set to ENABLED vehicle will only disarm after landing (in AUTO, LAND or RTL) if pilot has put throttle to zero | ||
|
||
//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation | ||
|
||
// User Hooks : For User Developed code that you wish to run | ||
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below). | ||
//#define USERHOOK_VARIABLES "UserVariables.h" | ||
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below | ||
//#define USERHOOK_INIT userhook_init(); // for code to be run once at startup | ||
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz | ||
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz | ||
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz | ||
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz | ||
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz |
30 changes: 30 additions & 0 deletions
30
betacopter/betacopter34-v011r-dist/ArduCopter/APM_Config_mavlink_hil.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,30 @@ | ||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- | ||
|
||
// HIL_MODE SELECTION | ||
// | ||
// Mavlink supports | ||
// 1. HIL_MODE_SENSORS: full sensor simulation | ||
#define HIL_MODE HIL_MODE_SENSORS | ||
|
||
// HIL_PORT SELCTION | ||
// | ||
// PORT 1 | ||
// If you would like to run telemetry communications for a groundstation | ||
// while you are running hardware in the loop it is necessary to set | ||
// HIL_PORT to 1. This uses the port that would have been used for the gps | ||
// as the hardware in the loop port. You will have to solder | ||
// headers onto the gps port connection on the apm | ||
// and connect via an ftdi cable. | ||
// | ||
// The baud rate is set to 115200 in this mode. | ||
// | ||
// PORT 3 | ||
// If you don't require telemetry communication with a gcs while running | ||
// hardware in the loop you may use the telemetry port as the hardware in | ||
// the loop port. Alternatively, use a telemetry/HIL shim like FGShim | ||
// https://ardupilot-mega.googlecode.com/svn/Tools/trunk/FlightGear | ||
// | ||
// The buad rate is controlled by SERIAL1_BAUD in this mode. | ||
|
||
#define HIL_PORT 3 | ||
|
141 changes: 141 additions & 0 deletions
141
betacopter/betacopter34-v011r-dist/ArduCopter/AP_State.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,141 @@ | ||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- | ||
|
||
#include "Copter.h" | ||
|
||
// set_home_state - update home state | ||
void Copter::set_home_state(enum HomeState new_home_state) | ||
{ | ||
// if no change, exit immediately | ||
if (ap.home_state == new_home_state) | ||
return; | ||
|
||
// update state | ||
ap.home_state = new_home_state; | ||
|
||
// log if home has been set | ||
if (new_home_state == HOME_SET_NOT_LOCKED || new_home_state == HOME_SET_AND_LOCKED) { | ||
Log_Write_Event(DATA_SET_HOME); | ||
} | ||
} | ||
|
||
// home_is_set - returns true if home positions has been set (to GPS location, armed location or EKF origin) | ||
bool Copter::home_is_set() | ||
{ | ||
return (ap.home_state == HOME_SET_NOT_LOCKED || ap.home_state == HOME_SET_AND_LOCKED); | ||
} | ||
|
||
// --------------------------------------------- | ||
void Copter::set_auto_armed(bool b) | ||
{ | ||
// if no change, exit immediately | ||
if( ap.auto_armed == b ) | ||
return; | ||
|
||
ap.auto_armed = b; | ||
if(b){ | ||
Log_Write_Event(DATA_AUTO_ARMED); | ||
} | ||
} | ||
|
||
// --------------------------------------------- | ||
void Copter::set_simple_mode(uint8_t b) | ||
{ | ||
if(ap.simple_mode != b){ | ||
if(b == 0){ | ||
Log_Write_Event(DATA_SET_SIMPLE_OFF); | ||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode off"); | ||
}else if(b == 1){ | ||
Log_Write_Event(DATA_SET_SIMPLE_ON); | ||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode on"); | ||
}else{ | ||
// initialise super simple heading | ||
update_super_simple_bearing(true); | ||
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON); | ||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on"); | ||
} | ||
ap.simple_mode = b; | ||
} | ||
} | ||
|
||
// --------------------------------------------- | ||
void Copter::set_failsafe_radio(bool b) | ||
{ | ||
// only act on changes | ||
// ------------------- | ||
if(failsafe.radio != b) { | ||
|
||
// store the value so we don't trip the gate twice | ||
// ----------------------------------------------- | ||
failsafe.radio = b; | ||
|
||
if (failsafe.radio == false) { | ||
// We've regained radio contact | ||
// ---------------------------- | ||
failsafe_radio_off_event(); | ||
}else{ | ||
// We've lost radio contact | ||
// ------------------------ | ||
failsafe_radio_on_event(); | ||
} | ||
|
||
// update AP_Notify | ||
AP_Notify::flags.failsafe_radio = b; | ||
} | ||
} | ||
|
||
|
||
// --------------------------------------------- | ||
void Copter::set_failsafe_battery(bool b) | ||
{ | ||
failsafe.battery = b; | ||
AP_Notify::flags.failsafe_battery = b; | ||
} | ||
|
||
// --------------------------------------------- | ||
void Copter::set_failsafe_gcs(bool b) | ||
{ | ||
failsafe.gcs = b; | ||
} | ||
|
||
// --------------------------------------------- | ||
|
||
void Copter::set_pre_arm_check(bool b) | ||
{ | ||
if(ap.pre_arm_check != b) { | ||
ap.pre_arm_check = b; | ||
AP_Notify::flags.pre_arm_check = b; | ||
} | ||
} | ||
|
||
void Copter::set_pre_arm_rc_check(bool b) | ||
{ | ||
if(ap.pre_arm_rc_check != b) { | ||
ap.pre_arm_rc_check = b; | ||
} | ||
} | ||
|
||
void Copter::update_using_interlock() | ||
{ | ||
#if FRAME_CONFIG == HELI_FRAME | ||
// helicopters are always using motor interlock | ||
ap.using_interlock = true; | ||
#else | ||
// check if we are using motor interlock control on an aux switch or are in throw mode | ||
// which uses the interlock to stop motors while the copter is being thrown | ||
ap.using_interlock = check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) || (control_mode == THROW); | ||
#endif | ||
} | ||
|
||
void Copter::set_motor_emergency_stop(bool b) | ||
{ | ||
if(ap.motor_emergency_stop != b) { | ||
ap.motor_emergency_stop = b; | ||
} | ||
|
||
// Log new status | ||
if (ap.motor_emergency_stop){ | ||
Log_Write_Event(DATA_MOTORS_EMERGENCY_STOPPED); | ||
} else { | ||
Log_Write_Event(DATA_MOTORS_EMERGENCY_STOP_CLEARED); | ||
} | ||
} |
Oops, something went wrong.