Browse Source

Copter: slow start motors after landing in Stabilize, Acro

master
Randy Mackay 10 years ago
parent
commit
4eb6f0f646
  1. 4
      ArduCopter/control_acro.cpp
  2. 4
      ArduCopter/control_stabilize.cpp

4
ArduCopter/control_acro.cpp

@ -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.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;
}

4
ArduCopter/control_stabilize.cpp

@ -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(!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;
}

Loading…
Cancel
Save