mirror of https://github.com/ArduPilot/ardupilot
ArduSub: tidy setting of sensor status flags
This commit is contained in:
parent
6a32afcd72
commit
cb7ac6fb54
|
@ -9,6 +9,7 @@ uint8_t GCS_Sub::sysid_this_mav() const
|
|||
|
||||
void GCS_Sub::update_vehicle_sensor_status_flags()
|
||||
{
|
||||
// mode-specific sensors:
|
||||
control_sensors_present |=
|
||||
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
|
||||
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||
|
@ -24,19 +25,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
|||
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
|
||||
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
|
||||
|
||||
// first what sensors/controllers we have
|
||||
if (sub.ap.depth_sensor_present) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
}
|
||||
#if OPTFLOW == ENABLED
|
||||
const OpticalFlow *optflow = AP::opticalflow();
|
||||
if (optflow && optflow->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
}
|
||||
#endif
|
||||
|
||||
control_sensors_present |=
|
||||
MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL |
|
||||
MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
|
||||
|
@ -57,11 +45,23 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
|||
break;
|
||||
}
|
||||
|
||||
// override the parent class's values for ABSOLUTE_PRESSURE to
|
||||
// only check internal barometer:
|
||||
if (sub.ap.depth_sensor_present) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
}
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; // check the internal barometer only
|
||||
if (sub.sensor_health.depth) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||
}
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
const OpticalFlow *optflow = AP::opticalflow();
|
||||
if (optflow && optflow->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
}
|
||||
if (optflow && optflow->healthy()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue