Only released in EOL distros:
Package Summary
Controller for a steer drive mobile base.
- Maintainer status: maintained
- Maintainer: Masaru Morita <p595201m AT mail.kyutech DOT jp>
- Author: CIR-KIT <cirkit.infomation AT gmail DOT com>, Masaru Morita <p595201m AT mail.kyutech DOT jp>
- License: BSD
- Bug / feature tracker: https://github.com/CIR-KIT/steer_drive_ros/issues
- Source: git https://github.com/CIR-KIT/steer_drive_ros.git (branch: indigo-devel)
Contents
An example of using the packages can be seen in Robots/CIR-KIT-Unit03.
Overview
Controller for wheel systems with 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 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 steer 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 steer_drive_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
Realtime-safe implementation.
- Odometry publishing
- Task-space velocity, acceleration and jerk limits
- Automatic stop after command time-out
Robots
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)- Velocity command.
Published Topics
odom (nav_msgs/Odometry)- Odometry computed from the hardware feedback.
- Transform from odom to base_footprint
Joint Parameters
rear_wheel (string)
- Rear wheel joint name
- Front steer joint name
Coveriance Parameters
pose_covariance_diagonal (double[6])
- Diagonal of the covariance matrix for odometry pose publishing
- Diagonal of the covariance matrix for odometry twist publishing
Time Related Parameters
publish_rate (double, default: 50.0)
- Frequency (in Hz) at which the odometry is published. Used for both tf and odom
- Allowed period (in s) allowed between two successive velocity commands. After this delay, a zero speed command will be sent to the wheels.
TF Related Parameters
base_frame_id (string, default: base_link)
- Base frame_id, which is used to fill in the child_frame_id of the Odometry messages and TF.
- Odometry frame_id
- Publish to TF directly or not
Multiplier Parameters
wheel_separation_h_multiplier (double, default: 1.0)
- Multiplier applied to the wheel separation parameter. This is used to account for a difference between the robot model and a real robot (e.g. odometry tuning).
- Multiplier applied to the wheel radius parameter. This is used to account for a difference between the robot model and a real robot (e.g. odometry tuning).
- Steer position angle multipliers for fine tuning.
Limmiter Parameters
linear/x/has_velocity_limits (bool, default: false)
- Whether the controller should limit linear speed or not.
- Maximum linear velocity (in m/s)
- Minimum linear velocity (in m/s). Setting this to 0.0 will disable backwards motion. When unspecified, -max_velocity is used.
- Whether the controller should limit linear acceleration or not.
- Maximum linear acceleration (in m/s^2)
- Minimum linear acceleration (in m/s^2). When unspecified, -max_acceleration is used.
- Whether the controller should limit linear jerk or not.
- Maximum linear jerk (in m/s^3).
- Whether the controller should limit angular velocity or not.
- Maximum angular velocity (in rad/s)
- Minimum angular velocity (in rad/s). Setting this to 0.0 will disable counter-clockwise rotation. When unspecified, -max_velocity is used.
- Whether the controller should limit angular acceleration or not.
- Maximum angular acceleration (in rad/s^2)
- Minimum angular acceleration (in rad/s^2). When unspecified, -max_acceleration is used.
- Whether the controller should limit angular jerk or not.
- Maximum angular jerk (in m/s^3).
Calibration Parameters
wheel_separation_h (double)
- The distance of the rear wheel and the front wheel. The diff_drive_controller will attempt to read the value from the URDF if this parameter is not specified.
- Radius of the wheels. It is expected they all have the same size. The diff_drive_controller will attempt to read the value from the URDF if this parameter is not specified.
Controller configuration examples
Minimal description
mobile_base_controller: type: "steer_drive_controller/SteerDriveController" 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 : "diff_drive_controller/DiffDriveController" 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. # steer_drive_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 steer_drive_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 steer mechanism base robots in stepback_and_steerturn_recovery. Feel free to see Robots/CIR-KIT-Unit03 to learn how to use it.