mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Plane: check for safety switch state in quadplane motor output
get_soft_armed() will be false if safety on
This commit is contained in:
parent
e17c8ac851
commit
c81d8364ac
@ -1078,7 +1078,7 @@ void QuadPlane::check_throttle_suppression(void)
|
||||
*/
|
||||
void QuadPlane::motors_output(void)
|
||||
{
|
||||
if (plane.afs.should_crash_vehicle()) {
|
||||
if (!hal.util->get_soft_armed() || plane.afs.should_crash_vehicle()) {
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||
motors->output();
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user