Rover: changes for compass API

This commit is contained in:
Andrew Tridgell 2013-12-09 17:46:57 +11:00
parent c538816825
commit 563e5f71ff
2 changed files with 2 additions and 2 deletions

View File

@ -155,7 +155,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
// default to all healthy except compass and gps which we set individually
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS);
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) {

View File

@ -417,7 +417,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"),