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 Kilted.

omni_wheel_drive_controller

Controller for mobile robots with omnidirectional drive.

Supports using three or more omni wheels spaced at an equal angle from each other in a circular formation. To better understand this, have a look at Wheeled Mobile Robot Kinematics.

The controller uses velocity input, i.e., stamped Twist messages where linear x, y, and angular z components are used. Values in other components are ignored.

Odometry is computed from hardware feedback and published.

Other features

  • Realtime-safe implementation.

  • Odometry publishing

  • Automatic stop after command time-out

Description of controller’s interfaces

References (from a preceding controller)

When controller is in chained mode, it exposes the following references which can be commanded by the preceding controller:

  • <controller_name>/linear/x/velocity double, in m/s

  • <controller_name>/linear/y/velocity double, in m/s

  • <controller_name>/angular/z/velocity double, in rad/s

Together, these represent the body twist (which in unchained-mode would be obtained from ~/cmd_vel).

State interfaces

As feedback interface type the joints’ position (hardware_interface::HW_IF_POSITION) or velocity (hardware_interface::HW_IF_VELOCITY, if parameter position_feedback=false) are used.

Command interfaces

Joints’ velocity (hardware_interface::HW_IF_VELOCITY) are used.

ROS 2 Interfaces

Subscribers

~/cmd_vel [geometry_msgs/msg/TwistStamped]

Velocity command for the controller. The controller extracts the x and y component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.

Publishers

~/odom [nav_msgs::msg::Odometry]

This represents an estimate of the robot’s position and velocity in free space.

/tf [tf2_msgs::msg::TFMessage]

tf tree. Published only if enable_odom_tf=true

Parameters

This controller uses the generate_parameter_library to handle its parameters. The parameter definition file located in the src folder contains descriptions for all the parameters used by the controller.

wheel_offset (double)

Angular offset (radians) of the first wheel from the positive direction of the x-axis of the robot.

Read only: True

wheel_names (string_array)

Names of the wheels’ joints, given in an anti-clockwise order starting from the wheel aligned with the positive direction of the x-axis of the robot / offset from it by the value specified in wheel_offset.

Read only: True

Constraints:

  • parameter is not empty

robot_radius (double)

Radius of the robot, distance between the center of the robot and the wheels. If this parameter is wrong, the robot will not behave correctly in curves.

Read only: True

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 than expected.

Read only: True

Constraints:

  • greater than 0.0

tf_frame_prefix_enable (bool)

Enables or disables appending tf_prefix to tf frame id’s.

Read only: True

Default: true

tf_frame_prefix (string)

(optional) Prefix to be appended to the tf frames, will be added to odom_id and base_frame_id before publishing. If the parameter is empty, controller’s namespace will be used.

Read only: True

Default: “”

odom_frame_id (string)

Name of the frame for odometry. This frame is parent of base_frame_id when controller publishes odometry.

Read only: True

Default: “odom”

base_frame_id (string)

Name of the robot’s base frame that is child of the odometry frame.

Read only: True

Default: “base_link”

diagonal_covariance.pose (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].

Read only: True

Default: {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}

diagonal_covariance.twist (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].

Read only: True

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.

Read only: True

Default: false

position_feedback (bool)

Only valid if open_loop is set to false. If there is position feedback from the hardware, set the parameter to true, else set it to false.

Read only: True

Default: true

enable_odom_tf (bool)

Publish transformation between odom_frame_id and base_frame_id.

Read only: True

Default: true

cmd_vel_timeout (double)

Timeout in seconds, after which input command on ~/cmd_vel topic is considered stale.

Read only: True

Default: 0.5

An example parameter file for this controller can be found in the test directory:

test_omni_wheel_drive_controller:
  ros__parameters:
    wheel_offset: 0.0
    wheel_names:
      [
        "front_wheel_joint",
        "left_wheel_joint",
        "back_wheel_joint",
        "right_wheel_joint",
      ]

    robot_radius: 0.20
    wheel_radius: 0.02

    odom_frame_id: odom
    base_frame_id: base_link
    pose_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

    open_loop: true
    position_feedback: false
    enable_odom_tf: true

    cmd_vel_timeout: 0.5
    publish_limited_velocity: true