mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: move setting of GPS SYS_STATUS bits up to base class
This commit is contained in:
parent
3547e74991
commit
526adee814
@ -24,11 +24,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
|||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
}
|
}
|
||||||
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 OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
const OpticalFlow *optflow = AP::opticalflow();
|
const OpticalFlow *optflow = AP::opticalflow();
|
||||||
if (optflow && optflow->enabled()) {
|
if (optflow && optflow->enabled()) {
|
||||||
@ -61,9 +56,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
|||||||
if (sub.sensor_health.depth) {
|
if (sub.sensor_health.depth) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
}
|
}
|
||||||
if (gps.is_healthy()) {
|
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
||||||
}
|
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
if (optflow && optflow->healthy()) {
|
if (optflow && optflow->healthy()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||||
|
Loading…
Reference in New Issue
Block a user