This tutorial will teach you how to create a Gazebo world and spawn Atlas into it.
We assume that you've already done the installation step.
If you haven't done so, add the environment setup.sh files to your .bashrc.
echo 'source /usr/share/drcsim/setup.sh' >> ~/.bashrc
source ~/.bashrc
Use roscreate-pkg to create a ROS package for this tutorial, depending on drcsim_gazebo
:
cd ~/ros
export ROS_PACKAGE_PATH=`pwd`:$ROS_PACKAGE_PATH
roscreate-pkg world_create_tutorial drcsim_gazebo
roscd world_create_tutorial
mkdir worlds launch
Next, copy and paste this launchfile into ~/ros/world_create_tutorial/launch/atlas.launch
, or download the file here:
<launch>
<arg name="gzname" default="gazebo"/>
<arg name="gzworld" default="$(find world_create_tutorial)/worlds/myworld.world"/>
<arg name="hand_suffix" default=""/>
<arg name="extra_gazebo_args" default="-q" />
<arg name="model_args" default="" />
<arg name="inertia_args" default="" /> <!-- _with_v1_inertia -->
<param name="/atlas/time_to_unpin" type="double" value="1.0"/>
<param name="/atlas/startup_mode" type="string" value="bdi_stand"/>
<!-- start gazebo with the Atlas -->
<include file="$(find drcsim_gazebo)/launch/atlas_no_controllers.launch">
<arg name="gzname" value="$(arg gzname)"/>
<arg name="gzworld" value="$(arg gzworld)"/>
<arg name="extra_gazebo_args" value="$(arg extra_gazebo_args)"/>
</include>
<!-- to trigger synchronization delay, set
atlas_msgs::AtlasCommand::desired_controller_period_ms to non-zero -->
<param name="/atlas/delay_window_size" type="double" value="5.0"/>
<param name="/atlas/delay_max_per_window" type="double" value="0.25"/>
<param name="/atlas/delay_max_per_step" type="double" value="0.025"/>
<!-- Robot Description -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find atlas_description)/robots/atlas$(arg model_args)$(arg inertia_args)$(arg hand_suffix).urdf.xacro'" />
<param name="robot_initial_pose/x" value="0" type="double"/>
<param name="robot_initial_pose/y" value="0" type="double"/>
<param name="robot_initial_pose/z" value="0.90" type="double"/>
<param name="robot_initial_pose/roll" value="0" type="double"/>
<param name="robot_initial_pose/pitch" value="0" type="double"/>
<param name="robot_initial_pose/yaw" value="0" type="double"/>
<include file="$(find drcsim_gazebo)/launch/atlas$(arg hand_suffix)_bringup.launch">
<arg name="model_args" value="$(arg model_args)"/>
</include>
</launch>
This launchfile is nearly identical of the atlas.launch
file in drcsim_gazebo
, except that the gzworld
argument has been changed to a different file. This file doesn't exist yet, but we will create it in the next step.
If you want to spawn Atlas in a different position, change robot_initial_pose/x
and robot_initial_pose/y
.
Open gazebo with no command line arguments:
gazebo
You will see a blank world.
Now, add some simple shapes to the environment using the icons in the toolbar. You can add boxes, spheres or cylinders.
You can even add pre-existing models to the environment using the "Insert Models" tab:
When you're done, save the world by clicking "File" then "Save World As". You can also use the keyboard shortcut, CTRL-SHIFT-S. Call it myworld.world
and save it to ~/ros/world_create_tutorial/worlds
. When you are finished, exit Gazebo.
Now, open the new .world
in your favorite text editor.
Copy/paste the following block into the file. Make sure the block is a direct child of the <world></world>
element.
<plugin filename="libVRCPlugin.so" name="vrc_plugin">
<atlas>
<model_name>atlas</model_name>
<pin_link>utorso</pin_link>
</atlas>
<drc_vehicle>
<model_name>golf_cart</model_name>
<seat_link>chassis</seat_link>
</drc_vehicle>
<drc_fire_hose>
<fire_hose_model>fire_hose</fire_hose_model>
<coupling_link>coupling</coupling_link>
<standpipe_model>standpipe</standpipe_model>
<spout_link>standpipe</spout_link>
<thread_pitch>-1000</thread_pitch>
<coupling_relative_pose>1.17038e-05 -0.125623 0.35 -0.0412152 -1.57078 1.61199</coupling_relative_pose>
</drc_fire_hose>
</plugin>
This plugin element spawns Atlas using the VRCPlugin, which also manages the robot's standing controllers, the control interface to the robot, etc.
When you are finished, launch Atlas in the new world:
roslaunch world_create_tutorial atlas.launch
You should see Atlas spawned next to the objects you placed in the previous step:
From here, you're ready to modify the robot's environment any way you like. Have a look at SDF documentation and edit ~/ros/world_modification_tutorial/worlds/atlas.world
however you like.