allow MAG_ENABLE to be changed in flight

this disables the compass in DCM if MAG_ENABLE is changed in
flight. Without this we would use a fixed yaw once the compass is
disabled

This also makes sure we don't pass the compass to DCM till we have
done a read. This ensures we have a good compass fix for the initial
DCM heading
This commit is contained in:
Andrew Tridgell 2012-02-25 14:26:54 +11:00
parent eb71b26d3f
commit 0248b48d30
3 changed files with 5 additions and 3 deletions

View File

@ -78,7 +78,7 @@ static int32_t read_barometer(void)
static void init_compass() static void init_compass()
{ {
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
if (!compass.init()) { if (!compass.init() || !compass.read()) {
// make sure we don't pass a broken compass to DCM // make sure we don't pass a broken compass to DCM
Serial.println_P(PSTR("COMPASS INIT ERROR")); Serial.println_P(PSTR("COMPASS INIT ERROR"));
return; return;

View File

@ -769,8 +769,11 @@ static void medium_loop()
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE
if (g.compass_enabled && compass.read()) { if (g.compass_enabled && compass.read()) {
dcm.set_compass(&compass);
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
compass.null_offsets(dcm.get_dcm_matrix()); compass.null_offsets(dcm.get_dcm_matrix());
} else {
dcm.set_compass(NULL);
} }
#endif #endif
/*{ /*{

View File

@ -175,12 +175,11 @@ static void init_ardupilot()
if (g.compass_enabled==true) { if (g.compass_enabled==true) {
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
if (!compass.init()) { if (!compass.init() || !compass.read()) {
Serial.println_P(PSTR("Compass initialisation failed!")); Serial.println_P(PSTR("Compass initialisation failed!"));
g.compass_enabled = false; g.compass_enabled = false;
} else { } else {
dcm.set_compass(&compass); dcm.set_compass(&compass);
compass.get_offsets(); // load offsets to account for airframe magnetic interference
compass.null_offsets_enable(); compass.null_offsets_enable();
} }
} }