From 90b0d769f8c0ec9729b4dcaead8ddb899fad7602 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sun, 3 Jul 2011 12:00:45 +0000 Subject: [PATCH] compass: fixed normal operation mode change for 5883L We need to set the right rates after config too. Thanks to Randy for spotting this one git-svn-id: https://arducopter.googlecode.com/svn/trunk@2737 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 07144631a0..12ae835dfa 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -120,7 +120,11 @@ AP_Compass_HMC5843::init() // leave test mode Wire.beginTransmission(COMPASS_ADDRESS); Wire.send(ConfigRegA); - Wire.send(NormalOperation); + if (product_id == AP_COMPASS_TYPE_HMC5843) { + Wire.send(NormalOperation); + } else { + Wire.send(SampleAveraging_8<<5 | DataOutputRate_75HZ<<2 | NormalOperation); + } Wire.endTransmission(); delay(50);