mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
APM: ArduPlane updates for new compass interface
This commit is contained in:
parent
e4d28b12e5
commit
3a2594fa1a
@ -793,9 +793,6 @@ static void medium_loop()
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if (g.compass_enabled && compass.read()) {
|
||||
ahrs.set_compass(&compass);
|
||||
// Calculate heading
|
||||
Matrix3f m = ahrs.get_dcm_matrix();
|
||||
compass.calculate(m);
|
||||
compass.null_offsets();
|
||||
} else {
|
||||
ahrs.set_compass(NULL);
|
||||
|
@ -173,7 +173,6 @@ static void init_ardupilot()
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
ahrs.set_compass(&compass);
|
||||
compass.null_offsets_enable();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -533,10 +533,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||
if(g.compass_enabled) {
|
||||
medium_loopCounter++;
|
||||
if(medium_loopCounter == 5){
|
||||
if (compass.read()) {
|
||||
// Calculate heading
|
||||
compass.calculate(ahrs.get_dcm_matrix());
|
||||
}
|
||||
compass.read();
|
||||
medium_loopCounter = 0;
|
||||
}
|
||||
}
|
||||
@ -573,7 +570,6 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
Serial.println_P(PSTR("Compass initialisation failed!"));
|
||||
return 0;
|
||||
}
|
||||
compass.null_offsets_enable();
|
||||
ahrs.set_compass(&compass);
|
||||
report_compass();
|
||||
|
||||
@ -582,6 +578,8 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
ahrs.reset();
|
||||
|
||||
int counter = 0;
|
||||
float heading = 0;
|
||||
|
||||
//Serial.printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION);
|
||||
|
||||
print_hit_enter();
|
||||
@ -602,7 +600,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
if (compass.read()) {
|
||||
// Calculate heading
|
||||
Matrix3f m = ahrs.get_dcm_matrix();
|
||||
compass.calculate(m);
|
||||
heading = compass.calculate_heading(m);
|
||||
compass.null_offsets();
|
||||
}
|
||||
medium_loopCounter = 0;
|
||||
@ -613,7 +611,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
if (compass.healthy) {
|
||||
Vector3f maggy = compass.get_offsets();
|
||||
Serial.printf_P(PSTR("Heading: %ld, XYZ: %d, %d, %d,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
||||
(wrap_360(ToDeg(compass.heading) * 100)) /100,
|
||||
(wrap_360(ToDeg(heading) * 100)) /100,
|
||||
(int)compass.mag_x,
|
||||
(int)compass.mag_y,
|
||||
(int)compass.mag_z,
|
||||
|
Loading…
Reference in New Issue
Block a user