mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 16:03:58 -04:00
AP_InertialNav: fixed example builds
This commit is contained in:
parent
84cda98bec
commit
d5e129457e
@ -9,7 +9,7 @@
|
||||
#include <AP_Buffer.h> // FIFO buffer library
|
||||
#include <AP_GPS_Glitch.h> // GPS Glitch detection library
|
||||
#include <AP_Baro_Glitch.h> // Baro Glitch detection library
|
||||
#include <AP_Nav_Common.h> // 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
|
||||
|
@ -31,12 +31,15 @@
|
||||
#include <AP_Terrain.h>
|
||||
#include <AP_Notify.h>
|
||||
#include <AP_InertialNav.h>
|
||||
#include <AP_NavEKF.h>
|
||||
#include <AP_Nav_Common.h>
|
||||
#include <AP_BattMonitor.h> // battery monitor library
|
||||
#include <AP_SerialManager.h> // 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);
|
||||
|
Loading…
Reference in New Issue
Block a user