Skip to content
Snippets Groups Projects
Commit 4eb6f0f6 authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter: slow start motors after landing in Stabilize, Acro

parent 0bf1d041
No related branches found
No related tags found
No related merge requests found
...@@ -23,6 +23,10 @@ void Copter::acro_run() ...@@ -23,6 +23,10 @@ void Copter::acro_run()
// if motors not running reset angle targets // if motors not running reset angle targets
if(!motors.armed() || ap.throttle_zero) { if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
// slow start if landed
if (ap.land_complete) {
motors.slow_start(true);
}
return; return;
} }
......
...@@ -28,6 +28,10 @@ void Copter::stabilize_run() ...@@ -28,6 +28,10 @@ void Copter::stabilize_run()
// if not armed or throttle at zero, set throttle to zero and exit immediately // if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || ap.throttle_zero) { if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
// slow start if landed
if (ap.land_complete) {
motors.slow_start(true);
}
return; return;
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment