mirror of https://github.com/ArduPilot/ardupilot
AC_Autotune: Separate landing and terrain following.
This commit is contained in:
parent
d936fbeba6
commit
baf58607fa
|
@ -409,7 +409,7 @@ void AC_AutoTune::run()
|
|||
}
|
||||
|
||||
// call position controller
|
||||
pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cms, false);
|
||||
pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cms);
|
||||
pos_control->update_z_controller();
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue