You're reading the documentation for an older, but still supported, version of ROS 2. For information on the latest version, please have a look at Jazzy.
steering_controllers_library
Library with shared functionalities for mobile robot controllers with steering drives, with so-called non-holonomic constraints.
The library implements generic odometry and update methods and defines the main interfaces.
The update methods only use inverse kinematics, it does not implement any feedback control loops like path-tracking controllers etc.
For an introduction to mobile robot kinematics and the nomenclature used here, see Wheeled Mobile Robot Kinematics.
Execution logic of the controller
The controller uses velocity input, i.e., stamped or unstamped twist messages where linear x
and angular z
components are used.
Values in other components are ignored.
In the chain mode the controller provides two reference interfaces, one for linear velocity and one for steering angle position. Other relevant features are:
support for front and rear steering configurations;
odometry publishing as Odometry and TF message;
input command timeout based on a parameter.
The command for the wheels are calculated using odometry
library where based on concrete kinematics traction and steering commands are calculated.
Currently implemented kinematics
Bicycle - with one steering and one drive joints;
Tricylce - with one steering and two drive joints;
Ackermann - with two steering and two drive joints.
Description of controller’s interfaces
References (from a preceding controller)
Used when controller is in chained mode (in_chained_mode == true
).
<controller_name>/linear/velocity
double, in m/s<controller_name>/angular/velocity
double, in rad/s
representing the body twist.
Command interfaces
If parameter front_steering == true
<front_wheels_names[i]>/position
double, in rad<rear_wheels_names[i]>/velocity
double, in m/s
If parameter front_steering == false
<front_wheels_names[i]>/velocity
double, in m/s<rear_wheels_names[i]>/position
double, in rad
State interfaces
Depending on the position_feedback
, different feedback types are expected
position_feedback == true
–>TRACTION_FEEDBACK_TYPE = position
position_feedback == false
–>TRACTION_FEEDBACK_TYPE = velocity
If parameter front_steering == true
<front_wheels_names[i]>/position
double, in rad<rear_wheels_names[i]>/<TRACTION_FEEDBACK_TYPE>
double, in m or m/s
If parameter front_steering == false
<front_wheels_names[i]>/<TRACTION_FEEDBACK_TYPE>
double, in m or m/s<rear_wheels_names[i]>/position
double, in rad
Subscribers
Used when controller is not in chained mode (in_chained_mode == false
).
<controller_name>/reference
[geometry_msgs/msg/TwistStamped] If parameteruse_stamped_vel
istrue
.<controller_name>/reference_unstamped
[geometry_msgs/msg/Twist] If parameteruse_stamped_vel
isfalse
.
Publishers
<controller_name>/odometry
[nav_msgs/msg/Odometry]<controller_name>/tf_odometry
[tf2_msgs/msg/TFMessage]<controller_name>/controller_state
[control_msgs/msg/SteeringControllerStatus]
Parameters
This controller uses the generate_parameter_library to handle its parameters.
For an exemplary parameterization see the test
folder of the controller’s package.
- reference_timeout (double)
Timeout for controller references after which they will be reset. This is especially useful for controllers that can cause unwanted and dangerous behaviour if reference is not reset, e.g., velocity controllers. If value is 0 the reference is reset after each run.
Default: 1.0
- front_steering (bool)
Is the steering on the front of the robot?
Read only: True
Default: true
- rear_wheels_names (string_array)
Names of rear wheel joints.
Read only: True
Constraints:
length is less than 5
contains no duplicates
parameter is not empty
- front_wheels_names (string_array)
Names of front wheel joints.
Read only: True
Constraints:
length is less than 5
contains no duplicates
parameter is not empty
- rear_wheels_state_names (string_array)
(Optional) Names of rear wheel joints to read states from. If not set joint names from ‘rear_wheels_names’ will be used.
Read only: True
Default: {}
Constraints:
length is less than 5
contains no duplicates
- front_wheels_state_names (string_array)
(Optional) Names of front wheel joints to read states from. If not set joint names from ‘front_wheels_names’ will be used.
Read only: True
Default: {}
Constraints:
length is less than 5
contains no duplicates
- open_loop (bool)
Choose if open-loop or not (feedback) is used for odometry calculation.
Default: false
- velocity_rolling_window_size (int)
The number of velocity samples to average together to compute the odometry twist.linear.x and twist.angular.z velocities.
Default: 10
- base_frame_id (string)
Base frame_id set to value of base_frame_id.
Default: “base_link”
- odom_frame_id (string)
Odometry frame_id set to value of odom_frame_id.
Default: “odom”
- enable_odom_tf (bool)
Publishing to tf is enabled or disabled?
Default: true
- twist_covariance_diagonal (double_array)
diagonal values of twist covariance matrix.
Default: {0.0, 7.0, 14.0, 21.0, 28.0, 35.0}
- pose_covariance_diagonal (double_array)
diagonal values of pose covariance matrix.
Default: {0.0, 7.0, 14.0, 21.0, 28.0, 35.0}
- position_feedback (bool)
Choice of feedback type, if position_feedback is false then
HW_IF_VELOCITY
is taken as interface type, if position_feedback is true thenHW_IF_POSITION
is taken as interface typeDefault: false
- use_stamped_vel (bool)
Choice of vel type, if use_stamped_vel is false then
geometry_msgs::msg::Twist
is taken as vel msg type, if use_stamped_vel is true thengeometry_msgs::msg::TwistStamped
is taken as vel msg typeDefault: false