From 55e7e1eb3e0340e91404e57ea1c4ebd502d8f089 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 23 Apr 2014 15:24:03 +0900 Subject: [PATCH] Copter: allow HYBRID to be disabled to save flash Hybrid flight mode costs 4.5k of flash which currently puts us over the limit for APM1 and APM2 unless optical flow or other features are disabled --- ArduCopter/APM_Config.h | 1 + ArduCopter/Parameters.pde | 2 ++ ArduCopter/config.h | 3 +++ ArduCopter/control_hybrid.pde | 4 ++++ ArduCopter/flight_mode.pde | 4 ++++ 5 files changed, 14 insertions(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index ab6bd158e1..a43cfecb75 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -31,6 +31,7 @@ //#define CAMERA DISABLED // disable camera trigger to save 1k of flash //#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash +//#define HYBRID_ENABLED DISABLED // disable hybrid flight mode to save 4.5k of flash // features below are disabled by default //#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 57b7afc08c..1813880445 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -407,6 +407,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_VERY_CRISP), +#if HYBRID_ENABLED == ENABLED // @Param: HYBR_BRAKE_RATE // @DisplayName: Hybrid braking rate // @Description: hybrid flight mode's rotation rate during braking in deg/sec @@ -421,6 +422,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Range: 2000 4500 // @User: Advanced GSCALAR(hybrid_brake_angle_max, "HYBR_BRAKE_ANGLE", HYBRID_BRAKE_ANGLE_DEFAULT), +#endif #if FRAME_CONFIG == HELI_FRAME // @Group: HS1_ diff --git a/ArduCopter/config.h b/ArduCopter/config.h index cf3787d53d..fce023f367 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -635,6 +635,9 @@ ////////////////////////////////////////////////////////////////////////////// // Hybrid parameter defaults // +#ifndef HYBRID_ENABLED + # define HYBRID_ENABLED ENABLED // hybrid flight mode enabled by default +#endif #ifndef HYBRID_BRAKE_RATE_DEFAULT # define HYBRID_BRAKE_RATE_DEFAULT 8 // default HYBRID_BRAKE_RATE param value. Rotation rate during braking in deg/sec #endif diff --git a/ArduCopter/control_hybrid.pde b/ArduCopter/control_hybrid.pde index 0661798c73..2a74187ea7 100644 --- a/ArduCopter/control_hybrid.pde +++ b/ArduCopter/control_hybrid.pde @@ -1,5 +1,7 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#if HYBRID_ENABLED == ENABLED + /* * control_hybrid.pde - init and run calls for hybrid flight mode * hybrid tries to improve upon regular loiter by mixing the pilot input with the loiter controller @@ -661,3 +663,5 @@ static void hybrid_pitch_controller_to_pilot_override() // store final loiter outputs for mixing with pilot input hybrid.controller_final_pitch = hybrid.pitch; } + +#endif // HYBRID_ENABLED == ENABLED diff --git a/ArduCopter/flight_mode.pde b/ArduCopter/flight_mode.pde index 6a2418f1c2..c2135ff52b 100644 --- a/ArduCopter/flight_mode.pde +++ b/ArduCopter/flight_mode.pde @@ -87,9 +87,11 @@ static bool set_mode(uint8_t mode) break; #endif +#if HYBRID_ENABLED == ENABLED case HYBRID: success = hybrid_init(ignore_checks); break; +#endif default: success = false; @@ -182,9 +184,11 @@ static void update_flight_mode() break; #endif +#if HYBRID_ENABLED == ENABLED case HYBRID: hybrid_run(); break; +#endif } }