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

Create a map using gmapping

Description: How to create a map using a slam package (gmapping) and a simple obstacle avoidance node to move a robot autonomously while mapping.

Tutorial Level: INTERMEDIATE

Next Tutorial: stdr_simulator/Tutorials/Using turtlebot for teleoperation

Start STDR Simulator with one robot

We will use one of the launchers provided in stdr_launchers. In a terminal run:

$ roslaunch stdr_launchers server_with_map_and_gui_plus_robot.launch

Run slam_gmapping node

You need to install gmapping first if you haven't already. Gmapping by default publishes the generated map to /map topic that conflicts /map topic used by STDR Simulator for the static map. You must change that, otherwise the simulator will crash. Start gmapping running the following command in a new terminal:

$ rosrun gmapping slam_gmapping scan:=/robot0/laser_0 _base_frame:="/robot0"  map:=/gmapping/map

Start stdr_obstacle_avoidance node to move the robot autonomously

We will use stdr_obstacle_avoidance node, provided by stdr_samples package. You can use any navigation package you want, that publishes a geometry_msgs/Twist message, like move_base. To start stdr_obstacle_avoidance node, in a new terminal run:

$ rosrun stdr_samples stdr_obstacle_avoidance robot0 laser_0

The robot will start moving randomly and avoid collisions:

gui

Run rviz to visualize the generated map

You can run rviz and subscribe to /gmapping/map topic to visualize the map, or you can use the launcher provided by stdr_launchers package and change the subscribed topic. In a new terminal, run:

$ roslaunch stdr_launchers  rviz.launch

After you have subscribed to the correct topic, you should see the generated map by gmapping:

rviz

Wiki: stdr_simulator/Tutorials/Create a map with gmapping (last edited 2018-01-26 19:07:34 by TullyFoote)