AP_AHRS: fixed example build

This commit is contained in:
Andrew Tridgell 2014-11-28 10:40:52 +11:00
parent e45522f51d
commit 89cdae62b4

View File

@ -29,32 +29,34 @@
#include <AP_Notify.h> #include <AP_Notify.h>
#include <AP_Vehicle.h> #include <AP_Vehicle.h>
#include <DataFlash.h> #include <DataFlash.h>
#include <AP_NavEKF.h>
#include <AP_Rally.h>
#include <AP_Scheduler.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h> #include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
#include <AP_HAL_PX4.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// INS and Baro declaration // INS and Baro declaration
AP_InertialSensor ins; AP_InertialSensor ins;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 #if CONFIG_HAL_BOARD == HAL_BOARD_APM2
AP_Baro_MS5611 baro(&AP_Baro_MS5611::spi); AP_Baro_MS5611 baro(&AP_Baro_MS5611::spi);
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 adc; AP_ADC_ADS7844 adc;
AP_Baro_BMP085 baro;
#else
AP_InertialSensor ins;
#endif #endif
AP_Compass_HMC5843 compass; AP_Compass_HMC5843 compass;
AP_GPS gps; AP_GPS gps;
AP_Baro_HIL baro;
// choose which AHRS system to use // choose which AHRS system to use
AP_AHRS_DCM ahrs(ins, baro, gps); AP_AHRS_DCM ahrs(ins, baro, gps);
AP_Baro_HIL barometer;
#define HIGH 1 #define HIGH 1