Browse Source

Plane: cleanup driver declaration

remove a lot of the #if nesting
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
4d9a74d742
  1. 123
      ArduPlane/ArduPlane.pde
  2. 19
      ArduPlane/config.h
  3. 13
      ArduPlane/defines.h

123
ArduPlane/ArduPlane.pde

@ -136,95 +136,88 @@ static GPS *g_gps;
// flight modes convenience array // flight modes convenience array
static AP_Int8 *flight_modes = &g.flight_mode1; static AP_Int8 *flight_modes = &g.flight_mode1;
#if HIL_MODE == HIL_MODE_DISABLED #if CONFIG_ADC == ENABLED
// real sensors
#if CONFIG_ADC == ENABLED
static AP_ADC_ADS7844 adc; static AP_ADC_ADS7844 adc;
#endif #endif
# if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass;
AP_InertialSensor_Stub ins;
SITL sitl;
#else
#if CONFIG_BARO == AP_BARO_BMP085 #if CONFIG_BARO == AP_BARO_BMP085
static AP_Baro_BMP085 barometer; static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == AP_BARO_PX4 #elif CONFIG_BARO == AP_BARO_PX4
static AP_Baro_PX4 barometer; static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == AP_BARO_MS5611 #elif CONFIG_BARO == AP_BARO_HIL
#if CONFIG_MS5611_SERIAL == AP_BARO_MS5611_SPI static AP_Baro_BMP085_HIL barometer;
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi); #elif CONFIG_BARO == AP_BARO_MS5611
#elif CONFIG_MS5611_SERIAL == AP_BARO_MS5611_I2C #if CONFIG_MS5611_SERIAL == AP_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c); static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else #elif CONFIG_MS5611_SERIAL == AP_BARO_MS5611_I2C
#error Unrecognized CONFIG_MS5611_SERIAL setting. static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#endif #else
#endif #error Unrecognized CONFIG_MS5611_SERIAL setting.
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static AP_Compass_PX4 compass;
#else #else
#error Unrecognized CONFIG_BARO setting
#endif
#if CONFIG_COMPASS == AP_COMPASS_PX4
static AP_Compass_PX4 compass;
#elif CONFIG_COMPASS == AP_COMPASS_HMC5843
static AP_Compass_HMC5843 compass; static AP_Compass_HMC5843 compass;
#elif CONFIG_COMPASS == AP_COMPASS_HIL
static AP_Compass_HIL compass;
#else
#error Unrecognized CONFIG_COMPASS setting
#endif #endif
#endif
// real GPS selection // GPS selection
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO #if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
AP_GPS_Auto g_gps_driver(&g_gps); AP_GPS_Auto g_gps_driver(&g_gps);
#elif GPS_PROTOCOL == GPS_PROTOCOL_NMEA #elif GPS_PROTOCOL == GPS_PROTOCOL_NMEA
AP_GPS_NMEA g_gps_driver(); AP_GPS_NMEA g_gps_driver;
#elif GPS_PROTOCOL == GPS_PROTOCOL_SIRF #elif GPS_PROTOCOL == GPS_PROTOCOL_SIRF
AP_GPS_SIRF g_gps_driver(); AP_GPS_SIRF g_gps_driver;
#elif GPS_PROTOCOL == GPS_PROTOCOL_UBLOX #elif GPS_PROTOCOL == GPS_PROTOCOL_UBLOX
AP_GPS_UBLOX g_gps_driver(); AP_GPS_UBLOX g_gps_driver;
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK #elif GPS_PROTOCOL == GPS_PROTOCOL_MTK
AP_GPS_MTK g_gps_driver(); AP_GPS_MTK g_gps_driver;
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK19 #elif GPS_PROTOCOL == GPS_PROTOCOL_MTK19
AP_GPS_MTK19 g_gps_driver(); AP_GPS_MTK19 g_gps_driver;
#elif GPS_PROTOCOL == GPS_PROTOCOL_NONE #elif GPS_PROTOCOL == GPS_PROTOCOL_NONE
AP_GPS_None g_gps_driver(); AP_GPS_None g_gps_driver;
#else #elif GPS_PROTOCOL == GPS_PROTOCOL_HIL
AP_GPS_HIL g_gps_driver;
#else
#error Unrecognised GPS_PROTOCOL setting. #error Unrecognised GPS_PROTOCOL setting.
#endif // GPS PROTOCOL #endif // GPS PROTOCOL
# if CONFIG_INS_TYPE == CONFIG_INS_MPU6000 #if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
AP_InertialSensor_MPU6000 ins; AP_InertialSensor_MPU6000 ins;
# elif CONFIG_INS_TYPE == CONFIG_INS_PX4 #elif CONFIG_INS_TYPE == CONFIG_INS_PX4
AP_InertialSensor_PX4 ins; AP_InertialSensor_PX4 ins;
# elif CONFIG_HAL_BOARD != HAL_BOARD_AVR_SITL #elif CONFIG_INS_TYPE == CONFIG_INS_STUB
AP_InertialSensor_Stub ins;
#elif CONFIG_INS_TYPE == CONFIG_INS_OILPAN
AP_InertialSensor_Oilpan ins( &adc ); AP_InertialSensor_Oilpan ins( &adc );
#endif // CONFIG_INS_TYPE #else
#error Unrecognised CONFIG_INS_TYPE setting.
#endif // CONFIG_INS_TYPE
#if HIL_MODE == HIL_MODE_ATTITUDE
AP_AHRS_HIL ahrs(&ins, g_gps);
#else
AP_AHRS_DCM ahrs(&ins, g_gps); AP_AHRS_DCM ahrs(&ins, g_gps);
#endif
#elif HIL_MODE == HIL_MODE_SENSORS #if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
// sensor emulators SITL sitl;
AP_Baro_BMP085_HIL barometer; #endif
AP_Compass_HIL compass;
AP_GPS_HIL g_gps_driver;
AP_InertialSensor_Stub ins;
AP_AHRS_DCM ahrs(&ins, g_gps);
#elif HIL_MODE == HIL_MODE_ATTITUDE
AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass;
AP_GPS_HIL g_gps_driver;
AP_InertialSensor_Stub ins;
AP_AHRS_HIL ahrs(&ins, g_gps);
#else
#error Unrecognised HIL_MODE setting.
#endif // HIL MODE
// Training mode // Training mode
static bool training_manual_roll; // user has manual roll control static bool training_manual_roll; // user has manual roll control

19
ArduPlane/config.h

@ -101,6 +101,7 @@
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ADC # define CONFIG_PITOT_SOURCE PITOT_SOURCE_ADC
# define CONFIG_PITOT_SOURCE_ADC_CHANNEL 7 # define CONFIG_PITOT_SOURCE_ADC_CHANNEL 7
# define CONFIG_BARO AP_BARO_BMP085 # define CONFIG_BARO AP_BARO_BMP085
# define CONFIG_COMPASS AP_COMPASS_HMC5843
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
# define A_LED_PIN 27 # define A_LED_PIN 27
# define B_LED_PIN 26 # define B_LED_PIN 26
@ -126,6 +127,7 @@
# define CONFIG_BARO AP_BARO_MS5611 # define CONFIG_BARO AP_BARO_MS5611
# define CONFIG_MS5611_SERIAL AP_BARO_MS5611_SPI # define CONFIG_MS5611_SERIAL AP_BARO_MS5611_SPI
# endif # endif
# define CONFIG_COMPASS AP_COMPASS_HMC5843
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL #elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
# define A_LED_PIN 27 # define A_LED_PIN 27
# define B_LED_PIN 26 # define B_LED_PIN 26
@ -139,6 +141,8 @@
# define CONFIG_PITOT_SOURCE_ANALOG_PIN 0 # define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
# define CONFIG_PITOT_SCALING 4.0 # define CONFIG_PITOT_SCALING 4.0
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define CONFIG_BARO AP_BARO_HIL
# define CONFIG_COMPASS AP_COMPASS_HIL
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
# define A_LED_PIN 27 # define A_LED_PIN 27
# define B_LED_PIN 26 # define B_LED_PIN 26
@ -154,6 +158,7 @@
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define MAG_ORIENTATION ROTATION_NONE # define MAG_ORIENTATION ROTATION_NONE
# define CONFIG_BARO AP_BARO_PX4 # define CONFIG_BARO AP_BARO_PX4
# define CONFIG_COMPASS AP_COMPASS_PX4
# define SERIAL0_BAUD 57600 # define SERIAL0_BAUD 57600
#endif #endif
@ -173,6 +178,10 @@
# error "CONFIG_BARO not set" # error "CONFIG_BARO not set"
#endif #endif
#ifndef CONFIG_COMPASS
# error "CONFIG_COMPASS not set"
#endif
#ifndef CONFIG_PITOT_SOURCE #ifndef CONFIG_PITOT_SOURCE
# error "CONFIG_PITOT_SOURCE not set" # error "CONFIG_PITOT_SOURCE not set"
#endif #endif
@ -185,14 +194,20 @@
#endif #endif
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode #if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
# undef GPS_PROTOCOL #undef GPS_PROTOCOL
# define GPS_PROTOCOL GPS_PROTOCOL_NONE #define GPS_PROTOCOL GPS_PROTOCOL_HIL
#undef CONFIG_BARO
#define CONFIG_BARO AP_BARO_HIL
#undef CONFIG_INS_TYPE
#define CONFIG_INS_TYPE CONFIG_INS_STUB
#undef CONFIG_ADC #undef CONFIG_ADC
#define CONFIG_ADC DISABLED #define CONFIG_ADC DISABLED
#undef CONFIG_PITOT_SOURCE #undef CONFIG_PITOT_SOURCE
#define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN #define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
#undef CONFIG_PITOT_SOURCE_ANALOG_PIN #undef CONFIG_PITOT_SOURCE_ANALOG_PIN
#define CONFIG_PITOT_SOURCE_ANALOG_PIN -1 #define CONFIG_PITOT_SOURCE_ANALOG_PIN -1
#undef CONFIG_PITOT_SCALING
#define CONFIG_PITOT_SCALING 4.0
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////

13
ArduPlane/defines.h

@ -224,13 +224,22 @@ enum log_messages {
// mark a function as not to be inlined // mark a function as not to be inlined
#define NOINLINE __attribute__((noinline)) #define NOINLINE __attribute__((noinline))
#define CONFIG_INS_OILPAN 1 // InertialSensor driver types
#define CONFIG_INS_OILPAN 1
#define CONFIG_INS_MPU6000 2 #define CONFIG_INS_MPU6000 2
#define CONFIG_INS_STUB 3 #define CONFIG_INS_STUB 3
#define CONFIG_INS_PX4 4
// barometer driver types
#define AP_BARO_BMP085 1 #define AP_BARO_BMP085 1
#define AP_BARO_MS5611 2 #define AP_BARO_MS5611 2
#define AP_BARO_PX4 3 #define AP_BARO_PX4 3
#define AP_BARO_HIL 4
// compass driver types
#define AP_COMPASS_HMC5843 1
#define AP_COMPASS_PX4 2
#define AP_COMPASS_HIL 3
// altitude control algorithms // altitude control algorithms
enum { enum {

Loading…
Cancel
Save