Browse Source

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
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
55e7e1eb3e
  1. 1
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/Parameters.pde
  3. 3
      ArduCopter/config.h
  4. 4
      ArduCopter/control_hybrid.pde
  5. 4
      ArduCopter/flight_mode.pde

1
ArduCopter/APM_Config.h

@ -31,6 +31,7 @@ @@ -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)

2
ArduCopter/Parameters.pde

@ -407,6 +407,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -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 = { @@ -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_

3
ArduCopter/config.h

@ -635,6 +635,9 @@ @@ -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

4
ArduCopter/control_hybrid.pde

@ -1,5 +1,7 @@ @@ -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() @@ -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

4
ArduCopter/flight_mode.pde

@ -87,9 +87,11 @@ static bool set_mode(uint8_t mode) @@ -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() @@ -182,9 +184,11 @@ static void update_flight_mode()
break;
#endif
#if HYBRID_ENABLED == ENABLED
case HYBRID:
hybrid_run();
break;
#endif
}
}

Loading…
Cancel
Save