Wiki

  Show EOL distros: 

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 steer 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 steer 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 | velocity_controllers

Package Summary

Controller for a steer 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 | velocity_controllers

Package Summary

Controller for a steer drive mobile base.

An example of using the packages can be seen in Robots/CIR-KIT-Unit03.

Overview

Controller for wheel systems with ackermann steering mechanism. Control is in the form of a velocity command, that is split then sent on the single rear wheel and the single front steer of a ackermann steering 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 inherits multi_interface_controller to work with wheel joints through a velocity interface for a linear wheel and a position interface for a front steer wheel, which is the the most basic configuration for the ackermann steering driving mechanism.

Converting controller's interfaces to actual controller's interfaces

If you want rviz to show states of robot's actual joint interfaces' tf through joint_state_controller and robot_state_publisher, you need to convert the two interfaces of ackermann_steering_controller to your robot's specific ones via RobotHW or RobotHWSim (generally used for GAZEBO). This is because the controller only update it's basic interfaces mentioned in the previous section.

Other features

Robots

CIR-KIT-Unit03

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)

Joint Parameters

rear_wheel (string)

front_steer (string)

Coveriance Parameters

pose_covariance_diagonal (double[6])

twist_covariance_diagonal (double[6])

publish_rate (double, default: 50.0)

cmd_vel_timeout (double, default: 0.5)

base_frame_id (string, default: base_link)

odom_frame_id (string, default: odom) enable_odom_tf (bool, default: true)

Multiplier Parameters

wheel_separation_h_multiplier (double, default: 1.0)

wheel_radius_multiplier (double, default: 1.0) steer_pos_multiplier (double, default: 1.0)

Limiter Parameters

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)

Calibration Parameters

wheel_separation_h (double)

wheel_radius (double)

Other Parameters

velocity_rolling_window_size (int, default: 10)

Controller configuration examples

Minimal description

mobile_base_controller:
  type: "ackermann_steering_controller/AckermannSteeringController"
  rear_wheel: 'rear_wheel_joint'
  front_steer: 'front_steer_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        : "ackermann_steering_controller/AckermannSteeringController"
  rear_wheel: 'rear_wheel_joint'
  front_steer: 'front_steer_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 between the rear and the front, and diameter of the rear. 
  # These are both optional.
  # ackermann_steering_controller will attempt to read either one or both from the
  # URDF if not specified as a parameter.
  wheel_separation_h : 1.0
  wheel_radius : 0.3

  # Wheel separation and radius multipliers for odometry calibration.
  wheel_separation_h_multiplier: 1.0 # default: 1.0
  wheel_radius_multiplier    : 1.0 # default: 1.0

  # Steer position angle multipliers for fine tuning.
  steer_pos_multiplier       : 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

  # Odom frame_id
  odom_frame_id: odom

  # 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

RobotHW

An example for usage of ackermann_steering_controller with RobotHW can be grabbed from Robots/CIR-KIT-Unit03.

RobotHWSim for GAZEBO

We developped a general RobotHWSim plugin for usage of GAZEBO. You can get the plugin from steer_bot_hardware_gazebo and also see an example of application on Robots/CIR-KIT-Unit03.

Recovery Behavior

We also provide a recovery behavior plugin of move_base specifically desigined for ackermann steering mechanism base robots in stepback_and_steerturn_recovery. Feel free to see Robots/CIR-KIT-Unit03 to learn how to use it.

Wiki: ackermann_steering_controller (last edited 2021-05-19 01:27:14 by MattReynolds)