diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.cpp b/src/modules/mc_pos_control/MulticopterPositionControl.cpp index b2f88d4c65..abc389f082 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.cpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.cpp @@ -506,7 +506,6 @@ void MulticopterPositionControl::Run() // Allow ramping from zero thrust on takeoff const float minimum_thrust = flying ? _param_mpc_thr_min.get() : 0.f; - _control.setThrustLimits(minimum_thrust, _param_mpc_thr_max.get()); float max_speed_xy = _param_mpc_xy_vel_max.get(); diff --git a/src/modules/mc_pos_control/PositionControl/PositionControl.cpp b/src/modules/mc_pos_control/PositionControl/PositionControl.cpp index 10aa105d06..8e58fa66d1 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControl.cpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControl.cpp @@ -81,10 +81,11 @@ void PositionControl::updateHoverThrust(const float hover_thrust_new) // T' = T => a_sp' * Th' / g - Th' = a_sp * Th / g - Th // so a_sp' = (a_sp - g) * Th / Th' + g // we can then add a_sp' - a_sp to the current integrator to absorb the effect of changing Th by Th' - if (hover_thrust_new > FLT_EPSILON) { - _vel_int(2) += (_acc_sp(2) - CONSTANTS_ONE_G) * _hover_thrust / hover_thrust_new + CONSTANTS_ONE_G - _acc_sp(2); - setHoverThrust(hover_thrust_new); - } + const float previous_hover_thrust = _hover_thrust; + setHoverThrust(hover_thrust_new); + + _vel_int(2) += (_acc_sp(2) - CONSTANTS_ONE_G) * previous_hover_thrust / _hover_thrust + + CONSTANTS_ONE_G - _acc_sp(2); } void PositionControl::setState(const PositionControlStates &states) @@ -138,6 +139,9 @@ void PositionControl::_positionControl() void PositionControl::_velocityControl(const float dt) { + // Constrain vertical velocity integral + _vel_int(2) = math::constrain(_vel_int(2), -CONSTANTS_ONE_G, CONSTANTS_ONE_G); + // PID velocity control Vector3f vel_error = _vel_sp - _vel; Vector3f acc_sp_velocity = vel_error.emult(_gain_vel_p) + _vel_int - _vel_dot.emult(_gain_vel_d); @@ -195,9 +199,6 @@ void PositionControl::_velocityControl(const float dt) ControlMath::setZeroIfNanVector3f(vel_error); // Update integral part of velocity control _vel_int += vel_error.emult(_gain_vel_i) * dt; - - // limit thrust integral - _vel_int(2) = math::min(fabsf(_vel_int(2)), CONSTANTS_ONE_G) * sign(_vel_int(2)); } void PositionControl::_accelerationControl() diff --git a/src/modules/mc_pos_control/PositionControl/PositionControl.hpp b/src/modules/mc_pos_control/PositionControl/PositionControl.hpp index 124fd08b03..4eb909e1fa 100644 --- a/src/modules/mc_pos_control/PositionControl/PositionControl.hpp +++ b/src/modules/mc_pos_control/PositionControl/PositionControl.hpp @@ -122,9 +122,9 @@ public: /** * Set the normalized hover thrust - * @param thrust [0.1, 0.9] with which the vehicle hovers not acelerating down or up with level orientation + * @param hover_thrust [HOVER_THRUST_MIN, HOVER_THRUST_MAX] with which the vehicle hovers not accelerating down or up with level orientation */ - void setHoverThrust(const float hover_thrust) { _hover_thrust = math::constrain(hover_thrust, 0.1f, 0.9f); } + void setHoverThrust(const float hover_thrust) { _hover_thrust = math::constrain(hover_thrust, HOVER_THRUST_MIN, HOVER_THRUST_MAX); } /** * Update the hover thrust without immediately affecting the output @@ -185,6 +185,10 @@ public: static const trajectory_setpoint_s empty_trajectory_setpoint; private: + // The range limits of the hover thrust configuration/estimate + static constexpr float HOVER_THRUST_MIN = 0.05f; + static constexpr float HOVER_THRUST_MAX = 0.9f; + bool _inputValid(); void _positionControl(); ///< Position proportional control @@ -206,7 +210,7 @@ private: float _lim_thr_xy_margin{}; ///< Margin to keep for horizontal control when saturating prioritized vertical thrust float _lim_tilt{}; ///< Maximum tilt from level the output attitude is allowed to have - float _hover_thrust{}; ///< Thrust [0.1, 0.9] with which the vehicle hovers not accelerating down or up with level orientation + float _hover_thrust{}; ///< Thrust [HOVER_THRUST_MIN, HOVER_THRUST_MAX] with which the vehicle hovers not accelerating down or up with level orientation // States matrix::Vector3f _pos; /**< current position */