Copter: enable PARACHUTE and RALLY for all but APM

This commit is contained in:
Randy Mackay 2014-05-27 14:43:33 +09:00
parent 796aaac475
commit 20719e23fd
2 changed files with 9 additions and 17 deletions

View File

@ -30,12 +30,14 @@
//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash //#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
//#define HYBRID_ENABLED DISABLED // disable hybrid flight mode to save 4.5k of flash //#define HYBRID_ENABLED DISABLED // disable hybrid flight mode to save 4.5k of flash
// features below are disabled by default // features below are disabled by default on APM (but enabled on Pixhawk)
//#define OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
//#define AC_RALLY ENABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands //#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
// 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 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 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 // other settings
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000) //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)

View File

@ -59,6 +59,8 @@
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000 # define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define PARACHUTE DISABLED
# define AC_RALLY DISABLED
# ifdef APM2_BETA_HARDWARE # ifdef APM2_BETA_HARDWARE
# define CONFIG_BARO AP_BARO_BMP085 # define CONFIG_BARO AP_BARO_BMP085
# else // APM2 Production Hardware (default) # else // APM2 Production Hardware (default)
@ -69,13 +71,11 @@
# define CONFIG_IMU_TYPE CONFIG_IMU_SITL # define CONFIG_IMU_TYPE CONFIG_IMU_SITL
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define OPTFLOW DISABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
# define CONFIG_IMU_TYPE CONFIG_IMU_PX4 # define CONFIG_IMU_TYPE CONFIG_IMU_PX4
# define CONFIG_BARO AP_BARO_PX4 # define CONFIG_BARO AP_BARO_PX4
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define OPTFLOW DISABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE #elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
# define CONFIG_IMU_TYPE CONFIG_IMU_FLYMAPLE # define CONFIG_IMU_TYPE CONFIG_IMU_FLYMAPLE
# define CONFIG_BARO AP_BARO_BMP085 # define CONFIG_BARO AP_BARO_BMP085
@ -83,7 +83,6 @@
# define CONFIG_ADC DISABLED # define CONFIG_ADC DISABLED
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define OPTFLOW DISABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
# define CONFIG_IMU_TYPE CONFIG_IMU_L3G4200D # define CONFIG_IMU_TYPE CONFIG_IMU_L3G4200D
# define CONFIG_BARO AP_BARO_BMP085 # define CONFIG_BARO AP_BARO_BMP085
@ -91,13 +90,11 @@
# define CONFIG_ADC DISABLED # define CONFIG_ADC DISABLED
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define OPTFLOW DISABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define CONFIG_IMU_TYPE CONFIG_IMU_VRBRAIN # define CONFIG_IMU_TYPE CONFIG_IMU_VRBRAIN
# define CONFIG_BARO AP_BARO_VRBRAIN # define CONFIG_BARO AP_BARO_VRBRAIN
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN # define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define OPTFLOW DISABLED
#endif #endif
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL #if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
@ -144,13 +141,6 @@
# define RATE_YAW_I 0.015f # define RATE_YAW_I 0.015f
#endif #endif
// optical flow doesn't work in SITL yet
#ifdef DESKTOP_BUILD
# define OPTFLOW DISABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// IMU Selection // IMU Selection
// //
@ -413,7 +403,7 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Parachute release // Parachute release
#ifndef PARACHUTE #ifndef PARACHUTE
# define PARACHUTE DISABLED # define PARACHUTE ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
@ -753,7 +743,7 @@
#endif #endif
#ifndef AC_RALLY #ifndef AC_RALLY
#define AC_RALLY DISABLED #define AC_RALLY ENABLED
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////