You're reading the documentation for a development version. For the latest released version, please have a look at Iron.
tricycle_controller
Controller for mobile robots with a single double-actuated wheel, including traction and steering. An example is a tricycle robot with the actuated wheel in the front and two trailing wheels on the rear axle.
Input for control are robot base_link twist commands which are translated to traction and steering commands for the tricycle drive base. Odometry is computed from hardware feedback and published.
For an introduction to mobile robot kinematics and the nomenclature used here, see Wheeled Mobile Robot Kinematics.
Other features
Realtime-safe implementation. Odometry publishing Velocity, acceleration and jerk limits Automatic stop after command timeout
ROS 2 Interfaces
Subscribers
- ~/cmd_vel [geometry_msgs/msg/TwistStamped]
Velocity command for the controller. The controller extracts the x component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.
Parameters
This controller uses the generate_parameter_library to handle its parameters.
- traction_joint_name (string)
Name of the traction joint
Default: “”
Constraints:
parameter is not empty
- steering_joint_name (string)
Name of the steering joint
Default: “”
Constraints:
parameter is not empty
- wheelbase (double)
Shortest distance between the front wheel and the rear axle. If this parameter is wrong, the robot will not behave correctly in curves.
Default: 0.0
Constraints:
greater than 0.0
- wheel_radius (double)
Radius of a wheel, i.e., wheels size, used for transformation of linear velocity into wheel rotations. If this parameter is wrong the robot will move faster or slower then expected.
Default: 0.0
Constraints:
greater than 0.0
- odom_frame_id (string)
Name of the frame for odometry. This frame is parent of
base_frame_id
when controller publishes odometry.Default: “odom”
- base_frame_id (string)
Name of the robot’s base frame that is child of the odometry frame.
Default: “base_link”
- pose_covariance_diagonal (double_array)
Odometry covariance for the encoder output of the robot for the pose. These values should be tuned to your robot’s sample odometry data, but these values are a good place to start:
[0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
.Default: {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}
- twist_covariance_diagonal (double_array)
Odometry covariance for the encoder output of the robot for the speed. These values should be tuned to your robot’s sample odometry data, but these values are a good place to start:
[0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
.Default: {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}
- open_loop (bool)
If set to true the odometry of the robot will be calculated from the commanded values and not from feedback.
Default: false
- enable_odom_tf (bool)
Publish transformation between
odom_frame_id
andbase_frame_id
.Default: false
- odom_only_twist (bool)
for doing the pose integration in separate node.
Default: false
- cmd_vel_timeout (int)
Timeout in milliseconds, after which input command on
cmd_vel
topic is considered staled.Default: 500
- publish_ackermann_command (bool)
Publish limited commands.
Default: false
- velocity_rolling_window_size (int)
Size of the rolling window for calculation of mean velocity use in odometry.
Default: 10
Constraints:
greater than 0
- traction.max_velocity (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.min_velocity (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.max_acceleration (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.min_acceleration (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.max_deceleration (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.min_deceleration (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.max_jerk (double)
Default: std::numeric_limits<double>::quiet_NaN()
- traction.min_jerk (double)
Default: std::numeric_limits<double>::quiet_NaN()
- steering.max_position (double)
Default: std::numeric_limits<double>::quiet_NaN()
- steering.min_position (double)
Default: std::numeric_limits<double>::quiet_NaN()
- steering.max_velocity (double)
Default: std::numeric_limits<double>::quiet_NaN()
- steering.min_velocity (double)
Default: std::numeric_limits<double>::quiet_NaN()
- steering.max_acceleration (double)
Default: std::numeric_limits<double>::quiet_NaN()
- steering.min_acceleration (double)
Default: std::numeric_limits<double>::quiet_NaN()