Autonomous SLAM Using Frontier Exploration in ROS
In another post, we perform GMapping SLAM while we tele-operate a robot. Now in this post we are going to perform GMapping autonomously. This is done by using frontier_exploration package. Here are some links about this approach:
- Original paper: http://www.robotfrontier.com/papers/cira97.pdf
- ROS Wiki page: http://wiki.ros.org/frontier_exploration
- Github link: https://github.com/paulbovbel/frontier_exploration
- Frontier exploration using Husky: https://www.clearpathrobotics.com/assets/guides/melodic/husky/HuskyFrontiers.html
- Frontier expolartion using Husky (source code for ROS Melodic): https://github.com/husky/husky/tree/melodic-devel/husky_navigation
It turns out that the original source code of frontier_exploration is only maintained until ROS Melodic. However, we can see that it is used until ROS Noetic by Husky here.
The frontier_exploration node basically will provide rules for the motion planning of the mobile robot to explore the environment without going out of a prescribed boundary (defined by a prescribed polygon). By using move_base node, the robot can be navigated to follow the rules provided by the frontier_exploration node. Hence, instead of being tele-operaated, the robot will move autonomously based on the planned path.
In order to perform GMapping SLAM autonomously using frontier_exploration, you should launch the following nodes:
- gmapping node
- move_base node
- frontier_exploration server node
- frontier_exploration client node
Below are the steps to do it by using Husky UGV (with a few adaptation for more readability):
Step 1: Install the “frontier_exploration” from the source code.
|
1 2 |
cd ~/catkin_ws/src git clone https://github.com/paulbovbel/frontier_exploration.git |
Install all the dependency packages:
|
1 2 |
cd ~/catkin_ws rosdep install --from-paths src --ignore-src -r -y |
And finally build the package by using the catkin_make command.
Step 2: Create your navigation package if you have not created it yet. In this case, let’s say the navigation package is called “husky_navigation”. Create “launch” and “config” folders inside the package folder.
Step 3: Create a launch file to run the “gmapping” node. Let’s call it “gmapping.launch”. Let’s say the laser scan topic is called “/my_scan”.
|
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 |
<launch> <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping"> <rosparam> odom_frame: odom base_frame: base_link map_frame: map map_update_interval: 0.5 # Publish new map maxUrange: 5.5 # Should be just less than sensor range maxRange: 6.1 # Should be just greater than sensor range particles: 100 # Increased from 80 # Update frequencies linearUpdate: 0.3 angularUpdate: 0.5 temporalUpdate: 2.0 resampleThreshold: 0.5 # Initial Map Size xmin: -100.0 ymin: -100.0 xmax: 100.0 ymax: 100.0 delta: 0.05 # All default sigma: 0.05 kernelSize: 1 lstep: 0.05 astep: 0.05 iterations: 5 lsigma: 0.075 ogain: 3.0 lskip: 0 llsamplerange: 0.01 llsamplestep: 0.01 lasamplerange: 0.005 lasamplestep: 0.005 </rosparam> <remap from="scan" to="my_scan"/> </node> </launch> |
Step 4: Create a launch file to run the move_base node. Let’s call it “move_base.launch”:
|
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 |
<launch> <arg name="no_static_map" default="false"/> <arg name="base_global_planner" default="navfn/NavfnROS"/> <arg name="base_local_planner" default="dwa_local_planner/DWAPlannerROS"/> <!-- <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> --> <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen"> <param name="base_global_planner" value="$(arg base_global_planner)"/> <param name="base_local_planner" value="$(arg base_local_planner)"/> <rosparam file="$(find husky_navigation)/config/planner.yaml" command="load"/> <!-- observation sources located in costmap_common.yaml --> <rosparam file="$(find husky_navigation)/config/costmap_common.yaml" command="load" ns="global_costmap" /> <rosparam file="$(find husky_navigation)/config/costmap_common.yaml" command="load" ns="local_costmap" /> <!-- local costmap, needs size --> <rosparam file="$(find husky_navigation)/config/costmap_local.yaml" command="load" ns="local_costmap" /> <param name="local_costmap/width" value="10.0"/> <param name="local_costmap/height" value="10.0"/> <!-- static global costmap, static map provides size --> <rosparam file="$(find husky_navigation)/config/costmap_global_static.yaml" command="load" ns="global_costmap" unless="$(arg no_static_map)"/> <!-- global costmap with laser, for odom_navigation_demo --> <rosparam file="$(find husky_navigation)/config/costmap_global_laser.yaml" command="load" ns="global_costmap" if="$(arg no_static_map)"/> <param name="global_costmap/width" value="100.0" if="$(arg no_static_map)"/> <param name="global_costmap/height" value="100.0" if="$(arg no_static_map)"/> </node> </launch> |
Step 5: Create a launch file to run the frontier_exploration server and client nodes. Let’s call the launch file “exploration.launch”:
|
1 2 3 4 5 6 7 8 9 10 11 12 13 14 |
<launch> <node pkg="frontier_exploration" type="explore_client" name="explore_client" output="screen"/> <node pkg="frontier_exploration" type="explore_server" name="explore_server" output="screen"> <param name="frequency" value="1.0"/> <!-- Should be less than sensor range --> <param name="goal_aliasing" value="2.0"/> <rosparam file="$(find husky_navigation)/config/costmap_common.yaml" command="load" ns="explore_costmap" /> <rosparam file="$(find husky_navigation)/config/costmap_exploration.yaml" command="load" ns="explore_costmap" /> </node> </launch> |
Step 6: Create a launch file to launch all the launch files previously created. Let’s call this launch file “exploration_demo.launch”:
|
1 2 3 4 5 6 7 8 9 10 11 12 |
<launch> <!--- Run gmapping --> <include file="$(find husky_navigation)/launch/gmapping.launch" /> <!--- Run Move Base --> <include file="$(find husky_navigation)/launch/move_base.launch" /> <!-- Run Frontier Exploration --> <include file="$(find husky_navigation)/launch/exploration.launch" /> </launch> |
Running the GMapping SLAM by using the frontier_exploration
Step 1: Run your robot or your robot simulator.
Step 2: Run Rviz to visualize the SLAM process. Enable the “Navigation” visualizer.
Step 3: Prescribe a closed polygon on Rviz using “Point” tool. Observe the terminal for instructions.
Step 4: Observe the map creation on Rviz during the SLAM process. Also observe the terminal to see the feedback messages.
Step 5: Save the created map:
|
1 |
rosrun map_server map_saver -f <filename> |

Is the use of frontier exploration in ROS for autonomous SLAM challenging traditional methods and pushing the boundaries of robotic mapping and navigation capabilities?