InertialNav: fix example sketch

This commit is contained in:
Randy Mackay 2014-07-29 11:51:49 +09:00
parent c9667131dd
commit 2951fb50e9

View File

@ -12,6 +12,7 @@
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
#include <AP_ADC_AnalogSource.h>
#include <AP_Baro.h> // ArduPilot Mega Barometer Library
#include <AP_Baro_Glitch.h> // Baro glitch protection library
#include <Filter.h>
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Declination.h>
@ -28,8 +29,8 @@
#include <AP_Mission.h>
#include <AP_Terrain.h>
#include <AP_Notify.h>
#include <AP_InertialNav.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
@ -46,11 +47,12 @@ AP_Baro_BMP085 baro;
AP_GPS gps;
GPS_Glitch gps_glitch(gps);
Baro_Glitch baro_glitch(baro);
AP_Compass_HMC5843 compass;
AP_AHRS_DCM ahrs(ins, baro, gps);
AP_InertialNav inertialnav(ahrs, baro, gps_glitch);
AP_InertialNav inertialnav(ahrs, baro, gps_glitch, baro_glitch);
uint32_t last_update;