Browse Source

Sub: always neutralize inputs during pilot input failsafe

mission-4.1.18
Jacob Walser 7 years ago
parent
commit
b7e367e21d
  1. 3
      ArduSub/failsafe.cpp

3
ArduSub/failsafe.cpp

@ -216,8 +216,9 @@ void Sub::failsafe_pilot_input_check() @@ -216,8 +216,9 @@ void Sub::failsafe_pilot_input_check()
Log_Write_Error(ERROR_SUBSYSTEM_INPUT, ERROR_CODE_FAILSAFE_OCCURRED);
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lost manual control");
set_neutral_controls();
if(g.failsafe_pilot_input == FS_PILOT_INPUT_DISARM) {
set_neutral_controls();
init_disarm_motors();
}
#endif

Loading…
Cancel
Save