mirror of https://github.com/ArduPilot/ardupilot
Copter: disable Parachute by default
This saves 1k of flash and we are desperately low on the APM1/APM2. Hopefully we can find savings somewhere and re-enable it by default.
This commit is contained in:
parent
ea64438ef9
commit
19f1e7fec4
|
@ -29,13 +29,13 @@
|
|||
//#define AC_RALLY DISABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
|
||||
//#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 OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
|
||||
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
|
||||
//#define EPM_ENABLED ENABLED // enable epm cargo gripper costs 500bytes of flash
|
||||
//#define PARACHUTE ENABLED // enable parachute release at a cost of 1k of flash
|
||||
|
||||
// other settings
|
||||
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
|
||||
|
|
|
@ -413,7 +413,7 @@
|
|||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Parachute release
|
||||
#ifndef PARACHUTE
|
||||
# define PARACHUTE ENABLED
|
||||
# define PARACHUTE DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
Loading…
Reference in New Issue