Note: This tutorial assumes that you have completed the ROS Navigation, amcl, move_base and roch_bringup.
(!) 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.

SLAM Map Building with Roch and navigation

Description: How to generate a map using gmapping, and navigation on a static map after mapping using lidar.

Tutorial Level: BEGINNER

Next Tutorial: Setup the Navigation Stack for Roch

This assumes that you have a Roch which has already been brought. And if you want to use at first that can play with simulating Roch in Gazebo.

note: before you playing roch_navigation, you should configure which sensors you want to use, configuration process please checkout this tutorial.

Launch Gmapping demo

This demo is for map building, so you should note that for 3D sensor r200, ensure ROCH_3D_SENSOR_NAV_ENABLE is false.

You can choose which sensor using gmapping, but just one.

Disable lidar you should put ROCH_LASER_ENABLE into false.

Disable 3d sensor with navigation you should change ROCH_3D_SENSOR_NAV_ENABLE to false.

Disable 3d sensor neither navigation nor anything you can change ROCH_3D_SENSOR_ENABLE to false.

note: You will get unpredictable errors if you using two sensors in navigation.

On the Roch

Connect to Roch's board or PC using ssh:

  • ssh <Roch_PC_NAME>@<IP_OF_Roch>

For example:  ssh ubuntu@192.168.1.100 

And bringup the robot

  • roslaunch roch_bringup minimal.launch

Then run the gmapping demo app

  • roslaunch roch_navigation gmapping_demo.launch

After running gmapping demo, you should control Roch move, typing following command:

  • roslaunch roch_teleop keyboard_teleop.launch

About code of roch_teleop, reference turtlebot_follower.

On your PC

This assumes you have ROS on your PC and ROS_MASTER_URI has been set to point to your Roch. If you have not configure this value, please read Network configuratrion to setup ROS_MASTER_URI and ROS_HOSTNAME.

  • Checkout map in rviz
    roslaunch roch_viz view_navigation.launch

Finish Mapping

You can save your map using following command:

  • rosrun map_server map_saver -f <map_path>/<map_name>

note: map_name just is a name without suffix such as .pgm. And don not close the terminal which is running gmapping until finish map saved.

Launch AMCL

To Run amcl with lidar, you should note under items.

  • Because of navigation based on costmap, and truth command sent by local planner based on local costmap, the plan you want robot go to goal should always haves data which obstacles in local costmap, otherwise will cause amcl can not estimate pose in map.
  • Before you command robot for navigation you should clear obstacles around, otherwise will also cause robot can not use amcl.

In this section, we learning how to using roch_navigation to navigation on a known map. Before we launch amcl_demo.launch, let's know some points.

There have two mainly section in amcl_demo.launch, one is amcl and another is move_base.

In this section, we need to use one variable is ROCH_MAP_FILE which always point your map path which you created.

For example, the map you created is in ~/maps, and in this folder there will have two file my_map.yaml and my_map.pgm.

note: my_map is the map name we used for example. Then on the Roch, modify ~/.bashrc file:

  • export ROCH_MAP_FILE=~/maps/my_map.yaml

Running demo

  1. On the Roch, bring up driver:
    roslaunch roch_bringup minimal.launch
  2. On the Roch, run amcl_demo.launch:
    roslaunch roch_navigation amcl_demo.launch
  3. On your PC, Run rviz:
    roslaunch roch_viz view_navigation.launch

Rviz

Localize

When rviz is open, at first you should localize the roch approximate location on the map, and use following ways:

  • 1.Click the "2D Pose Estimate" button. 2.Click on the map where the Roch approximate is and drage in the direction the Roch is pointing.

And now you will see Roch move to the pace you specify on map.

Send goal

After the Roch localized on map, and now you will see Roch and model of Roch on map or real life is correspond. You can send goal on map now:

  • 1.Click the "2D Nav Goal" button. 2.Click on the map where you want the Roch to go and drag in the direction the Roch should bepointing at the end.

And Now you will see Roch moving to the place you want.

Wiki: roch/Tutorials/Using package of roch_navigation (last edited 2017-03-10 06:17:11 by SawYer)