Only released in EOL distros:  

steer_drive_ros: steer_bot_hardware_gazebo | steer_drive_controller | stepback_and_steerturn_recovery

Package Summary

steer bot hardware for gazebo simulation

  • Maintainer status: maintained
  • Maintainer: Enrique Fernandez <enrique.fernandez.perdomo AT gmail DOT com>
  • Author: Enrique Fernandez <enrique.fernandez.perdomo AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/CIR-KIT/steer_drive_ros.git (branch: indigo-devel)

An example of usage of this plugin can be seen in Robots/CIR-KIT-Unit03, especially in cirkit_unit03_gazebo.

About

This package provides 4-wheel car-like robot model with steer mechanism for Gazebo simulation, by using gazebo_ros_control plugin.

steer_bot_hardware_gazebo::SteerBotHardwareGazebo inherits gazebo_ros_control::RobotHWSim so that the plugin is integrated to Gazebo.

We developed this plugins assuming that steer_drive_controller is selected as the driving controller.

Joint configuration of steer_bot_hardware_gazebo

Review about steer_drive_controller

steer_drive_controller is designed to have two joint interfaces, one is velocity_joint_interface for the single rear wheel joint and the other is position_joint_interface for the single front steer joint. This concept keeps the controller's abstraction to be applied in various types of configuration by converting the joint interfaces in the controller to ones on an actual robot via RobotHW or RobotHWSim.

Converting cmd_vel command to Gazebo joint command

Now we need to do it for a Gazebo model too, which is the main role of this plugin. The following figure shows how a velocity command of geometry_msgs::Twist converted to a joint command to Gazebo via steer_drive_controller.

steerbot_steer_drive_controller_integrate_01

Each type of joint interface on steer_drive_controller is split into two interface for right and left. This is because URDF doesn't support closed links (e.g. parallel link or Ackermann link), which means we need to virtually imitate such links by software.

Registering joint interfaces in URDF model

In order to achieve the conversion mentioned above, you need to register joint interfaces for both steer_drive_controller and Gazebo in steer_bot_hardware_gazebo.

register_joint_interfaces

For steer_drive_controller, it's simple to just register two joint interface for a rear wheel and a front steer as mentioned previously.

For Gazebo, 4 more velocity joint interfaces for wheels and 2 more position joint interface for front steers (in total 2 + 4 + 2 = 8 joint interface are registered in this plugin).

  • The 2 rear wheel velocity joint interfaces are used as command interface for controlling linear drive on Gazebo.

  • The other 2 front wheel joints just grabs current angle to update joint_states, namely tf.

  • The front 2 steer joints virtually behave like parallel link or Ackermann link as you configure in a ROS parameter.

These joint interfaces are mapped with joints shown in the sub section 2.

Registering joint _nterfaces_in_URDF_model

An example of registering such joint interfaces can be seen in cirkit_unit03_gazebo.

Usage

URDF

In URDF in your robot, add the following tag to apply steer_bot_hardware_gazebo.

  <!-- Gazebo plugin for ROS Control -->
  <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      <robotNamespace>/</robotNamespace>
      <robotSimType>steer_bot_hardware_gazebo/SteerBotHardwareGazebo</robotSimType>
    </plugin>
  </gazebo>

An example of a xacro is description.gazebo.xacro in steer_bot_hardware_gazebo.

Paremters

You need to register ROS parameter to apply the plugin to your original robot.

Joint Parameters

rear_wheel (string)

front_steer (string) virtual_rear_wheels (string [2])
  • Virtual rear wheel joint names to send a velocity command to the correspondent wheel joints in Gazebo.
virtual_front_wheels (string [2])
  • Virtual front wheel joint names to grab current angle of the correspondent wheel joints in Gazebo.
virtual_front_steers (string [2])
  • Virtual front steer joint names to send a position command to the correspondent steer joints in Gazebo.

enable_ackermann_link (bool)

  • If it is true, enable virtual ackerman link mechanism. Otherwise, paralell link mechanism is enabled.
wheel_separation_w (double)
  • Wheel separation length between the left side and the right side, which is used for calculating steer angle of Ackermann link mechanism.
wheel_separation_h (double)
  • Wheel separation length between the front side and the rear side, which is used for calculating steer angle of Ackermann link mechanism.

PID parameters to send velocity to the rear wheel joints in Gazebo

gains:
  base_to_right_rear_wheel  :  {p: 100000.0, d: 10.0, i: 0.50, i_clamp: 3.0}
  base_to_left_rear_wheel   :  {p: 100000.0, d: 10.0, i: 0.50, i_clamp: 3.0}

cirkit_unit03_simulator has an example launch file to spawn Robots/CIR-KIT-Unit03 with steer_bot_hardware_gazebo named cirkit_unit03_world.launch.

Wiki: steer_bot_hardware_gazebo (last edited 2016-12-25 12:46:08 by MoriKen)