Copter: let GCS base class handle fence sys_status bits

This commit is contained in:
Peter Barker 2019-08-29 19:26:24 +10:00 committed by Andrew Tridgell
parent 9da0efaaef
commit ab7b4616ff
1 changed files with 0 additions and 16 deletions

View File

@ -70,11 +70,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
}
#endif
#if AC_FENCE == ENABLED
if (copter.fence.sys_status_present()) {
control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
}
#endif
#if RANGEFINDER_ENABLED == ENABLED
const RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
@ -112,11 +107,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
break;
}
#if AC_FENCE == ENABLED
if (copter.fence.sys_status_enabled()) {
control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
}
#endif
#if PROXIMITY_ENABLED == ENABLED
if (copter.g2.proximity.sensor_enabled()) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
@ -176,10 +166,4 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
}
#endif
#if AC_FENCE == ENABLED
if (!copter.fence.sys_status_failed()) {
control_sensors_health |= MAV_SYS_STATUS_GEOFENCE;
}
#endif
}