Browse Source

Rover: move setting of GPS SYS_STATUS bits up to base class

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
49f26f08e1
  1. 8
      APMrover2/GCS_Rover.cpp

8
APMrover2/GCS_Rover.cpp

@ -23,11 +23,6 @@ bool GCS_Rover::supersimple_input_active() const @@ -23,11 +23,6 @@ bool GCS_Rover::supersimple_input_active() const
void GCS_Rover::update_vehicle_sensor_status_flags(void)
{
// 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;
}
const AP_VisualOdom *visual_odom = AP::visualodom();
if (visual_odom && visual_odom->enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
@ -58,9 +53,6 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void) @@ -58,9 +53,6 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void)
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control
}
if (gps.is_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (visual_odom && visual_odom->enabled() && visual_odom->healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
}

Loading…
Cancel
Save