mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Copter: slow start motors after landing in Stabilize, Acro
This commit is contained in:
parent
0bf1d04172
commit
4eb6f0f646
@ -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()
|
|||||||
// 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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user