In this video, we are going to show how to create a launch file to spawn a URDF robot model in a given gazebo world.
Up to the end of the video, you will be able to spawn any robot model you may have described in URDF in Gazebo.
Step 1. Create a project in ROS Development Studio(ROSDS)
ROSDS helps you follow our tutorial in a fast pace without dealing without setting up an environment locally. If you haven’t had an account yet, you can create a free account here. Let’s create a new project and call it launch_urdf_model_in_gazebo.
Step 2. Create a package
Let’s create a ROS package for our code by using the following command.
cd ~/catkin_ws/src catkin_create_pkg my_robot_urdf rospy
Then we create a m2wr.urdf file under the my_robot_urdf/urdf folder.
<?xml version="1.0"?>
<robot name="m2wr" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.203125 0.23828125 0.28515625 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.80078125 0.12890625 0.1328125 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<gazebo reference="link_chassis">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="link_left_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="link_right_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
<alwaysOn>true</alwaysOn>
<updateRate>20</updateRate>
<leftJoint>joint_left_wheel</leftJoint>
<rightJoint>joint_right_wheel</rightJoint>
<wheelSeparation>0.4</wheelSeparation>
<wheelDiameter>0.2</wheelDiameter>
<torque>0.1</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>link_chassis</robotBaseFrame>
</plugin>
</gazebo>
<gazebo reference="sensor_laser">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/m2wr/laser/scan</topicName>
<frameName>sensor_laser</frameName>
</plugin>
</sensor>
</gazebo>
<link name="link_chassis">
<!-- pose and inertial -->
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass value="5"/>
<origin rpy="0 0 0" xyz="0 0 0.1"/>
<inertia ixx="0.0395416666667" ixy="0" ixz="0" iyy="0.106208333333" iyz="0" izz="0.106208333333"/>
</inertial>
<!-- body -->
<collision name="collision_chassis">
<geometry>
<box size="0.5 0.3 0.07"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.5 0.3 0.07"/>
</geometry>
<material name="blue"/>
</visual>
<!-- caster front -->
<collision name="caster_front_collision">
<origin rpy=" 0 0 0" xyz="0.35 0 -0.05"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="caster_front_visual">
<origin rpy=" 0 0 0" xyz="0.2 0 -0.05"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</visual>
</link>
<link name="link_right_wheel">
<inertial>
<mass value="0.2"/>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<inertia ixx="0.000526666666667" ixy="0" ixz="0" iyy="0.000526666666667" iyz="0" izz="0.001"/>
</inertial>
<collision name="link_right_wheel_collision">
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.1"/>
</geometry>
</collision>
<visual name="link_right_wheel_visual">
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.1"/>
</geometry>
</visual>
</link>
<joint name="joint_right_wheel" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 0.15 0"/>
<child link="link_right_wheel"/>
<parent link="link_chassis"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<link name="link_left_wheel">
<inertial>
<mass value="0.2"/>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<inertia ixx="0.000526666666667" ixy="0" ixz="0" iyy="0.000526666666667" iyz="0" izz="0.001"/>
</inertial>
<collision name="link_left_wheel_collision">
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.1"/>
</geometry>
</collision>
<visual name="link_left_wheel_visual">
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.1"/>
</geometry>
</visual>
</link>
<joint name="joint_left_wheel" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 -0.15 0"/>
<child link="link_left_wheel"/>
<parent link="link_chassis"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
</robot>
This file defines the physical parameters of our robot and the type of controller that we want to use.
We’ll create a launch file to launch this description. We name it spawn_urdf.launch and put it under the launch folder.
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<param name="robot_description" command="cat '$(find my_robot_urdf)/urdf/m2wr.urdf'" />
<node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -param robot_description -model m2wr" />
</launch>
You can see that the launch file try to find the description file from the my_robot_urdf package.
Now we have to compile it with the following command
cd ~/catkin_ws catkin_make source devel/setup.bash
Now you can launch an empty world simulation from Simulations->Empty, then use the command roslaunch my_robot_urdf spawn_urdf.launch to spawn the robot!
If you are interested in this topic and want to learn more about URDF, please check our Robot Creation with URDF course.
Edit by: Tony Huang
Related resources and links:
- Robot Ignite Academy
- ROS Development Studio
- My 2 wheeled robot model repository:https://bitbucket.org/theconstructcore/two-wheeled-robot-simulation
- Original question: http://answers.gazebosim.org/question/19959/how-to-create-launch-file-for-my-urdf-file-and-open-it-in-gazebo/
![[ROS-Q&A]-142—How-to-create-launch-file-for-URDF-and-open-in-Gazebo [ROS-Q&A]-142---How-to-create-launch-file-for-URDF-and-open-in-Gazebo](https://www.theconstruct.ai/wp-content/uploads/2018/07/ROS-QA-142-How-to-create-launch-file-for-URDF-and-open-in-Gazebo.jpg)




0 Comments