Skip to content

Commit c7dabf6

Browse files
committed
AC_AttitudeControl: AC_PosControl: change force_descend to ignore_descent_limit
1 parent 62f653c commit c7dabf6

File tree

2 files changed

+8
-4
lines changed

2 files changed

+8
-4
lines changed

libraries/AC_AttitudeControl/AC_PosControl.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -755,12 +755,13 @@ void AC_PosControl::init_z()
755755
/// The kinematic path is constrained by the maximum acceleration and time constant set using the function set_max_speed_accel_z and time constant.
756756
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
757757
/// The time constant also defines the time taken to achieve the maximum acceleration.
758-
void AC_PosControl::input_vel_accel_z(Vector3f& vel, const Vector3f& accel, bool force_descend)
758+
/// ignore_descent_limit turns off output saturation handling to aid in landing detection. ignore_descent_limit should be true unless landing.
759+
void AC_PosControl::input_vel_accel_z(Vector3f& vel, const Vector3f& accel, bool ignore_descent_limit)
759760
{
760761
// check for ekf z position reset
761762
handle_ekf_z_reset();
762763

763-
if (force_descend) {
764+
if (ignore_descent_limit) {
764765
// turn off limits in the negative z direction
765766
_limit_vector.z = MAX(_limit_vector.z, 0.0f);
766767
}
@@ -788,10 +789,11 @@ void AC_PosControl::input_vel_accel_z(Vector3f& vel, const Vector3f& accel, bool
788789

789790
/// set_pos_target_z_from_climb_rate_cm - adjusts target up or down using a commanded climb rate in cm/s
790791
/// using the default position control kinimatic path.
791-
void AC_PosControl::set_pos_target_z_from_climb_rate_cm(const float vel, bool force_descend)
792+
/// ignore_descent_limit turns off output saturation handling to aid in landing detection. ignore_descent_limit should be true unless landing.
793+
void AC_PosControl::set_pos_target_z_from_climb_rate_cm(const float vel, bool ignore_descent_limit)
792794
{
793795
Vector3f vel_3f = Vector3f{0.0f, 0.0f, vel};
794-
input_vel_accel_z(vel_3f, Vector3f{0.0f, 0.0f, 0.0f}, force_descend);
796+
input_vel_accel_z(vel_3f, Vector3f{0.0f, 0.0f, 0.0f}, ignore_descent_limit);
795797
}
796798

797799
/// input_pos_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.

libraries/AC_AttitudeControl/AC_PosControl.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -167,10 +167,12 @@ class AC_PosControl
167167
/// The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration.
168168
/// The time constant also defines the time taken to achieve the maximum acceleration.
169169
/// The function alters the input velocitiy to be the velocity that the system could reach zero acceleration in the minimum time.
170+
/// ignore_descent_limit turns off output saturation handling to aid in landing detection. ignore_descent_limit should be true unless landing.
170171
virtual void input_vel_accel_z(Vector3f& vel, const Vector3f& accel, bool force_descend);
171172

172173
/// set_pos_target_z_from_climb_rate_cm - adjusts target up or down using a climb rate in cm/s
173174
/// using the default position control kinimatic path.
175+
/// ignore_descent_limit turns off output saturation handling to aid in landing detection. ignore_descent_limit should be true unless landing.
174176
void set_pos_target_z_from_climb_rate_cm(const float vel, bool force_descend);
175177

176178
/// input_pos_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration.

0 commit comments

Comments
 (0)