mirror of https://github.com/ArduPilot/ardupilot
Plane: stop updating sensor status flags
These are updated as required in the gcs library itself.
This commit is contained in:
parent
b9a387ed9e
commit
2768d229ed
|
@ -291,12 +291,6 @@ void Plane::one_second_loop()
|
||||||
// reset the landing altitude correction
|
// reset the landing altitude correction
|
||||||
landing.alt_offset = 0;
|
landing.alt_offset = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// update error mask of sensors and subsystems. The mask uses the
|
|
||||||
// MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
|
|
||||||
// indicates that the sensor or subsystem is present but not
|
|
||||||
// functioning correctly
|
|
||||||
gcs().update_sensor_status_flags();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::compass_save()
|
void Plane::compass_save()
|
||||||
|
|
Loading…
Reference in New Issue