mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: enable motor slow start in auto mode
This commit is contained in:
parent
cc6acac1dd
commit
daa0cb7914
@ -2051,6 +2051,11 @@ void update_throttle_mode(void)
|
||||
case THROTTLE_AUTO:
|
||||
// auto pilot altitude controller with target altitude held in wp_nav.get_desired_alt()
|
||||
if(ap.auto_armed) {
|
||||
// special handling if we are just taking off
|
||||
if (ap.land_complete) {
|
||||
// tell motors to do a slow start.
|
||||
motors.slow_start(true);
|
||||
}
|
||||
get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity());
|
||||
set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint
|
||||
}else{
|
||||
|
Loading…
Reference in New Issue
Block a user