mirror of https://github.com/ArduPilot/ardupilot
Plane: changes for compass healthy API
This commit is contained in:
parent
d265e54043
commit
49f49648ec
|
@ -206,7 +206,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_3D_MAG |
|
||||
MAV_SYS_STATUS_SENSOR_GPS |
|
||||
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE);
|
||||
if (g.compass_enabled && compass.healthy && ahrs.use_compass()) {
|
||||
if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) {
|
||||
|
|
|
@ -522,7 +522,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
counter++;
|
||||
if (counter>20) {
|
||||
if (compass.healthy) {
|
||||
if (compass.healthy()) {
|
||||
const Vector3f &mag_ofs = compass.get_offsets();
|
||||
const Vector3f &mag = compass.get_field();
|
||||
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
||||
|
|
Loading…
Reference in New Issue