Mini-Lab Mapping with a Laser Range Finder

Overview

In this section we will present the mapping capability of the Mini-Lab. The robot uses some of its sensors in order to reproduce the same environment where it is placed. The built map could be used for other tasks like autonomous navigation or patrol.

Mapping procedure

This package contains a ROS wrapper for OpenSlam's Gmapping. The gmapping package provides laser-based SLAM (Simultaneous Localization and Mapping), as a ROS node called slam_gmapping. This node enables you to create a 2-D occupancy grid map (like a building floorplan) from laser and pose data collected by a mobile robot.

Gmapping subscribes to the /tf and /scan topics which carries odometric data and the scan data gathered by one of the sensors.

The odometry tends to be inaccurate over time as it accumulates a derivative error. This inaccuracy if corrected by matching the odemetry data to the scans as they are more accurate.

Thus, the process relies on two key transformations between three frames; the scan frame (laser frame), the robot base frame and the odometry frame.

To test the mapping capability you have to follow these instructions:

$ roslaunch minilab_gazebo minilab_gazebo.launch
$ roslaunch minilab_teleop keyboard_teleop.launch
$ roslaunch minilab_description minilab_state_publisher.launch
$ roslaunch minilab_navigation gmapping.launch

The first command will launch the simulation on Gazebo and spawns the test environment.

The second command provides keyboard tele-operation while the third one starts the mapping process.

The third command is responsible for the robot’s model and frames transformations (tf) as well as Rviz, the tool used to visualize the mapping process and the application’s parameters. When Rviz loads, you have to load the supplied configuration file (navigation.rviz) for the mapping task.

And finally the fourth command will start the gmapping task.

Mapping usage

Once the simulation and RVIZ is opened keep the terminal window of the keyboard Tele-operation launch file and move the robot around the environment to build the map. http://www.enovarobotics.eu/Wiki/skins/common/images/gmapping1.png

The mapping process is displayed on real-time on Rviz. http://www.enovarobotics.eu/Wiki/skins/common/images/gmaping2.png

Once you’re finished mapping, use the map server to save your map for future uses.

$ rosrun map_server map_saver -f MAP_NAME

This command will provide two files, one is yaml file wich contain some information about the map like resolution or size, the second is picture (pgm) show the mapped environment. This files can be used for the minilab's navigation. http://www.enovarobotics.eu/Wiki/images/5/59/Screenshot_from_2015-05-06_12_39_48.png

What Next?

Autonomous Navigation

Contact us

For question about the software email us at: support@enovarobotics.com

For more information about the product please visit our website : https://enovarobotics.com

Or email us directly at contact@enovarobotics.com

Wiki: Mini-Lab/Tutorials/Laser_mapping (last edited 2015-08-10 13:40:31 by NabilGabbouj)