From 7d58916a9daea025b0f4ddc1fbd5838ae14a23d9 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Wed, 10 Aug 2011 12:47:25 +0000 Subject: [PATCH] compass: add a small delay in compass init this adds a 50ms delay after setting the compass gains before reading the compass. Added as paranoia after some strange results on a 5843 git-svn-id: https://arducopter.googlecode.com/svn/trunk@3070 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 04bded5228..f978b07585 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -138,6 +138,7 @@ AP_Compass_HMC5843::init() calibration[2] = 1.0; // read values from the compass + delay(50); read(); if (last_update == update_stamp) continue; // we didn't read valid values