-
Notifications
You must be signed in to change notification settings - Fork 65
Tutorial2
In the first tutorial we used the RobotOperator to actively avoid obstacles while we still controlled the robot with the joystick. In this tutorial we add a new node, the RobotNavigator, to make our robot navigate autonomously within the environment.
- robot_operator
- robot_navigator
- remote_controller
- map_server
- amcl
- stage
- joy
- p2os (optional)
- robot_state_publisher (optional)
In order to use the RobotNavigator, we will need some additional stuff before we can get started. To navigate, the robot needs a map in order to plan a path to a given location. The MapServer will provide this map as a ROS service, so that the RobotNavigator can use it.
<node name="MapServer" pkg="map_server" type="map_server" args="$(find nav2d_tutorials)/world/tutorial.yaml" />
While the robot moves within the environment, we also have to keep track of it's current position. We will use the ROS package amcl (Adaptive Monte-Carlo Localization) which uses a particle filter to continuously localize the robot. We give it the initial pose of the robot, which is easy in this case as this position is set explicitly in the tutorial.world file.
<node name="AMCL" pkg="amcl" type="amcl">
<remap from="scan" to="base_scan"/>
<param name="initial_pose_x" type="double" value="0.0"/>
<param name="initial_pose_y" type="double" value="-2.0"/>
<param name="recovery_alpha_slow" type="double" value="0.01"/>
<param name="recovery_alpha_fast" type="double" value="0.5"/>
<param name="min_particles" type="int" value="5000"/>
<param name="max_particles" type="int" value="20000"/>
</node>
Now we can include the RobotNavigator to do the navigation. It will send the commands to the RobotOperator that we formerly send manually by using the joystick. The SetGoal node is used in this example to set a goal for the navigator via the ROS topic "/goal".
<node name="Navigator" pkg="robot_navigator" type="navigator">
<rosparam file="$(find nav2d_tutorials)/param/navigator.yaml"/>
</node>
<node name="SetGoal" pkg="robot_navigator" type="set_goal_client" />
Note that the suggested way to use the RobotNavigator is via its actionlib interface by calling the action "robot_navigator/MoveToPosition2D". However in this example the SetGoal node encapsulated this interface, so we can use RVIZ to simply set a goal position manually. Click on the "2D Nav Goal" button in RVIZ and then click into the map to set a position and heading for the robot to move to. If it does not, make sure to check rxconsole and rxgraph for possible error messages and unconnected nodes. Most likely you will have mismatches in topic names or tf frames.
Again you can find a complete launch file in "nav2d_tutorials/launch/tutorial2.launch".