|
|
|
@ -535,7 +535,8 @@ void ModeGuided::pos_control_run()
@@ -535,7 +535,8 @@ void ModeGuided::pos_control_run()
|
|
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
|
|
|
|
if (is_disarmed_or_landed()) { |
|
|
|
|
make_safe_spool_down(); |
|
|
|
|
// do not spool down tradheli when on the ground with motor interlock enabled
|
|
|
|
|
make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -593,7 +594,8 @@ void ModeGuided::accel_control_run()
@@ -593,7 +594,8 @@ void ModeGuided::accel_control_run()
|
|
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
|
|
|
|
if (is_disarmed_or_landed()) { |
|
|
|
|
make_safe_spool_down(); |
|
|
|
|
// do not spool down tradheli when on the ground with motor interlock enabled
|
|
|
|
|
make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -656,7 +658,8 @@ void ModeGuided::velaccel_control_run()
@@ -656,7 +658,8 @@ void ModeGuided::velaccel_control_run()
|
|
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
|
|
|
|
if (is_disarmed_or_landed()) { |
|
|
|
|
make_safe_spool_down(); |
|
|
|
|
// do not spool down tradheli when on the ground with motor interlock enabled
|
|
|
|
|
make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -731,7 +734,8 @@ void ModeGuided::posvelaccel_control_run()
@@ -731,7 +734,8 @@ void ModeGuided::posvelaccel_control_run()
|
|
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
|
|
|
|
if (is_disarmed_or_landed()) { |
|
|
|
|
make_safe_spool_down(); |
|
|
|
|
// do not spool down tradheli when on the ground with motor interlock enabled
|
|
|
|
|
make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -845,7 +849,8 @@ void ModeGuided::angle_control_run()
@@ -845,7 +849,8 @@ void ModeGuided::angle_control_run()
|
|
|
|
|
|
|
|
|
|
// if not armed set throttle to zero and exit immediately
|
|
|
|
|
if (!motors->armed() || !copter.ap.auto_armed || (copter.ap.land_complete && !positive_thrust_or_climbrate)) { |
|
|
|
|
make_safe_spool_down(); |
|
|
|
|
// do not spool down tradheli when on the ground with motor interlock enabled
|
|
|
|
|
make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|