From 989304fb47bc833c49e9eb81e5899b5d2f74f95f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:16:41 +1100 Subject: [PATCH] APM: enable the new offset nulling in APM --- ArduPlane/ArduPlane.pde | 2 +- ArduPlane/test.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 676a8720bc..3fa4751119 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -784,7 +784,7 @@ static void medium_loop() // Calculate heading Matrix3f m = ahrs.get_dcm_matrix(); compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); } else { ahrs.set_compass(NULL); } diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index ec988bbdd3..b0e1c27462 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -603,7 +603,7 @@ test_mag(uint8_t argc, const Menu::arg *argv) // Calculate heading Matrix3f m = ahrs.get_dcm_matrix(); compass.calculate(m); - compass.null_offsets(m); + compass.null_offsets(); } medium_loopCounter = 0; }