ros2_control - rolling
Public Member Functions | List of all members
tricycle_controller::TractionLimiter Class Reference

Public Member Functions

 TractionLimiter (double min_velocity=NAN, double max_velocity=NAN, double min_acceleration=NAN, double max_acceleration=NAN, double min_deceleration=NAN, double max_deceleration=NAN, double min_jerk=NAN, double max_jerk=NAN)
 Constructor. More...
 
double limit (double &v, double v0, double v1, double dt)
 Limit the velocity and acceleration. More...
 
double limit_velocity (double &v)
 Limit the velocity. More...
 
double limit_acceleration (double &v, double v0, double dt)
 Limit the acceleration. More...
 
double limit_jerk (double &v, double v0, double v1, double dt)
 Limit the jerk. More...
 

Constructor & Destructor Documentation

◆ TractionLimiter()

tricycle_controller::TractionLimiter::TractionLimiter ( double  min_velocity = NAN,
double  max_velocity = NAN,
double  min_acceleration = NAN,
double  max_acceleration = NAN,
double  min_deceleration = NAN,
double  max_deceleration = NAN,
double  min_jerk = NAN,
double  max_jerk = NAN 
)

Constructor.

Parameters are applied symmetrically for both directions, i.e., are applied to the absolute value of the corresponding quantity.

Warning
  • Setting min_velocity: the robot can't stand still
  • Setting min_deceleration/min_acceleration: the robot can't move with constant velocity
  • Setting min_jerk: the robot can't move with constant acceleration
Parameters
[in]min_velocityMinimum velocity [m/s] or [rad/s]
[in]max_velocityMaximum velocity [m/s] or [rad/s]
[in]min_accelerationMinimum acceleration [m/s^2] or [rad/s^2]
[in]max_accelerationMaximum acceleration [m/s^2] or [rad/s^2]
[in]min_decelerationMinimum deceleration [m/s^2] or [rad/s^2]
[in]max_decelerationMaximum deceleration [m/s^2] or [rad/s^2]
[in]min_jerkMinimum jerk [m/s^3]
[in]max_jerkMaximum jerk [m/s^3]

Member Function Documentation

◆ limit()

double tricycle_controller::TractionLimiter::limit ( double &  v,
double  v0,
double  v1,
double  dt 
)

Limit the velocity and acceleration.

Parameters
[in,out]vVelocity [m/s] or [rad/s]
[in]v0Previous velocity to v [m/s] or [rad/s]
[in]v1Previous velocity to v0 [m/s] or [rad/s]
[in]dtTime step [s]
Returns
Limiting factor (1.0 if none)

◆ limit_acceleration()

double tricycle_controller::TractionLimiter::limit_acceleration ( double &  v,
double  v0,
double  dt 
)

Limit the acceleration.

Parameters
[in,out]vVelocity [m/s] or [rad/s]
[in]v0Previous velocity [m/s] or [rad/s]
[in]dtTime step [s]
Returns
Limiting factor (1.0 if none)

◆ limit_jerk()

double tricycle_controller::TractionLimiter::limit_jerk ( double &  v,
double  v0,
double  v1,
double  dt 
)

Limit the jerk.

Parameters
[in,out]vVelocity [m/s] or [rad/s]
[in]v0Previous velocity to v [m/s] or [rad/s]
[in]v1Previous velocity to v0 [m/s] or [rad/s]
[in]dtTime step [s]
Returns
Limiting factor (1.0 if none)
See also
http://en.wikipedia.org/wiki/Jerk_%28physics%29#Motion_control

◆ limit_velocity()

double tricycle_controller::TractionLimiter::limit_velocity ( double &  v)

Limit the velocity.

Parameters
[in,out]vVelocity [m/s] or [rad/s]
Returns
Limiting factor (1.0 if none)

The documentation for this class was generated from the following files: