Copter: use sensors from board subtypes

This commit is contained in:
Andrew Tridgell 2014-07-07 12:05:28 +10:00
parent ae29a24348
commit 49954a3a61
4 changed files with 85 additions and 124 deletions

View File

@ -215,15 +215,8 @@ static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
static DataFlash_APM2 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
static DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
static DataFlash_File DataFlash("logs");
//static DataFlash_SITL DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
static DataFlash_File DataFlash("logs");
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
#elif defined(HAL_BOARD_LOG_DIRECTORY)
static DataFlash_File DataFlash(HAL_BOARD_LOG_DIRECTORY);
#else
static DataFlash_Empty DataFlash;
#endif
@ -258,77 +251,57 @@ static GPS_Glitch gps_glitch(gps);
// flight modes convenience array
static AP_Int8 *flight_modes = &g.flight_mode1;
#if HIL_MODE == HIL_MODE_DISABLED
#if CONFIG_ADC == ENABLED
static AP_ADC_ADS7844 adc;
#endif
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
static AP_InertialSensor_MPU6000 ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_MPU9250
static AP_InertialSensor_MPU9250 ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
static AP_InertialSensor_Oilpan ins(&adc);
#elif CONFIG_IMU_TYPE == CONFIG_IMU_SITL
static AP_InertialSensor_HIL ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_PX4
static AP_InertialSensor_PX4 ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_VRBRAIN
static AP_InertialSensor_VRBRAIN ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_FLYMAPLE
AP_InertialSensor_Flymaple ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_L3G4200D
AP_InertialSensor_L3G4200D ins;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
// When building for SITL we use the HIL barometer and compass drivers
static AP_Baro_HIL barometer;
static AP_Compass_HIL compass;
static SITL sitl;
#else
// Otherwise, instantiate a real barometer and compass driver
#if CONFIG_BARO == AP_BARO_BMP085
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == AP_BARO_PX4
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == AP_BARO_VRBRAIN
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == AP_BARO_MS5611
#if CONFIG_MS5611_SERIAL == AP_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#elif CONFIG_MS5611_SERIAL == AP_BARO_MS5611_I2C
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#else
#error Unrecognized CONFIG_MS5611_SERIAL setting.
#endif
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static AP_Compass_PX4 compass;
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
static AP_Compass_VRBRAIN compass;
#else
static AP_Compass_HMC5843 compass;
#endif
#endif
#elif HIL_MODE != HIL_MODE_DISABLED
// sensor emulators
static AP_ADC_HIL adc;
static AP_Baro_HIL barometer;
static AP_Compass_HIL compass;
static AP_InertialSensor_HIL ins;
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
// When building for SITL we use the HIL barometer and compass drivers
static SITL sitl;
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
#elif CONFIG_COMPASS == HAL_COMPASS_VRBRAIN
static AP_Compass_VRBRAIN compass;
#elif CONFIG_COMPASS == HAL_COMPASS_HMC5843
static AP_Compass_HMC5843 compass;
#elif CONFIG_COMPASS == HAL_COMPASS_HIL
static AP_Compass_HIL compass;
#else
#error Unrecognised HIL_MODE setting.
#endif // HIL MODE
#error Unrecognized CONFIG_COMPASS setting
#endif
#if CONFIG_INS_TYPE == HAL_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc;
#endif
#if CONFIG_INS_TYPE == HAL_INS_MPU6000
AP_InertialSensor_MPU6000 ins;
#elif CONFIG_INS_TYPE == HAL_INS_PX4
AP_InertialSensor_PX4 ins;
#elif CONFIG_INS_TYPE == HAL_INS_VRBRAIN
AP_InertialSensor_VRBRAIN ins;
#elif CONFIG_INS_TYPE == HAL_INS_HIL
AP_InertialSensor_HIL ins;
#elif CONFIG_INS_TYPE == HAL_INS_OILPAN
AP_InertialSensor_Oilpan ins( &apm1_adc );
#elif CONFIG_INS_TYPE == HAL_INS_FLYMAPLE
AP_InertialSensor_Flymaple ins;
#elif CONFIG_INS_TYPE == HAL_INS_L3G4200D
AP_InertialSensor_L3G4200D ins;
#elif CONFIG_INS_TYPE == HAL_INS_MPU9250
AP_InertialSensor_MPU9250 ins;
#else
#error Unrecognised CONFIG_INS_TYPE setting.
#endif // CONFIG_INS_TYPE
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
@ -337,6 +310,10 @@ AP_AHRS_NavEKF ahrs(ins, barometer, gps);
AP_AHRS_DCM ahrs(ins, barometer, gps);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
SITL sitl;
#endif
// Mission library
// forward declaration to keep compiler happy
static bool start_command(const AP_Mission::Mission_Command& cmd);

View File

@ -53,48 +53,50 @@
#endif
//////////////////////////////////////////////////////////////////////////////
// FLIGHT CONTROLLER HARDWARE DEFAULT SETTINGS
//
// sensor types
#define CONFIG_INS_TYPE HAL_INS_DEFAULT
#define CONFIG_BARO HAL_BARO_DEFAULT
#define CONFIG_COMPASS HAL_COMPASS_DEFAULT
#ifdef HAL_SERIAL0_BAUD_DEFAULT
# define SERIAL0_BAUD HAL_SERIAL0_BAUD_DEFAULT
#endif
//////////////////////////////////////////////////////////////////////////////
// HIL_MODE OPTIONAL
#ifndef HIL_MODE
#define HIL_MODE HIL_MODE_DISABLED
#endif
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
#undef CONFIG_BARO
#define CONFIG_BARO HAL_BARO_HIL
#undef CONFIG_INS_TYPE
#define CONFIG_INS_TYPE HAL_INS_HIL
#undef CONFIG_COMPASS
#define CONFIG_COMPASS HAL_COMPASS_HIL
#endif
#define MAGNETOMETER ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
# define PARACHUTE DISABLED
# define AC_RALLY DISABLED
# ifdef APM2_BETA_HARDWARE
# define CONFIG_BARO AP_BARO_BMP085
# else // APM2 Production Hardware (default)
# define CONFIG_BARO AP_BARO_MS5611
# define CONFIG_MS5611_SERIAL AP_BARO_MS5611_SPI
# endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
# define CONFIG_IMU_TYPE CONFIG_IMU_SITL
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
# define CONFIG_IMU_TYPE CONFIG_IMU_PX4
# define CONFIG_BARO AP_BARO_PX4
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
# define CONFIG_IMU_TYPE CONFIG_IMU_FLYMAPLE
# define CONFIG_BARO AP_BARO_BMP085
# define CONFIG_COMPASS AP_COMPASS_HMC5843
# define CONFIG_ADC DISABLED
# define MAGNETOMETER ENABLED
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
# define CONFIG_IMU_TYPE CONFIG_IMU_L3G4200D
# define CONFIG_BARO AP_BARO_BMP085
# define CONFIG_COMPASS AP_COMPASS_HMC5843
# define CONFIG_ADC DISABLED
# define MAGNETOMETER ENABLED
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define CONFIG_IMU_TYPE CONFIG_IMU_VRBRAIN
# define CONFIG_BARO AP_BARO_VRBRAIN
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#endif
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
@ -102,6 +104,11 @@
# define MAIN_LOOP_RATE 100
# define MAIN_LOOP_SECONDS 0.01
# define MAIN_LOOP_MICROS 10000
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
// Linux boards
# define MAIN_LOOP_RATE 200
# define MAIN_LOOP_SECONDS 0.005
# define MAIN_LOOP_MICROS 5000
#else
// high power CPUs (Flymaple, PX4, Pixhawk, VRBrain)
# define MAIN_LOOP_RATE 400
@ -141,18 +148,11 @@
# define RATE_YAW_I 0.015f
#endif
//////////////////////////////////////////////////////////////////////////////
// IMU Selection
//
#ifndef CONFIG_IMU_TYPE
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
#endif
//////////////////////////////////////////////////////////////////////////////
// ADC Enable - used to eliminate for systems which don't have ADC.
//
#ifndef CONFIG_ADC
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
# if CONFIG_INS_TYPE == HAL_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
# define CONFIG_ADC ENABLED
# else
# define CONFIG_ADC DISABLED

View File

@ -334,22 +334,6 @@ enum FlipState {
// mark a function as not to be inlined
#define NOINLINE __attribute__((noinline))
// IMU selection
#define CONFIG_IMU_OILPAN 1
#define CONFIG_IMU_MPU6000 2
#define CONFIG_IMU_SITL 3
#define CONFIG_IMU_PX4 4
#define CONFIG_IMU_FLYMAPLE 5
#define CONFIG_IMU_VRBRAIN 6
#define AP_BARO_BMP085 1
#define AP_BARO_MS5611 2
#define AP_BARO_PX4 3
#define AP_BARO_VRBRAIN 4
#define AP_BARO_MS5611_SPI 1
#define AP_BARO_MS5611_I2C 2
// Error message sub systems and error codes
#define ERROR_SUBSYSTEM_MAIN 1
#define ERROR_SUBSYSTEM_RADIO 2

View File

@ -205,7 +205,7 @@ static void init_ardupilot()
#if CONFIG_ADC == ENABLED
// begin filtering the ADC Gyros
adc.Init(); // APM ADC library initialization
apm1_adc.Init(); // APM ADC library initialization
#endif // CONFIG_ADC
// Do GPS init