In this post, I will walk the reader through installing Gazebo and show how to model our RP2W Remote Telepresence Robot. This tutorial is based on Gazebo 5.0.1 and Ubuntu 14.04.
Gazebo is a robotics simulator that we will use to save time and money compared to using an actual machine. The end result of this tutorial will give you a robot modeled after the RP2W robot with all three wheels, rotating camera hinges on both axes, and two camera sensors. Click here for a video demonstration.
1. Installing Gazebo
First, we need to install the Gazebo physics simulator. Simply go to their website and follow the instructions: http://gazebosim.org/download
You will download the .deb, launch the terminal (keyboard shortcut: CTRL+ALT+T) and type the following command:
sh ~/Downloads/gazebo5_install.sh
After you are done installing, type in gazebo
as a command. You should see the program launch successfully.
2. Modeling the Robot for Gazebo
First, let’s setup a directory for our RP2W robot. Open up the terminal and type in the following command:
mkdir -p ~/.gazebo/models/rp2w
Then, create a configuration file necessary for our model to be readable by Gazebo:
gedit ~/.gazebo/models/rp2w/model.config
In gedit, copy+paste the following:
<?xml version="1.0"?> <model> <name>RP2W</name> <version>1.0</version> <sdf version='1.4'>model.sdf</sdf> <author> <name>Your Name</name> <email>your@email.com</email> </author> <description> RP2W Custom for E-Motion </description> </model>
Save and exit. Create and edit your model.sdf file. SDF is an XML-style file format used to describe objects for robotics simulators.
gedit ~/.gazebo/models/rp2w/model.sdf
Then, copy and paste the following. The code is a work in progress, but will help you understand what and SDF file should look like for our RP2W robot. Click here to skip past the code to see notes on the SDF format and links to useful resources.
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>false</static> <link name='chassis'> <pose>0 .2032 .0889 0 0 0</pose> <collision name="chassis"> <geometry> <box> <size>.4064 .3937 .127</size> </box> </geometry> </collision> <visual name="chassis"> <geometry> <box> <size>.4064 .3937 .127</size> </box> </geometry> </visual> <inertial> <mass>3</mass> </inertial> </link> <joint name='chassis_body' type='revolute'> <axis> <xyz>0 0 1</xyz> <limit> <lower>0</lower> <upper>0</upper> </limit> </axis> <parent>body</parent> <child>chassis</child> </joint> <link name='body'> <pose>0 .0381 0.7747 0 0 0</pose> <collision name="cylindrical_rod"> <geometry> <cylinder> <radius>.0381</radius><!-- estimation--> <length>1.2446</length> </cylinder> </geometry> </collision> <visual name="cylindrical_rod"> <geometry> <cylinder> <radius>.0381</radius><!-- estimation--> <length>1.2446</length> </cylinder> </geometry> </visual> <sensor type="camera" name="netbook_webcam"> <pose>0 0.0508 0.4953 0 0 1.57079632679</pose> <camera> <horizontal_fov>1.047</horizontal_fov> <image> <width>320</width> <height>240</height> </image> <clip> <near>0.1</near> <far>100</far> </clip> </camera> <always_on>1</always_on> <update_rate>30</update_rate> <visualize>true</visualize> </sensor> <collision name="netbook_board"> <pose>0 .11427 .2253 -0.34906585 0 0</pose><!--needs details on z-value--> <geometry> <box> <size>.2794 .19685 0</size> </box> </geometry> </collision> <visual name="netbook_board"> <pose>0 .11427 .2253 -0.34906585 0 0</pose><!--needs details on z-value--> <geometry> <box> <size>.2794 .19685 0</size> </box> </geometry> </visual> <inertial> <mass>1.5</mass> </inertial> </link> <link name='camera_base'> <pose>0 .0381 1.4 0 0 0</pose> <collision name="bottom"> <geometry> <box> <size>.0889 .0889 0</size> </box> </geometry> </collision> <visual name="visual"> <geometry> <box> <size>.0889 .0889 0.001</size> </box> </geometry> </visual> <collision name="height"> <pose>0 0.01905 0 0 0 0</pose> <geometry> <box> <size>0.0635 0.0635 0.0381</size> </box> </geometry> </collision> <visual name="height_visual"> <pose>0 0.01905 0 0 0 0</pose> <geometry> <box> <size>0.0635 0.0635 0.0381</size> </box> </geometry> </visual> <inertial> <mass>.005</mass> </inertial> </link> <link name='camera'> <pose>0 .05715 1.5113 0 0 1.57079632679</pose><!-- centered at camera focus point--> <sensor type="camera" name="my_sensor"> <camera> <pose>0 0 0 0 0 0</pose> <horizontal_fov>1.047</horizontal_fov> <image> <width>320</width> <height>240</height> </image> <clip> <near>0.1</near> <far>100</far> </clip> </camera> <always_on>1</always_on> <update_rate>30</update_rate> <visualize>true</visualize> </sensor> <inertial> <mass>.005</mass> </inertial> </link> <joint name="camera_base_camera" type="revolute"> <pose>0 0 -0.0762 0 0 0</pose> <axis> <xyz>1 0 0</xyz> <limit> <lower>-1.57079632679</lower> <upper>1.57079632679</upper> </limit> </axis> <parent>camera_base</parent> <child>camera</child> </joint> <link name='right_wheel'> <pose>0.1524 .2794 .0635 0 1.57079632679 0</pose> <collision name='collision'> <geometry> <cylinder> <radius>0.0635</radius> <length>0.0381</length> </cylinder> </geometry> </collision> <visual name='visual'> <geometry> <cylinder> <radius>0.0635</radius> <length>0.0381</length><!--estimate--> </cylinder> </geometry> </visual> <inertial> <mass>0.5</mass> </inertial> </link> <link name='left_wheel'> <pose>-0.1524 .2794 .0635 0 1.57079632679 0</pose> <collision name='collision'> <geometry> <cylinder> <radius>0.0635</radius> <length>0.0381</length> </cylinder> </geometry> </collision> <visual name='visual'> <geometry> <cylinder> <radius>0.0635</radius> <length>0.0381</length><!--estimate--> </cylinder> </geometry> </visual> <inertial> <mass>0.5</mass> </inertial> </link> <link name='front_wheel'> <pose>0 .0381 .0762 0 0 0</pose> <collision name='collision_y'> <pose>0 0 0 0 1.57079632679 0</pose> <geometry> <cylinder> <radius>.0762</radius> <length>.0508</length> </cylinder> </geometry> </collision> <visual name='visual_y'> <pose>0 0 0 0 1.57079632679 0</pose> <geometry> <cylinder> <radius>.0762</radius> <length>.0508</length> </cylinder> </geometry> </visual> <inertial> <mass>0.5</mass> </inertial> </link> <joint name="chassis_right_wheel" type="revolute"> <axis> <xyz>1 0 0</xyz> <dynamics> <friction>0.3</friction> </dynamics><!--EXPERIMENTAL--> </axis> <parent>chassis</parent> <child>right_wheel</child> </joint> <joint name="chassis_left_wheel" type="revolute"> <axis> <xyz>1 0 0</xyz> <dynamics> <friction>0.3</friction> </dynamics><!--EXPERIMENTAL--> </axis> <parent>chassis</parent> <child>left_wheel</child> </joint> <joint name="body_camera_base" type="revolute"> <axis> <xyz>0 0 1</xyz> </axis> <parent>body</parent> <child>camera_base</child> </joint> <joint name="body_front_wheel_y" type="revolute"> <axis> <xyz>1 0 0</xyz> </axis> <parent>body</parent> <child>front_wheel</child> </joint> <plugin name="rp2w" filename="/home/larry/gazebo_plugin/librp2w.so"/> </model> </sdf>
The <pose>
tag has six numbers separated by tag: x, y, z, roll, pitch, yaw (roll, pitch, and yaw are revolutions around the x, y, and z axes, respectively). Note that distance is in meters, angles are in radians, and mass is in kg.
3. Useful Resources
The following links helped me build the RP2W robot. You will find these helpful:
1. http://gazebosim.org/tutorials?tut=build_robot This tutorial will walk you through configuring the model to load into Gazebo and building a very basic robot.
2. http://sdformat.org/spec Specification for SDF. Explains the structure and function of its XML style tags.
3. http://osrf-distributions.s3.amazonaws.com/sdformat/api/1.5.html A more specific but less user-friendly specification for SDF.
4. http://answers.gazebosim.org/questions/ User community in case you have questions/problems about Gazebo.