diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index 1fd3bd40be..dfba6228bf 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -9,7 +9,7 @@ #include // FIFO buffer library #include // GPS Glitch detection library #include // Baro Glitch detection library -#include // definitions shared by inertial and ekf nav filters +#include "../AP_NavEKF/AP_Nav_Common.h" // definitions shared by inertial and ekf nav filters #define AP_INTERTIALNAV_TC_XY 2.5f // default time constant for complementary filter's X & Y axis #define AP_INTERTIALNAV_TC_Z 5.0f // default time constant for complementary filter's Z axis diff --git a/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde b/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde index 15ac6e1904..1b5712f415 100644 --- a/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde +++ b/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde @@ -31,12 +31,15 @@ #include #include #include +#include #include #include // battery monitor library +#include // Serial manager library const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_InertialSensor ins; +static AP_SerialManager serial_manager; #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 AP_ADC_ADS7844 adc; @@ -59,7 +62,8 @@ void setup(void) { hal.console->println_P(PSTR("AP_InertialNav test startup...")); - gps.init(NULL); + serial_manager.init(); + gps.init(NULL, serial_manager); ins.init(AP_InertialSensor::COLD_START, AP_InertialSensor::RATE_100HZ);