|
|
|
@ -11,6 +11,7 @@
@@ -11,6 +11,7 @@
|
|
|
|
|
#include <AP_HAL_AVR.h> |
|
|
|
|
|
|
|
|
|
#include <AP_GPS.h> // ArduPilot GPS library |
|
|
|
|
#include <AP_GPS_Glitch.h> // GPS glitch protection library |
|
|
|
|
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library |
|
|
|
|
#include <AP_ADC_AnalogSource.h> |
|
|
|
|
#include <AP_Baro.h> // ArduPilot Mega Barometer Library |
|
|
|
@ -48,12 +49,13 @@ AP_Baro_BMP085 baro;
@@ -48,12 +49,13 @@ AP_Baro_BMP085 baro;
|
|
|
|
|
// GPS declaration |
|
|
|
|
GPS *gps; |
|
|
|
|
AP_GPS_Auto auto_gps(&gps); |
|
|
|
|
GPS_Glitch gps_glitch(gps); |
|
|
|
|
|
|
|
|
|
AP_Compass_HMC5843 compass; |
|
|
|
|
AP_AHRS_DCM ahrs(&ins, gps); |
|
|
|
|
|
|
|
|
|
// Inertial Nav declaration |
|
|
|
|
AP_InertialNav inertial_nav(&ahrs, &ins, &baro, &gps); |
|
|
|
|
AP_InertialNav inertial_nav(&ahrs, &ins, &baro, gps, gps_glitch); |
|
|
|
|
|
|
|
|
|
// Fence |
|
|
|
|
AC_Fence fence(&inertial_nav); |
|
|
|
|