Using URDF in Gazebo Simulation
The URDF robot description can be used to simulate the robot in Gazebo. This can be done through the following steps. For the example below, the folders “urdf”, “config”, “rviz”, and “launch” used in the example are all inside “my_robot_description” package.
Step 1: Install gazebo_ros_pkgs package which connect between Gazebo and ROS.
Step 2: Install gazebo_ros_control package which enables controlling the robot in Gazebo by using ROS Control.
Step 3: Insert gazebo_ros_control Gazebo plugin into URDF. Insert the following before the </robot> tag in the URDF file.
1 2 3 4 5 |
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/</robotNamespace> </plugin> </gazebo> |
In the case of using a namespace for your robot, for example: /MYROBOT, the code snippet becomes like this:
1 2 3 4 5 |
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/MYROBOT</robotNamespace> </plugin> </gazebo> |
Step 4: Add <transmission> into URDF. This specifies the joint actuation.
1 2 3 4 5 6 7 8 9 |
<transmission name="joint1_transmission"> <type>transmission_interface/SimpleTransmission</type> <actuator name="joint1_motor"> <mechanicalReduction>1</mechanicalReduction> </actuator> <joint name="joint1"> <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface> </joint> </transmission> |
In this example, only one joint called “joint1” is actuated. If you have more joints to be actuated, you need to include all of them in the <transmission> tag. Furthermore, here “PositionJointInterface” is used as the hardware interface. Other hardware interfaces can be see here: http://wiki.ros.org/ros_control#Hardware_Interfaces
Step 5: Create a config file (.yaml file) which configures the controller which controls the actuated joint(s). A good practice is to put such configuration files in a folder called “config”. A controller configuration in a file called “joint_controller.yaml” looks like this:
1 2 3 4 5 6 7 8 9 10 |
# Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Position Controllers --------------------------------------- joint1_position_controller: type: effort_controllers/JointPositionController joint: joint1 pid: {p: 100.0, i: 0.01, d: 10.0} |
In the case of using a namespace for your robot, for example /MYROBOT, the yaml file looks like this:
1 2 3 4 5 6 7 8 9 10 11 |
MYROBOT: # Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Position Controllers --------------------------------------- joint1_position_controller: type: effort_controllers/JointPositionController joint: joint1 pid: {p: 100.0, i: 0.01, d: 10.0} |
Depending on the type of controller, the parameters in the yaml file may be different from one controller type to another controller type.
Step 6: Launch the robot in Gazebo by running the “urdf_spawner” node. This can be done by using a launch file called “gazebo.launch” like this:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 |
<launch> <!-- these are the arguments you can pass this launch file, for example paused:=true --> <arg name="paused" default="false"/> <arg name="use_sim_time" default="true"/> <arg name="gui" default="true"/> <arg name="headless" default="false"/> <arg name="debug" default="false"/> <arg name="model" default="$(find my_robot_description)/urdf/main_file.urdf.xacro"/> <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)"/> <arg name="use_sim_time" value="$(arg use_sim_time)"/> <arg name="headless" value="$(arg headless)"/> </include> <param name="robot_description" command="$(find xacro)/xacro $(arg model)" /> <!-- push robot_description to factory and spawn robot in gazebo --> <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args="-z 1.0 -unpause -urdf -model robot -param robot_description" respawn="false" output="screen" /> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"> <param name="publish_frequency" type="double" value="30.0" /> </node> </launch> |
In this launch, we can see the following:
- The empty_world environment is launched in Gazebo.
- The URDF is launched by running “urdf_spawner” node. This node requires some parameters including those shown above. The URDF robot description to be spawned is defined by the parameter -param.
- The “robot_state_publisher” node is also run.
So far, we already launch the robot in Gazebo “empty_world” environment. In order to be able to control the robot by using ROS, i.e. by using ROS Control, we need the next step below.
Step 7: Launch the controller(s). A launch file to launch the controller looks like this:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 |
<launch> <arg name="model" default="$(find my_robot_description)/urdf/main_file.urdf.xacro"/> <arg name="rvizconfig" default="$(find my_robot_description)/rviz/my_rviz.rviz" /> <include file="$(find my_robot_description)/launch/gazebo.launch"> <arg name="model" value="$(arg model)" /> </include> <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" /> <rosparam command="load" file="$(find my_robot_description)/config/joint_controller.yaml" ns="" /> <node name="controller_spawner" pkg="controller_manager" type="spawner" args="joint_state_controller joint1_position_controller"/> </launch> |
In the case of using a namespace for your robot, the “controller_spawner” part looks like this:
1 2 3 |
<node name="controller_spawner" pkg="controller_manager" type="spawner" ns="/MYROBOT" args="joint_state_controller joint1_position_controller"/> |
This launch file does not only launch the controller, but it also launch RViz. Of course, launching RViz here is optional. It is also possible to combine Step 6 and Step 7 in a single launch file if you wish.