mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: move setting of compass sys_status bits up
This commit is contained in:
parent
07b8473a20
commit
bba902ab94
@ -4,11 +4,6 @@
|
|||||||
void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
||||||
{
|
{
|
||||||
// first what sensors/controllers we have
|
// first what sensors/controllers we have
|
||||||
if (AP::compass().enabled()) {
|
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
||||||
}
|
|
||||||
|
|
||||||
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
||||||
if (airspeed && airspeed->enabled()) {
|
if (airspeed && airspeed->enabled()) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||||
@ -110,12 +105,6 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
|||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
|
||||||
|
|
||||||
const Compass &compass = AP::compass();
|
|
||||||
if (AP::compass().enabled() && compass.healthy() && ahrs.use_compass()) {
|
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
||||||
}
|
|
||||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.is_healthy()) {
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.is_healthy()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user