mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: move setting of GPS SYS_STATUS bits up to base class
This commit is contained in:
parent
da184ffdaf
commit
d63788a09f
@ -34,11 +34,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
|||||||
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||||
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||||
|
|
||||||
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()) {
|
||||||
@ -113,9 +108,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (gps.is_healthy()) {
|
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
||||||
}
|
|
||||||
if (ap.rc_receiver_present && !copter.failsafe.radio) {
|
if (ap.rc_receiver_present && !copter.failsafe.radio) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user