mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Tracker: move setting of GPS SYS_STATUS bits up to base class
This commit is contained in:
parent
49f26f08e1
commit
da184ffdaf
@ -51,17 +51,6 @@ void GCS_Tracker::update_vehicle_sensor_status_flags()
|
|||||||
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
||||||
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||||
|
|
||||||
// first what sensors/controllers we have
|
|
||||||
const AP_GPS &gps = AP::gps();
|
|
||||||
if (gps.status() > AP_GPS::NO_GPS) {
|
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (gps.is_healthy()) {
|
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// avoid building/linking LTM:
|
// avoid building/linking LTM:
|
||||||
|
Loading…
Reference in New Issue
Block a user