Skip to content
Sebastian Kasperski edited this page Jan 24, 2014 · 3 revisions

Goal

In this first tutorial we will use only the Operator to safely drive a simulated robot. The environment and the robot will be provided by the Stage simulator, which comes integrated with the ROS distribution. The Operator will use the simulated robot's laser range device to create a local map and use it to avoid collision with obstacles. The robot can be driven around using a joystick while actively avoiding any obstacle.

Required packages:

  • robot_operator
  • remote_controller
  • stage
  • joy
  • p2os (optional)
  • robot_state_publisher (optional)

Setup

You can find the launch file and all required parameter and Stage files in the nav2d_tutorials package.

<!-- Some general parameters -->
<param name="use_sim_time" value="true" />
<rosparam file="$(find nav2d_tutorials)/param/ros.yaml"/>

<!-- Start Stage simulator with a given environment -->
<node name="Stage" pkg="stage" type="stageros" args="$(find nav2d_tutorials)/world/tutorial.world">
	<param name="base_watchdog_timeout" value="0" />
</node>

<!-- Start the Operator to control the simulated robot -->
<node name="Operator" pkg="robot_operator" type="operator" >
	<remap from="scan" to="base_scan"/>
	<rosparam file="$(find nav2d_tutorials)/param/operator.yaml"/>
	<rosparam file="$(find nav2d_tutorials)/param/costmap.yaml" ns="local_map" />
</node>

<!-- Start the joystick-driver and remote-controller for operation-->
<node name="Joystick" pkg="joy" type="joy_node" />
<node name="Remote" pkg="remote_controller" type="remote_joy" />

<!-- Pioneer model for fancy visualization -->
<!-- Comment this out if you do not have the package 'p2os' available! -->
<param name="robot_description" command="$(find xacro)/xacro.py $(find p2os_urdf)/defs/pioneer3at.xacro" />

<node name="PioneerState" pkg="robot_state_publisher" type="state_publisher">
	<remap from="joint_state" to="joint_state"/>
	<param name="publish_frequency" type="double" value="15.0"/>
	<param name="tf_prefix" type="string" value=""/>
</node>

<node name="PioneerTransforms" pkg="p2os_urdf" type="publisher"/>

<!-- RVIZ to view the visulaization -->
<node name="RVIZ" pkg="rviz" type="rviz" args=" -d $(find nav2d_tutorials)/param/tutorial1.vcg" />

Now you can start the simulation with:

roslaunch nav2d_tutorials tutorial1.launch

If everything went alright, you should see the Stage window and RVIZ opening up. The Stage window shows the robot in its environment, while you can see the robot's model together with the local map in RVIZ.

If you also have a joystick, you can use it to drive the robot around. The blue line in RVIZ visualizes the motion command send with the joystick, the green line the motion command that is selected by the Operator and will be send to the robot.

Clone this wiki locally