mirror of https://github.com/ArduPilot/ardupilot
Plane: do not set desired vel/accel on takeoff
This effectively bypasses the input shaping. Currently this creates a step change in the position controller.
This commit is contained in:
parent
c3b6127b1b
commit
d5bd30bce0
|
@ -3099,8 +3099,6 @@ void QuadPlane::takeoff_controller(void)
|
||||||
if (no_navigation) {
|
if (no_navigation) {
|
||||||
pos_control->relax_velocity_controller_xy();
|
pos_control->relax_velocity_controller_xy();
|
||||||
} else {
|
} else {
|
||||||
pos_control->set_accel_desired_xy_cmss(zero);
|
|
||||||
pos_control->set_vel_desired_xy_cms(vel);
|
|
||||||
pos_control->input_vel_accel_xy(vel, zero);
|
pos_control->input_vel_accel_xy(vel, zero);
|
||||||
|
|
||||||
// nav roll and pitch are controller by position controller
|
// nav roll and pitch are controller by position controller
|
||||||
|
|
Loading…
Reference in New Issue