AP_Compass: fix example by instantiating Baro

Baro is required to get location, and Compass tries to get the declination based on current location
This commit is contained in:
Peter Barker 2019-09-13 09:14:42 +10:00 committed by Randy Mackay
parent 23d4473f88
commit 6193d6cf69
1 changed files with 2 additions and 0 deletions

View File

@ -21,6 +21,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
@ -30,6 +31,7 @@ static AP_BoardConfig board_config;
class DummyVehicle {
public:
AP_AHRS_DCM ahrs; // Need since https://github.com/ArduPilot/ardupilot/pull/10890
AP_Baro baro; // Compass tries to set magnetic model based on location.
};
static DummyVehicle vehicle;