ArduCopter: Mark motors un-healthy if any motors are not producing thrust

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2020-10-09 13:33:21 +02:00 committed by Peter Barker
parent b04dfda9fb
commit 2261f94361
1 changed files with 8 additions and 0 deletions

View File

@ -150,4 +150,12 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
break;
}
#endif
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROPULSION;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROPULSION;
// only mark propulsion healthy if all of the motors are producing
// nominal thrust
if (!copter.motors->get_thrust_boost()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROPULSION;
}
}