From 864ed1a87fefc1a2919b5da9ce0c66e90f05e0e2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 25 Feb 2012 14:09:12 +1100 Subject: [PATCH] ACM: check the return of compass.init() if the compass fails to initialise then don't pass it to DCM, or we will get no yaw control. Report the init failure to the user. --- ArduCopter/sensors.pde | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 2e1ed8ecd5..c00c0c54fd 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -78,10 +78,14 @@ static int32_t read_barometer(void) static void init_compass() { compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft - dcm.set_compass(&compass); - compass.init(); - compass.get_offsets(); // load offsets to account for airframe magnetic interference - compass.null_offsets_enable(); + if (!compass.init()) { + // make sure we don't pass a broken compass to DCM + Serial.println_P(PSTR("COMPASS INIT ERROR")); + return; + } + dcm.set_compass(&compass); + compass.get_offsets(); // load offsets to account for airframe magnetic interference + compass.null_offsets_enable(); } static void init_optflow()