(!) 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.

Navigate with REEM

Description: This tutorial will show you how to use the navigation stack with REEM

Tutorial Level: BEGINNER

Next Tutorial: Robots/REEM/Tutorials/Face detection with REEM

Launch REEM simulation with navigation

roslaunch reem_2dnav_gazebo reem_navigation.launch

reem-nav-gazebo-rviz.png

Here you will get REEM in a simple world of two rooms in Gazebo and a Rviz window pre-configured with some sensor and map visualization. Basically, you can see:

  • Robot pose estimation, as provided by the amcl localization algorithm.

  • The Occupancy Grid Map (OGM) that matches the world in gazebo, as provided by the map_server node.

  • The laser readings from the base laser in the front side of the robot between the wheels, which is used by the localization algorithm.

Send navigation goals through Rviz

In the Rviz window click on the 2D Nav Goal button and click and drag to set a navigation goal in the map. reem-nav-click-2dnavgoal.png

You will see how a path is generated to achieve the goal and the robot will start moving towards the goal. reem-nav-watch-path.png

If the robot get lost you can always click on 2D Pose Estimate and set the position in the map where the robot really is.

The path planning algorithm is divided in two modules:

  • Global planner, which is the actual path planning algorithm that find the path from the current robot pose to the goal. This is the green line we see in the previous image. This algorithm only uses the static OGM.
  • Local planner, which is an obstacle avoidance algorithm that uses a local costmap built using the sensors in order to avoid obstacles; including moving ones. The sensors used are the base laser and the sonars; the IRs and the torso laser con also be included.

We have different options when choosing the planner, specially for the local one. You can change the local planner by launching the navigation passing the name of the desired planner:

For example, to use the DWA you should do:

roslaunch reem_2dnav_gazebo reem_navigation.launch local_planner:=dwa

Note that in our robots we use a planner called PAL local planner; we are working on providing the binaries online for our simulation.

Send navigation goals through an axclient.py

Fire up your axclient.py pointing towards REEM's navigation action server. The action server is /move_base with action message type: move_base_msgs/MoveBase

rosrun actionlib axclient.py /move_base

axclient_move_base.png

Set frame_id to 'map'.

Set x and y, z must be 0.0. (For example, x=1.0, y=1.0).

Set the orientation quaternion of the goal (a dummy one can consist on w=1.0 and the rest to 0.0). You could also use the snippet deg_to_yaw.py to get the quaternion from a rotation in degrees.

Click SEND GOAL.

The robot should plan and go to the goal. You can check current position of the robot consulting the /amcl_pose topic which gives back the current known position of the robot:

rostopic echo /amcl_pose

header:
  seq: 23
  stamp:
    secs: 221
    nsecs: 133000000
  frame_id: map
pose:
  pose:
    position:
      x: 1.48284227221
      y: 5.86751160146
      z: 0.0
    orientation:
      x: 0.0
      y: 0.0
      z: 0.716315805764
      w: 0.69777622947
  covariance: [0.008844747179827195, -0.0009735504498152095, 0.0, 0.0, 0.0, 0.0, -0.0009735504498152095, 0.009650213577260335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014391377374212409]

Send navigation goals via (Python) code

Check out the reem_snippets package:

cd ~/reem-sim_ws/src
git clone https://github.com/reem-utils/reem_snippets

There you will find a demo code called navigation.py which examplifies how to send a navigation goal and also how to get the current pose in the map of the robot.

Mapping in simulation

On the real robot we have an Android tablet app that allows you to map easily. In order to test mapping in simulation first launch the corresponding simulation:

roslaunch reem_2dnav_gazebo reem_mapping.launch

reem-nav-mapping.png To move the robot you can send goals with Rviz or use the arrow keys of your keyboard cloning the following package in your catkin workspace source directory:

git clone https://github.com/pal-robotics/key_teleop.git

Then just run:

rosrun key_teleop key_teleop.py

Note that you must have the terminal where you ran this command on focus, it's recommended to put the Gazebo or Rviz window as "Always on top" so you can drive REEM with the keyboard.

A SLAM algorithm uses the robot odometry and the laser scans to build a map. You will see how the map is being built online with the new scans as the robot is moved around the environment.

To save the map:

rosrun map_server map_saver

To use it later on copy the map inside reem_maps/configurations.

Wiki: Robots/REEM/Tutorials/navigation (last edited 2017-05-15 11:21:08 by VictorLopez)