mirror of https://github.com/ArduPilot/ardupilot
Copter: cleanup enabling of cli and frsky telem for APM
This commit is contained in:
parent
26b5321130
commit
a1e707b7f9
|
@ -19,10 +19,6 @@
|
|||
*/
|
||||
|
||||
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_APM1)
|
||||
# define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
||||
# define FRSKY_TELEM_ENABLED DISABLED // disable the FRSKY TELEM
|
||||
#endif
|
||||
//#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
|
||||
|
@ -34,6 +30,7 @@
|
|||
// features below are disabled by default on APM (but enabled on Pixhawk)
|
||||
//#define AC_RALLY ENABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
|
||||
//#define PARACHUTE ENABLED // enable parachute release at a cost of 1k of flash
|
||||
//#define CLI_ENABLED ENABLED // enable the CLI (command-line-interface) at a cost of 21K of flash space
|
||||
|
||||
// features below are disabled by default on all boards
|
||||
//#define OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
|
||||
|
|
|
@ -84,6 +84,8 @@
|
|||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
||||
# define PARACHUTE DISABLED
|
||||
# define AC_RALLY DISABLED
|
||||
# define CLI_ENABLED DISABLED
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
|
|
Loading…
Reference in New Issue