!

Note: This tutorial assume that your familiar with Navigation package, Amcl, Hector slam.
(!) 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.

Robot navigation

Description:

Tutorial Level: ADVANCED

Next Tutorial: Arm manipulation

Overview

The Navigation Stack is fully supported on all robots.

You can choose between controlling the robot directly using the differential drive controller as explained in the Command your robot with simple motion commands tutorial, or use the move_base interface for high level commands.

In this tutorial we will also cover the supported localization and mapping options.

For simplicity we will use the ARMadillo robot for all following examples.

The move_base interface

The move_base package provides an implementation of an action (see the actionlib package) that, given a goal in the world, will attempt to reach it with a mobile base. The move_base node links together a global and local planner to accomplish its global navigation task. For more reference on move_base interface please refer to this link

Graphical use

To understand how to work with graphical interface, launch the simulated demo of amcl. To do that, open a new terminal and type the following:

$ roslaunch robotican_armadillo armadillo.launch lidar:=true move_base:=true amcl:=true gazebo:=true have_map_file:=true world_name:="`rospack find robotican_common`/worlds/UPlat.sdf" x:=0.5 y:=0.5

The launch contain the following packages:

  1. Move base. (For planning the path to the goal and moving the robot)
  2. Gazebo with armadillo model.
  3. Server map. (To provide a map for the amcl package)

  4. Amcl. (To position the robot in the map)
  5. Rviz. (For the graphical use)

The following video demonstrates how navigation stack work with the Rviz graphical interface.

API use

This code is available in the robotican_demos at the src folder. To run the code type the following command:

$ rosrun robotican_demos simple_navigation_goals

   1 #include <ros/ros.h>
   2 #include <move_base_msgs/MoveBaseAction.h>
   3 #include <actionlib/client/simple_action_client.h>
   4 
   5 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
   6 
   7 int main(int argc, char** argv){
   8   ros::init(argc, argv, "simple_navigation_goals");
   9 
  10   //tell the action client that we want to spin a thread by default
  11   MoveBaseClient ac("move_base", true);
  12 
  13   //wait for the action server to come up
  14   while(!ac.waitForServer(ros::Duration(5.0))){
  15     ROS_INFO("Waiting for the move_base action server to come up");
  16   }
  17 
  18   move_base_msgs::MoveBaseGoal goal;
  19 
  20   //we'll send a goal to the robot to move 1 meter forward
  21   goal.target_pose.header.frame_id = "base_link";
  22   goal.target_pose.header.stamp = ros::Time::now();
  23 
  24   goal.target_pose.pose.position.x = 1.0;
  25   goal.target_pose.pose.orientation.w = 1.0;
  26 
  27   ROS_INFO("Sending goal");
  28   ac.sendGoal(goal);
  29 
  30   ac.waitForResult();
  31 
  32   if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  33     ROS_INFO("Hooray, the base moved 1 meter forward");
  34   else
  35     ROS_INFO("The base failed to move forward 1 meter for some reason");
  36 
  37   return 0;
  38 }

Now, we'll break down the code line by line:

   2 #include <move_base_msgs/MoveBaseAction.h>
   3 

This line includes the action specification for move_base which is a ROS action that exposes a high level interface to the navigation stack. Essentially, the move_base action accepts goals from clients and attempts to move the robot to the specified position/orientation in the world. For a detailed discussion of ROS actions see the actionlib documentation.

   5 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;

This line creates a convenience typedef for a SimpleActionClient that will allow us to communicate with actions that adhere to the MoveBaseAction action interface.

  10   //tell the action client that we want to spin a thread by default
  11   MoveBaseClient ac("move_base", true);

This line constructs an action client that we'll use to communicate with the action named "move_base" that adheres to the MoveBaseAction interface. It also tells the action client to start a thread to call ros::spin() so that ROS callbacks will be processed by passing "true" as the second argument of the MoveBaseClient constructor.

  13   //wait for the action server to come up
  14   while(!ac.waitForServer(ros::Duration(5.0))){
  15     ROS_INFO("Waiting for the move_base action server to come up");
  16   }

These lines wait for the action server to report that it has come up and is ready to begin processing goals.

  18   move_base_msgs::MoveBaseGoal goal;
  19 
  20   //we'll send a goal to the robot to move 1 meter forward
  21   goal.target_pose.header.frame_id = "base_link";
  22   goal.target_pose.header.stamp = ros::Time::now();
  23 
  24   goal.target_pose.pose.position.x = 1.0;
  25   goal.target_pose.pose.orientation.w = 1.0;
  26 
  27   ROS_INFO("Sending goal");
  28   ac.sendGoal(goal);

Here we create a goal to send to move_base using the move_base_msgs::MoveBaseGoal message type which is included automatically with the MoveBaseAction.h header. We'll just tell the base to move 1 meter forward in the "base_link" coordinate frame. The call to ac.sendGoal will actually push the goal out over the wire to the move_base node for processing.

  30   ac.waitForResult();
  31 
  32   if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  33     ROS_INFO("Hooray, the base moved 1 meter forward");
  34   else
  35     ROS_INFO("The base failed to move forward 1 meter for some reason");

The only thing left to do now is to wait for the goal to finish using the ac.waitForGoalToFinish call which will block until the move_base action is done processing the goal we sent it. After it finishes, we can check if the goal succeded or failed and output a message to the user accordingly.

Simultaneous localization and mapping - SLAM

Hector SLAM

hector_slam uses the hector_mapping node to build a map in an environment and simultaneously estimates the platform's 2D pose at laser scanner frame rate. The frame names and options for hector_mapping have to be set correctly.

To see the hector_slam work in our robots we have provided a demo launch. To launch it, open a new terminal and type the following:

$ roslaunch robotican_armadillo armadillo.launch hector_slam:=true

The following video demonstrates how the hector_slam works:

GMapping SLAM

Rao-Blackwellized particle filters have been introduced as effective means to solve the simultaneous localization and mapping (SLAM) problem. This approach uses a particle filter in which each particle carries an individual map of the environment. Accordingly, a key question is how to reduce the number of particles. We present adaptive techniques to reduce the number of particles in a Rao- Blackwellized particle filter for learning grid maps. We propose an approach to compute an accurate proposal distribution taking into account, not only the movement of the robot but also the most recent observation. This drastically decrease the uncertainty about the robot's pose in the prediction step of the filter. Furthermore, we apply an approach to selectively carry out re-sampling operations which seriously reduces the problem of particle depletion. For more reference on this package please refer gmapping

To see the gmapping_slam work in our robots we provided a demo launch, To launch this demo please open a new terminal and type the following:

$ robotican_demos gmapping_demo.launch armadillo:=true

Saving the map

To save the current map just type the following command in a new terminal:

$ rosrun map_server map_saver 

The map_saver program will save the map in the current folder, and will output two file:

  1. map.pgm
  2. map.yaml

NOTE:To change the name of the files go to map.yaml file. In the image field change the map.pgm to <my_map>.pgm

Localization

AMCL

amcl is a probabilistic localization system for a robot moving in 2D. It implements the adaptive (or KLD-sampling) Monte Carlo localization approach (as described by Dieter Fox), which uses a particle filter to track the pose of a robot against a known map.

To see how amcl work with our robots refer to the first example in this page.

Wiki: robotican/Tutorials/Robot navigation (last edited 2017-10-09 07:05:53 by elhay)