mirror of https://github.com/ArduPilot/ardupilot
Sub: relax altitude controller in althold_init()
This commit is contained in:
parent
c6f1b9c458
commit
3228125a19
|
@ -16,7 +16,7 @@ bool Sub::althold_init()
|
|||
// sets the maximum speed up and down returned by position controller
|
||||
pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
||||
pos_control.set_max_accel_z(g.pilot_accel_z);
|
||||
|
||||
pos_control.relax_alt_hold_controllers();
|
||||
pos_control.set_target_to_stopping_point_z();
|
||||
holding_depth = true;
|
||||
|
||||
|
|
Loading…
Reference in New Issue