Copter: fixed vertical speed init for ALT_HOLD mode
This commit is contained in:
parent
d92e7a99a2
commit
39df609235
@ -9,6 +9,10 @@ static bool althold_init(bool ignore_checks)
|
||||
{
|
||||
// initialise altitude target to stopping point
|
||||
pos_control.set_target_to_stopping_point_z();
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user