@@ -40,7 +40,7 @@ class SpeedLimiter
4040 * \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0
4141 * \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0
4242 */
43- [[deprecated]] SpeedLimiter(
43+ [[deprecated]] explicit SpeedLimiter (
4444 bool has_velocity_limits = true , bool has_acceleration_limits = true ,
4545 bool has_jerk_limits = true , double min_velocity = std::numeric_limits<double >::quiet_NaN(),
4646 double max_velocity = std::numeric_limits<double>::quiet_NaN(),
@@ -79,16 +79,16 @@ class SpeedLimiter
7979 * >= 0
8080 * \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0
8181 * \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0
82+ *
83+ * \note
84+ * If max_* values are NAN, the respective limit is deactivated
85+ * If min_* values are NAN (unspecified), defaults to -max
86+ * If min_first_derivative_pos/max_first_derivative_neg values are NAN, symmetric limits are used
8287 */
83- SpeedLimiter (
84- double min_velocity = std::numeric_limits<double >::quiet_NaN(),
85- double max_velocity = std::numeric_limits<double >::quiet_NaN(),
86- double max_acceleration_reverse = std::numeric_limits<double >::quiet_NaN(),
87- double max_acceleration = std::numeric_limits<double >::quiet_NaN(),
88- double max_deceleration = std::numeric_limits<double >::quiet_NaN(),
89- double max_deceleration_reverse = std::numeric_limits<double >::quiet_NaN(),
90- double min_jerk = std::numeric_limits<double >::quiet_NaN(),
91- double max_jerk = std::numeric_limits<double >::quiet_NaN())
88+ explicit SpeedLimiter (
89+ double min_velocity, double max_velocity, double max_acceleration_reverse,
90+ double max_acceleration, double max_deceleration, double max_deceleration_reverse,
91+ double min_jerk, double max_jerk)
9292 {
9393 speed_limiter_ = control_toolbox::RateLimiter<double >(
9494 min_velocity, max_velocity, max_acceleration_reverse, max_acceleration, max_deceleration,
0 commit comments