Intro
Gazebo plugins enables the simulation of models and sensors, such as drivers, cameras, lidars, etc. Aside from some common tags (ex: updateRate, visualize), different plugins have different custom parameters that could be configured.
Lists of available plugins could be found at the official Gazebo Tutorial.
- This is for Gazebo-classic.
- Users of Ubuntu 18.04+ could switch to Gazebo Garden for more advanced functionalities.
General usage
In robot URDF, insert plugin inside the gazebo tag.
<robot>
......
<gazebo>
<plugin name="${name_of_plugin}" filename="${file_name_of_plugin}">
... plugin paameters ...
</plugin>
</gazebo>
......
</robot>
List of common plugins
Differential Drive
- plugin filename:
libgazebo_ros_diff_drive.so - suitable for driving 2-wheel robots
- listen to motion command (geometry_msgs/Twist)
<commandTopic>: topic name, default to ‘cmd_vel’- could be controlled with teleop mode
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
- publish to transforms for wheel links & odometry, joint states of wheels

- listen to motion command (geometry_msgs/Twist)
Skid Steering Drive
- plugin filename:
libgazebo_ros_skid_steer_drive.so - suitable for driving 4-wheel robots
- receive motion command (geometry_msgs/Twist)
<topicName>: default to ‘cmd_vel’
- publish transforms & joint states of wheels
<broadcastTF>: set true/false
- receive motion command (geometry_msgs/Twist)
Lidar
- plugin filename:
libgazebo_ros_lidar.so
Camera
- plugin filenmae:
libgazebo_ros_camera.so - In order to transform from the ROS coordinate to the camera frame, it is recommended to define additional frame with a
"_optical"suffix. (refer: REP 103) - The joint between camera_link & camera_optical_link would be configured as
<origin xyz="0.0 0.0 0.0" rpy="-1.57 0.0 -1.57"/> - example - camera.xacro
- In the gazebo section, the camera’s parameters, including the
fov,width,height,format,far/nearclip distance (deciding the shape of the frustrum),noise, could be configured - The gazebo reference would still be the camera_link, whereas the plugin frameName tag would be the camera_optical_link. ```xml
- In the gazebo section, the camera’s parameters, including the
```
Depth camera (Microsoft Kinect)
- plugin filename:
libgazebo_ros_openni_kinect.so - similar to camera, except the sensor
type(within<sensor>)would be “depth” - publish
camera/depth/image: depth imagecamera/image: RGB imagecamera/depth/points(sensor_msgs/PointCloud2): the pointcloud that contains the 3d information- The color format need to be reconfigured in order to show correct color, or else the R & B would be messed up
- This can be done by configuring the
<format>(within<image>) from R8G8B8 to B8G8R8
Projector
- plugin filename:
libgazebo_ros_projector.so - Project static image (texture) in world.
- The
<texture>tag would be the name of the image file.- The image should be put in folder
/usr/share/gazebo-7/media/materials/textures(see this thread). There also exist a couple of textures.
- The image should be put in folder
- Replace the
<sensor>tag with<projector>tag. - The projection would be in +Z direction.
- Projector parameters include
near_clipfar_clipfov(Other tags seem to have no effect by far…) (<textureTopicName>&<projectorTopicName>not working as well…)
Reference
- ros wiki - gazebo_plugins
- official Gazebo Tutorial - Gazebo plugins in ROS
- gazebo plugin source code - Github repo
- example of xacro files with lidar, (depth) camera, projector plugin - My project - mybot (branch “gazebo-sensors”)