Browse Source

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
mission-4.1.18
tridge60@gmail.com 14 years ago
parent
commit
90b0d769f8
  1. 4
      libraries/AP_Compass/AP_Compass_HMC5843.cpp

4
libraries/AP_Compass/AP_Compass_HMC5843.cpp

@ -120,7 +120,11 @@ AP_Compass_HMC5843::init() @@ -120,7 +120,11 @@ AP_Compass_HMC5843::init()
// leave test mode
Wire.beginTransmission(COMPASS_ADDRESS);
Wire.send(ConfigRegA);
if (product_id == AP_COMPASS_TYPE_HMC5843) {
Wire.send(NormalOperation);
} else {
Wire.send(SampleAveraging_8<<5 | DataOutputRate_75HZ<<2 | NormalOperation);
}
Wire.endTransmission();
delay(50);

Loading…
Cancel
Save