Note: This tutorial assumes that you have completed the previous tutorials: nav2d/Tutorials/RobotOperator.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Use the Navigator-Node to navigate on a given map.

Description: The tutorial will show how to setup a map server to provide a a-priori map, a Monte-Carlo-Localizer to track the robots position and the Navigator to do a simple path planning.

Keywords: navigation, path planning, localization

Tutorial Level: BEGINNER

Next Tutorial: Setup Mapper to build a map while driving. MultiMapper

Goal description

In the previous tutorial we just used the Operator to safely drive the robot around in an semi-autonomous way without hitting any obstacles. There we used a Joystick to send direction commands to the Operator. In order to drive fully-autonomous we will now have the Navigator sending the motion commands instead of the joystick. To get started with path planning and navigation, we have to provide three additional components: a map, the robot's position within this map, and the Navigator as the actual path planner.

The complete launch file to start the setup described can be found here: [nav2d_tutorials/launch/tutorial2.launch].

Providing a map

To provide a map, we will use the map_server node, which is part of the ROS navigation stack. Because we are using simulation, we can simply load the same map image that we used to create the environment in Stage. On a real robot the map has to be created first using the robot as described in the next tutorial.

<node name="MapServer" pkg="map_server" type="map_server" args="$(find nav2d_tutorials)/world/tutorial.yaml" />

Providing the robot pose

To provide the robot's pose within the map, we will use a particle filter to estimate its current position and heading.

<node name="SelfLocalizer" pkg="nav2d_localizer" type="localizer">
    <remap from="scan" to="base_scan"/>
    <param name="min_particles" type="int" value="5000"/>
    <param name="max_particles" type="int" value="20000"/>
</node>

Right now we can't give it an initial pose, so the particles will be distributed equally over the map.

Starting the Navigator

The Navigator is started in the usual way and given a set of parameters suitable for the simulated scenario.

<node name="Navigator" pkg="nav2d_navigator" type="navigator">
    <rosparam file="$(find nav2d_tutorials)/param/navigator.yaml"/>
</node>

The Navigator provides its functionality via so-called Actions and the actionlib-interface. While this is a very flexible way to handle asynchronous communication between nodes, in this tutorial we want to set navigation targets by clicking in the map using RVIZ. To this end we will also sa start the set_goal_client, which will subscribe to the "goal" topic and create requests to the Navigator's action server.

<node name="SetGoal" pkg="nav2d_navigator" type="set_goal_client" />

Using Navigation

Before you can actually use the Navigator, you have to drive the robot manually by using the Joystick as in the previous tutorial until the localizer has successfully estimated the robots position. Once this is done you can use RVIZ' "2D Nav Goal" to send a goal to the Navigator.

Wiki: nav2d/Tutorials/RobotNavigator (last edited 2016-01-06 09:17:07 by SebastianKasperski)