Sub: Change user config file for default options. Eventually these will be moved into the main config file as Sub defaults.

This commit is contained in:
Rustom Jehangir 2016-01-01 15:43:46 -08:00 committed by Andrew Tridgell
parent 54fa879116
commit 1e8c1e8a78
2 changed files with 16 additions and 11 deletions

View File

@ -21,20 +21,20 @@
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) // 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 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 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 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 AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash //#define CAMERA DISABLED // disable camera trigger to save 1k of flash
//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash //#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k 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_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
//#define AC_TERRAIN DISABLED // disable terrain library #define AC_TERRAIN DISABLED // disable terrain library
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash #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 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 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 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 OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry //#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
//#define ADSB_ENABLED DISABLED // disable ADSB support #define ADSB_ENABLED DISABLED // disable ADSB support
// features below are disabled by default on all boards // 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 SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)

View File

@ -13,7 +13,12 @@ static uint32_t auto_disarm_begin;
// called at 10hz // called at 10hz
void Copter::arm_motors_check() void Copter::arm_motors_check()
{ {
static int16_t arming_counter; // Arm motors automatically
if ( !motors.armed() ) {
init_arm_motors(false);
}
/*static int16_t arming_counter;
// ensure throttle is down // ensure throttle is down
if (channel_throttle->control_in > 0) { if (channel_throttle->control_in > 0) {
@ -66,13 +71,13 @@ void Copter::arm_motors_check()
// Yaw is centered so reset arming counter // Yaw is centered so reset arming counter
}else{ }else{
arming_counter = 0; arming_counter = 0;
} }*/
} }
// auto_disarm_check - disarms the copter if it has been sitting on the ground in manual mode with throttle low for at least 15 seconds // auto_disarm_check - disarms the copter if it has been sitting on the ground in manual mode with throttle low for at least 15 seconds
void Copter::auto_disarm_check() void Copter::auto_disarm_check()
{ {
uint32_t tnow_ms = millis(); /*uint32_t tnow_ms = millis();
uint32_t disarm_delay_ms = 1000*constrain_int16(g.disarm_delay, 0, 127); uint32_t disarm_delay_ms = 1000*constrain_int16(g.disarm_delay, 0, 127);
// exit immediately if we are already disarmed, or if auto // exit immediately if we are already disarmed, or if auto
@ -117,7 +122,7 @@ void Copter::auto_disarm_check()
if ((tnow_ms-auto_disarm_begin) >= disarm_delay_ms) { if ((tnow_ms-auto_disarm_begin) >= disarm_delay_ms) {
init_disarm_motors(); init_disarm_motors();
auto_disarm_begin = tnow_ms; auto_disarm_begin = tnow_ms;
} }*/
} }
// init_arm_motors - performs arming process including initialisation of barometer and gyros // init_arm_motors - performs arming process including initialisation of barometer and gyros