Wiki

  Show EOL distros: 

ros_controllers: diff_drive_controller | effort_controllers | force_torque_sensor_controller | forward_command_controller | gripper_action_controller | imu_sensor_controller | joint_state_controller | joint_trajectory_controller | position_controllers | velocity_controllers

Package Summary

Controller for a differential drive mobile base.

ros_controllers: diff_drive_controller | effort_controllers | force_torque_sensor_controller | forward_command_controller | gripper_action_controller | imu_sensor_controller | joint_state_controller | joint_trajectory_controller | position_controllers | rqt_joint_trajectory_controller | velocity_controllers

Package Summary

Controller for a differential drive mobile base.

ros_controllers: ackermann_steering_controller | diff_drive_controller | effort_controllers | force_torque_sensor_controller | forward_command_controller | gripper_action_controller | imu_sensor_controller | joint_state_controller | joint_trajectory_controller | position_controllers | rqt_joint_trajectory_controller | velocity_controllers

Package Summary

Controller for a differential drive mobile base.

Overview

Controller for differential drive wheel systems. Control is in the form of a velocity command, that is split then sent on the two wheels of a differential drive wheel base. Odometry is computed from the feedback from the hardware, and published.

Velocity commands

The controller works with a velocity twist from which it extracts the x component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.

Hardware interface type

The controller works with wheel joints through a velocity interface.

Other features

Mathematical Background

https://upload.wikimedia.org/wikipedia/commons/2/28/Differential_Drive_Kinematics_of_a_Wheeled_Mobile_Robot.svg

The illustration on the right shows a sketch of a differential drive wheeled robot. In this sketch, the following notation applies.

Using the kinematic model (see here), the diff_drive_controller calculates the left https://latex.codecogs.com/svg.image?\omega_{L} and right angular velocity https://latex.codecogs.com/svg.image?\omega_{R} to:

https://latex.codecogs.com/svg.image?\omega_{L}&space;=&space;\frac{V-\omega&space;\cdot&space;b/2}{r}

and

https://latex.codecogs.com/svg.image?\omega_{R}&space;=&space;&space;&space;\frac{V+\omega&space;\cdot&space;b/2}{r}.

Robots

REEM

PAL Robotics REEM

PMB2

PAL Robotics Mobile Base

Husky

Clearpath Robotics Husky

Robots/Jackal

Clearpath Robotics Jackal

i-Cart mini

i-Cart mini

Remo

ros-mobile-robots/diffbot

ROS API

Description

The controller main input is a geometry_msgs::Twist topic in the namespace of the controller.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)

Published Topics

odom (nav_msgs/Odometry) /tf (tf/tfMessage) publish_cmd (geometry_msgs/TwistStamped)

Parameters

left_wheel (string | string[...]) right_wheel (string | string[...]) pose_covariance_diagonal (double[6]) twist_covariance_diagonal (double[6]) publish_rate (double, default: 50.0) wheel_separation_multiplier (double, default: 1.0) wheel_radius_multiplier (double, default: 1.0) cmd_vel_timeout (double, default: 0.5) base_frame_id (string, default: base_link) linear/x/has_velocity_limits (bool, default: false) linear/x/max_velocity (double) linear/x/min_velocity (double) linear/x/has_acceleration_limits (bool, default: false) linear/x/max_acceleration (double) linear/x/min_acceleration (double) linear/x/has_jerk_limits (bool, default: false) linear/x/max_jerk (double) angular/z/has_velocity_limits (bool, default: false) angular/z/max_velocity (double) angular/z/min_velocity (double) angular/z/has_acceleration_limits (bool, default: false) angular/z/max_acceleration (double) angular/z/min_acceleration (double) angular/z/has_jerk_limits (bool, default: false) angular/z/max_jerk (double) enable_odom_tf (bool, default: true) wheel_separation (double) wheel_radius (double) odom_frame_id (string, default: "/odom") publish_cmd (bool, default: False) allow_multiple_cmd_vel_publishers (bool, default: False) velocity_rolling_window_size (int, default: 10)

Controller configuration examples

Minimal description

mobile_base_controller:
  type: "diff_drive_controller/DiffDriveController"
  left_wheel: 'wheel_left_joint'
  right_wheel: 'wheel_right_joint'
  pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
  twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]

Complete description

mobile_base_controller:
  type        : "diff_drive_controller/DiffDriveController"
  left_wheel  : 'wheel_left_joint'
  right_wheel : 'wheel_right_joint'
  publish_rate: 50.0               # default: 50
  pose_covariance_diagonal : [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
  twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]

  # Wheel separation and diameter. These are both optional.
  # diff_drive_controller will attempt to read either one or both from the
  # URDF if not specified as a parameter
  wheel_separation : 1.0
  wheel_radius : 0.3

  # Wheel separation and radius multipliers
  wheel_separation_multiplier: 1.0 # default: 1.0
  wheel_radius_multiplier    : 1.0 # default: 1.0

  # Velocity commands timeout [s], default 0.5
  cmd_vel_timeout: 0.25

  # Base frame_id
  base_frame_id: base_footprint #default: base_link

  # Velocity and acceleration limits
  # Whenever a min_* is unspecified, default to -max_*
  linear:
    x:
      has_velocity_limits    : true
      max_velocity           : 1.0  # m/s
      min_velocity           : -0.5 # m/s
      has_acceleration_limits: true
      max_acceleration       : 0.8  # m/s^2
      min_acceleration       : -0.4 # m/s^2
      has_jerk_limits        : true
      max_jerk               : 5.0  # m/s^3
  angular:
    z:
      has_velocity_limits    : true
      max_velocity           : 1.7  # rad/s
      has_acceleration_limits: true
      max_acceleration       : 1.5  # rad/s^2
      has_jerk_limits        : true
      max_jerk               : 2.5  # rad/s^3

Skid steer

The diff_drive_controller allows for skid steer driving with the geometry_msgs/Twist command interface however it doesn't support direct skid commands.

The current implementation allows you to register multiple wheels per side and will average those wheel positions in its odometry calculations. For more info read the code and issue.

Multiple wheels per side example from Jackal.

jackal_velocity_controller:
  type: "diff_drive_controller/DiffDriveController"
  left_wheel: ['front_left_wheel', 'rear_left_wheel']
  right_wheel: ['front_right_wheel', 'rear_right_wheel']
  publish_rate: 50
  pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
  twist_covariance_diagonal: [0.001, 0.001, 0.001, 1000000.0, 1000000.0, 0.03]
  cmd_vel_timeout: 0.25

  # Odometry fused with IMU is published by robot_localization, so
  # no need to publish a TF based on encoders alone.
  enable_odom_tf: false

  # Wheel separation and radius multipliers
  wheel_separation_multiplier: 1.5 # default: 1.0
  wheel_radius_multiplier    : 1.0 # default: 1.0

  # Velocity and acceleration limits
  # Whenever a min_* is unspecified, default to -max_*
  linear:
    x:
      has_velocity_limits    : true
      max_velocity           : 2.0   # m/s
      has_acceleration_limits: true
      max_acceleration       : 20.0   # m/s^2
  angular:
    z:
      has_velocity_limits    : true
      max_velocity           : 4.0   # rad/s
      has_acceleration_limits: true
      max_acceleration       : 25.0   # rad/s^2

Further reading

In addition to the robots addressed in chapter 2, tutorials for the application of the diff_drive_controller should be briefly mentioned.

A basic understanding of the implementation of ros_control and its interaction with the hardware_interface is explained in this post.

An overview of the diff_drive_controller and its integration into ros_control can be found in the DiffBot Base Package tutorial.

A detailed description of the specific execution and application of the diff_drive_controller can also be found in the DiffBot Base Package.

In the Jackal Robot, the diff_drive_controller is also applied, and the control commands (https://latex.codecogs.com/svg.image?\omega_{L} and https://latex.codecogs.com/svg.image?\omega_{R}) are being retrieved in the hardware_interface and forwarded to the corresponding drives.

Wiki: diff_drive_controller (last edited 2023-04-13 10:10:40 by Dr.No)