Copter: slow start motors after landing in Stabilize, Acro

This commit is contained in:
Randy Mackay 2015-07-27 16:37:37 +09:00
parent 77b97f8643
commit ef6b173326
2 changed files with 8 additions and 0 deletions

View File

@ -23,6 +23,10 @@ void Copter::acro_run()
// if motors not running reset angle targets
if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
// slow start if landed
if (ap.land_complete) {
motors.slow_start(true);
}
return;
}

View File

@ -28,6 +28,10 @@ void Copter::stabilize_run()
// if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
// slow start if landed
if (ap.land_complete) {
motors.slow_start(true);
}
return;
}