Copter: enable EPM by default on Pixhawk
This commit is contained in:
parent
bbe4438a6b
commit
adf00a207b
@ -34,11 +34,11 @@
|
||||
// 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 EPM_ENABLED ENABLED // enable epm cargo gripper costs 500bytes of flash
|
||||
|
||||
// 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
|
||||
//#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 NAV_GUIDED ENABLED // enable external navigation computer to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||
|
||||
// other settings
|
||||
|
@ -81,9 +81,11 @@
|
||||
|
||||
#define MAGNETOMETER ENABLED
|
||||
|
||||
// disable some features for APM1/APM2
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
||||
# define PARACHUTE DISABLED
|
||||
# define AC_RALLY DISABLED
|
||||
# define EPM_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
@ -391,7 +393,7 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// EPM cargo gripper
|
||||
#ifndef EPM_ENABLED
|
||||
# define EPM_ENABLED DISABLED
|
||||
# define EPM_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
Loading…
Reference in New Issue
Block a user