mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_PosControl: set-alt-target-with-slew sets desired to 0 once at target
This resolves and issue with the set-alt-target-with-slew method leaving the z-axis desired velocity at the max speed-up or speed-down this causes a jump in throttle if the user switches to Loiter after the vehicle has reached its target
This commit is contained in:
parent
b252eae404
commit
ba3303dc61
@ -286,6 +286,9 @@ void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
|
|||||||
_pos_target.z += climb_rate_cms*dt;
|
_pos_target.z += climb_rate_cms*dt;
|
||||||
_vel_desired.z = climb_rate_cms; // recorded for reporting purposes
|
_vel_desired.z = climb_rate_cms; // recorded for reporting purposes
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
// recorded for reporting purposes
|
||||||
|
_vel_desired.z = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// do not let target get too far from current altitude
|
// do not let target get too far from current altitude
|
||||||
|
Loading…
Reference in New Issue
Block a user