From 6193d6cf697ac2cf9c0791a2e82286b9d5a07d09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 13 Sep 2019 09:14:42 +1000 Subject: [PATCH] AP_Compass: fix example by instantiating Baro Baro is required to get location, and Compass tries to get the declination based on current location --- .../AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp index 9c2c435b54..7571e086c8 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include 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;