Browse Source

Copter: Report MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL and MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL as healthy if the flight mode says so.

Brings it up to the Sub and Plane status
zr-v5.1
Dr.-Ing. Amilcar do Carmo Lucas 5 years ago committed by Randy Mackay
parent
commit
d1eb03df30
  1. 3
      ArduCopter/GCS_Copter.cpp

3
ArduCopter/GCS_Copter.cpp

@ -86,7 +86,9 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) @@ -86,7 +86,9 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
case Mode::Number::THROW:
case Mode::Number::SMART_RTL:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break;
case Mode::Number::ALT_HOLD:
case Mode::Number::GUIDED_NOGPS:
@ -94,6 +96,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) @@ -94,6 +96,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
case Mode::Number::AUTOTUNE:
case Mode::Number::FLOWHOLD:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
break;
default:
// stabilize, acro, drift, and flip have no automatic x,y or z control (i.e. all manual)

Loading…
Cancel
Save