|
|
|
@ -8,27 +8,28 @@ uint8_t GCS_Plane::sysid_this_mav() const
@@ -8,27 +8,28 @@ uint8_t GCS_Plane::sysid_this_mav() const
|
|
|
|
|
|
|
|
|
|
void GCS_Plane::update_vehicle_sensor_status_flags(void) |
|
|
|
|
{ |
|
|
|
|
// first what sensors/controllers we have
|
|
|
|
|
// airspeed
|
|
|
|
|
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); |
|
|
|
|
if (airspeed && airspeed->enabled()) { |
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_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 (airspeed && airspeed->enabled() && airspeed->use()) { |
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; |
|
|
|
|
} |
|
|
|
|
if (airspeed && airspeed->all_healthy()) { |
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// reverse thrust
|
|
|
|
|
if (plane.have_reverse_thrust()) { |
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_REVERSE_MOTOR; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (airspeed && airspeed->enabled() && airspeed->use()) { |
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; |
|
|
|
|
if (plane.have_reverse_thrust() && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) < 0) { |
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_REVERSE_MOTOR; |
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_REVERSE_MOTOR; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// flightmode-specific
|
|
|
|
|
control_sensors_present |= |
|
|
|
|
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | |
|
|
|
|
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | |
|
|
|
@ -101,13 +102,15 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
@@ -101,13 +102,15 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#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; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
if (airspeed && airspeed->all_healthy()) { |
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; |
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; |
|
|
|
@ -141,9 +144,4 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
@@ -141,9 +144,4 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (plane.have_reverse_thrust() && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) < 0) { |
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_REVERSE_MOTOR; |
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_REVERSE_MOTOR; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|