Copter: integrate slow start feature
This commit is contained in:
parent
36bbed8fdd
commit
072b231c3f
@ -991,6 +991,8 @@ set_throttle_takeoff()
|
|||||||
if (g.pid_throttle_accel.get_integrator() < 0) {
|
if (g.pid_throttle_accel.get_integrator() < 0) {
|
||||||
g.pid_throttle_accel.reset_I();
|
g.pid_throttle_accel.reset_I();
|
||||||
}
|
}
|
||||||
|
// tell motors to do a slow start
|
||||||
|
motors.slow_start(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_throttle_accel - accelerometer based throttle controller
|
// get_throttle_accel - accelerometer based throttle controller
|
||||||
|
Loading…
Reference in New Issue
Block a user