mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
ArduCopter: Mark motors un-healthy if any motors are not producing thrust
This commit is contained in:
parent
b04dfda9fb
commit
2261f94361
@ -150,4 +150,12 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
#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;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user