mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
Copter: remove slow_start from takeoff
This commit is contained in:
parent
4514e8d100
commit
3c3b74adc8
@ -126,9 +126,6 @@ void Copter::set_throttle_takeoff()
|
|||||||
{
|
{
|
||||||
// tell position controller to reset alt target and reset I terms
|
// tell position controller to reset alt target and reset I terms
|
||||||
pos_control.init_takeoff();
|
pos_control.init_takeoff();
|
||||||
|
|
||||||
// tell motors to do a slow start
|
|
||||||
motors.slow_start(true);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_pilot_desired_throttle - transform pilot's throttle input to make cruise throttle mid stick
|
// get_pilot_desired_throttle - transform pilot's throttle input to make cruise throttle mid stick
|
||||||
|
Loading…
Reference in New Issue
Block a user