Keywords

1 Introduction

Mobile robot path planning is a hot research area. Indeed, the robot should have the ability to autonomously generate collision free path between any two positions in its environment. The path planning problem can be formulated as follows: given a mobile robot and a model of the environment, find the optimal path between a start position and a final position without colliding with obstacles. Designing an efficient path planning algorithm is an essential issue in mobile robot navigation since path quality influences the efficiency of the entire application. The constructed path must satisfy a set of optimization criteria including the traveled distance, the processing time, and the energy consumption.

In the literature, the path planning problem is influenced by two factors: (1) the environment, which can be static or dynamic, (2) the knowledge that the robot has about the environment; if the robot has a complete knowledge about the environment, this problem is known as global path planning. On the other hand, if the robot has an incomplete knowledge, this problem is classified as local path planning.

The navigation stack of the Robot Operating System (ROS) open-source middleware incorporates both global and local path planners to support ROS-enabled robot navigation. However, only basic algorithms are defined for the global path planner including Dijkstra, A*, and carrot planners.

In this tutorial, we present the steps for integrating a new global path planner into the ROS navigation system. The new path planner is based on a relaxed version of the A* (RA*) algorithm, and it can be found in [1]. Also, we compare the performance of the RA* with ROS default planner.

The rest of this tutorial is organized as follow.

  • Section 2 introduces ROS and its navigation system.

  • Section 3 introduces the relaxed A* algorithm.

  • In Sect. 4, we present the steps of integrating a new global path planner into the ROS navigation system.

  • Section 5 presents the ROS environment configuration.

  • In Sect. 6, we conduct the experimental evaluation study to compare the performance of RA* and ROS default planner.

2 ROS

ROS (Robot Operating System) [2] has been developed by Willow Garage [3] and Stanford University as a part of STAIR [4] project, as a free and open-source robotic middleware for the large-scale development of complex robotic systems.

ROS acts as a meta-operating system for robots as it provides hardware abstraction, low-level device control, inter-processes message-passing and package management. It also provides tools and libraries for obtaining, building, writing, and running code across multiple computers. The main advantage of ROS is that it allows manipulating sensor data of the robot as a labeled abstract data stream, called topic, without having to deal with hardware drivers. This makes the programming of robots much easier for software developers as they do not have to deal with hardware drivers and interfaces. Also, ROS provides many high-level applications such as arm controllers, face tracking, mapping, localization, and path planning. This allow the researchers to focus on specific research problems rather than on implementing the many necessary, but unrelated parts of the system.

Mobile robot navigation generally requires solutions for three different problems: mapping, localization, and path planning. In ROS, the Navigation Stack plays such a role to integrate together all the functions necessary for autonomous navigation.

Fig. 1
figure 1

ROS navigation stack [2]

2.1 ROS Navigation Stack

In order to achieve the navigation task, the Navigation Stack [5] is used to integrate the mapping, localization, and path planning together. It takes in information from odometry, sensor streams, and the goal position to produce safe velocity commands and send it to the mobile base (Fig. 1). The odometry comes through nav_msgs/Odometry message over ROS which stores an estimate of the position and velocity of a robot in free space to determine the robot’s location. The sensor information comes through either sensor_msgs/LaserScan or sensor_msgs/PointCloud messages over ROS to avoid any obstacles. The goal is sent to the navigation stack by geometry_msgs/PoseStamped message. The navigation stack sends the velocity commands through geometry_msgs/Twist message on /cmd_vel topic. The Twist message composed of two sub-messages:

figure a

linear sub-message is used for the x, y and z linear velocity components in meters per second and angular sub-message is used for the x, y and z angular velocity components in radians per second. For example the following Twist message:

figure b

will tell the robot to move with a speed of 0.2 m/s straight ahead. The base controller is responsible for converting Twist messages to “motor signals”which will actually move the robot’s wheels [6].

The navigation stack does not require a prior static map to start with. Actually it could be initialized with or without a map. When initialized without a prior map, the robot will know about the obstacles detected by its sensors only and will be able to avoid the seen obstacles so far. For the unknown areas, the robot will generate an optimistic global path which may hit unseen obstacles. The robot will be able to re-plan its path when it receives more information by the sensors about these unknown areas. Instead, when the navigation stack initialized with a static map for the environment, the robot will be able to generate an informed plans to its goal using the map as prior obstacle information. Starting with a prior map will have significant benefits on the performance [5].

To build a map using ROS, ROS provides a wrapper for OpenSlam’s Gmapping [7]. A particle filter-based mapping approach [8] is used by the gmapping package to build an occupancy grid map. Then a package named map_server could be used to save that map. The maps are stored in a pair of files: YAML file and image file. The YAML file describes the map meta-data, and names the image file. The image file encodes the occupancy data. The localization part is solved in the amcl package using an Adaptive Monte Carlo Localization [9] which is also based on particle filters. It is used to track the position of a robot against a known map. The path planning part is performed in the move_base package, and is divided into global and local planning modules which is a common strategy to deal with the complex planning problem.

The global path planner searches for a shortest path to the goal and the local path planner (also called the controller), incorporating current sensor readings, issues the actual commands to follow the global path while avoiding obstacles. More details about the global and local planners in ROS can be found in the next sections.

The \(move\_base\) package also maintains two costmaps, \(global\_costmap\) and \(local\_costmap\) to be used with the global and local planners respectively. The costmap used to store and maintain information in the form of occupancy grid about the obstacles in the environment and where the robot should navigate. The costmap initialized with prior static map if available, then it will be updated using sensor data to maintain the information about obstacles in the world. Besides that, the \(move\_base\) may optionally perform some previously defined recovery behaviors (Fig. 2) when it fails to find a valid plan.

Fig. 2
figure 2

Recovery behaviors [2]

One reason of failure, is when the robot find itself surrounded with obstacles and cannot find a way to its goal. The recovery behaviors will be performed in some order (defined by the user), and after performing one recovery, the \(move\_base\) will try to find a valid plan, if it succeeds, it will proceed its normal operation. Otherwise if it fails, it will perform the next recovery behavior. If it fails after performing all the recovery behaviors, the goal will be considered infeasible, and it will be aborted. The default recovery behaviors order is presented in Fig. 2 and it is in increasingly aggressive order to attempt to clear out the robot space. First recovery behavior is clearing all the obstacles outside a specific area from the robot’s map. Next, an in-place rotation will be performed if possible to clear the space. Next, in case this too fails, more aggressively clearing for the map will be performed, to remove all the obstacles outside of the rectangular area in which the robot can make an in-place rotation. Next, another in-place rotation will be performed. If all this fails, the goal will be aborted.

Therefore, in each execution cycle of the \(move\_base\), one of three main states should be performed:

  • Planning state: run the global path planner.

  • Controlling state: run the local path planner and move the robot.

  • Clearing state: run recovery behavior in case the robot stuck.

There are some predefined parameters in ROS navigation stack that are used to control the execution of the states, which are:

  • \(planner\_frequency\): to determine how often the global path planner should be called, and is expressed in Hz. When it is set to zero, the global plan will be computed only once for each goal received.

  • \(controller\_frequency\): to determine how often the local path planner or controller should be called, and also expressed in Hz.

For any global or local planner or recovery behavior to be used with the \(move\_base\) it must be first adhere to some interfaces defined in \(nav\_core\) package, which contains key interfaces for the navigation stack, then it must be added as a plugin to ROS. We developed a tutorial on how to add a new global planner as a plugin to ROS navigation stack, available at [10] and [11].

2.1.1 Global Planner

The global path planner in ROS operates on the \(global\_costmap\), which generally initialized from a prior static map, then it could be updated frequently based on the value of \(update\_frequency\) parameter. The global path planner is responsible for generating a long-term plan from the start or current position to the goal position before the robot starts moving. It will be seeded with the costmap, and the start and goal positions. These start and goal positions are expressed by their x and y coordinates. A grid-based global planner that can use Dijkstra’s algorithm [12] or A* algorithm to compute shortest collision free path for a robot is obtained in global_planner package. Also, ROS provide another global planner named carrot_planner, which is a simple planner that attempts to move the robot as close to its goal as possible even when that goal is in an obstacle. The current implementation of the global planner in ROS assumes a circular-shape robot. This results in generating an optimistic path for the actual robot footprint, which may be infeasible path. Besides that, the global planner ignores kinematic and acceleration constraints of the robot, so the generated path could be dynamically infeasible.

2.1.2 Local Planner

The local path planner or the controller in ROS operates on the \(local\_costmap\), which only uses local sensor information to build an obstacle map and dynamically updated with sensor data. It takes the generated plan from the global planner, and it will try to follow it as close as possible considering the kinematics and dynamics of the robot as well as any moving obstacles information in the \(local\_costmap\). ROS provides implementation of two local path planning algorithms namely the Trajectory Rollout [13] and the Dynamic Window Approach (DWA) [14] in the package \(base\_local\_planner\). Both algorithms have the same idea to first discretely sampled the control space then to perform forward simulation, and the selection among potential commands. The two algorithm differ in how they sample the robot’s control space.

After the global plan passed to the controller, the controller will produce velocity commands to send to a mobile base. For each control cycle, \(the\ controller\) will try to process part from global path (determined by the size of the \(local\_costmap\)).

First, the controller will sampled the control space of the robot discretely. The number of the samples will be specified by the controller parameters \(vx\_samples\) and \(vtheta\_samples\) (more details about the parameters can be found in the next section). Then, the controller will perform a simulation in advance for each one of those velocity samples from the current place of the robot to foresee the situation from applying each sample for amount of time (this time will be specified in the parameter \(sim\_time\)). Then, the controller will evaluate each resultant path from the simulation and will exclude any path having collisions with obstacles. For the evaluation, the controller will incorporates the following metrics: distance from obstacles, distance to the goal position, distance from the global plan and robot speed. Finally, the controller will send the velocity command of the highest-scoring path to the mobile base to execute it.

The “Map Grid” is used to evaluate and score the velocities. For each control cycle, the controller will create a grid around the robot (the grid size determined by the size of the \(local\_costmap\)), and the global path will be mapped onto this area. Then each grid cell will receive a distance value. The cells containing path points and the goal will be marked with 0. Then each other grid cell will be marked with its manhattan distance from nearest zero grid by a propagation algorithm. This “Map Grid” is then used in the evaluation and scoring of the velocities. As the “Map Grid” will cover small area from global path each time, the goal position often will lie outside that area. So in that case the first path point inside the area having a consecutive point outside the area will be considered as “local goal”, and the distance from that local goal will be considered when scoring trajectories for distance to goal.

3 Relaxed A*

RA* is a time linear relaxed version of A*. It is proposed to solve the path planning problem for large scale grid maps. The objective of RA* consists of finding optimal or near optimal solutions with small gaps, but at much smaller execution times than traditional A*. The core idea consists of exploiting the grid-map structure to establish an accurate approximation of the optimal path, without visiting any cell more than once.

In fact, in A* the exact cost g(n) of a node n may be computed many times; namely, it is computed for each path reaching node n from the start position. However, in the RA* algorithm g(n) is approximated by the cost of the minimum-move path from the start cell to the cell associated to node n.

In order to obtain the relaxed version RA*, some instructions of A*, that are time consuming with relatively low gain in terms of solution quality, are removed. In fact, a node is processed only once in RA*, so there is no need to use the closed set of the A* algorithm. Moreover, in order to save time and memory, we do not keep track of the previous node at each expanded node. Instead, after reaching the goal, the path can be reconstructed, from goal to start by selecting, at each step, the neighbor having the minimum g(n) value. Also, it is useless to compare the g(n) of each neighbor to the g(n) of the current node n as the first calculated g(n) is considered definite. Finally, it is not needed to check whether the neighbor of the current node is in the open list. In fact, if its g(n) value is infinite, it means that it has not been processed yet, and hence is not in the open list. The RA* algorithm is presented in Algorithm 1.

figure c

Both terms g(n) and h(n) of the evaluation function of the RA* algorithm are not exact, then there is no guaranty to find an optimal solution.

4 Integration Steps

In this section, we present the steps of integrating a new path planner into ROS. The integration has two main steps: (1) writing the path planner class, and (2) deploying it as a plugin. Following, we describe them in details.

4.1 Writing the Path Planner Class

As mentioned before, to make a new global planner work with ROS, it must first adhere to the interfaces defined in nav_core package. A similar example can be found in the carrot_planner.h [15] as a reference. All the methods defined in nav_core::BaseGlobalPlanner class must be overridden by the new global path planner. For this, you need to create a header file, that we will call in our case, RAstar_ros.h

figure d

Now, we will explain the different parts of the header file.

figure e

It is necessary to include core ROS libraries needed for path planner. The headers:

figure f

are needed to use the costmap_2d::Costmap2D class that will be used by the path planner as input map. This map will be accessed automatically by the path planner class when defined as a plugin. There is no need to subscribe to costmap2d to get the cost map from ROS.

figure g

is used to import the interface \(nav\_core::BaseGlobalPlanner\), which the plugin must adhere to.

figure h

It is a good practice, although not necessary, to define namespace for your class. Here, we define the namespace as RAstar_planner for the class RAstarPlannerROS. The namespace is used to define a full reference to the class, as RAstar_planner::RAstarPlannerROS. The class RAstarPlannerROS is then defined and inherits from the interface nav_core::BaseGlobalPlanner. All methods defined in nav_core::BaseGlobalPlanner must be overridden by the new class RAstarPlannerROS.

figure i

Is the default constructor which initializes the planner attributes with default values.

figure j

This constructor is used to initialize the costmap, that is the map that will be used for planning (costmap_ros), and the name of the planner (name).

figure k

Is an initialization function for the BaseGlobalPlanner, which initializes the costmap, that is the map that will be used for planning (costmap_ros), and the name of the planner (name).

The initialize method for RA* is implemented as follows:

figure l

For the particular case of the carrot_planner, the initialize method is implemented as follows:

figure m
figure n

Then, the method bool makePlan must be overridden. The final plan will be stored in the parameter std::vector \(<\) geometry_msgs::PoseStamped \(>\) & plan of the method. This plan will be automatically published through the plugin as a topic. An implementation of the makePlan method of the carrot_planner can be found in [16] as a reference.

Class Implementation In what follows, we present the main issues to be considered in the implementation of a global planner as plugin. The complete source code of the RA* planner can be found in [1]. Here is a minimum code implementation of the RA* global path planner (RAstar_ros.cpp).

figure o

The constructors can be implemented with respect to the planner requirements and specification. There are few important things to consider:

  • Register the planner as BaseGlobalPlanner plugin: this is done through the instruction:

    figure p

    For this it is necessary to include the library:

    figure q
  • The implementation of the makePlan() method: The start and goal parameters are used to get initial location and target location, respectively. For RA* path planners, the start and goal first will be converted from x and y coordinates to cell indices. Then, those indices will be passed to the RA* planner. When the planner finish its execution, it will return the computed path. Finally, the path cells will be converted to x and y coordinates, then inserted into the plan vector (plan.push_back(pose)) in the for loop. This planned path will then be sent to the move_base global planner module which will publish it through the ROS topic nav_msgs/Path, which will then be received by the local planner module.

Now that your global planner class is done, you are ready for the second step, that is creating the plugin for the global planner to integrate it in the global planner module nav_core::BaseGlobalPlanner of the move_base package.

Compilation To compile the RA* global planner library created above, it must be added (with all of its dependencies if any) to the CMakeLists.txt. This is the code to be added:

figure r

Then, in a terminal run catkin_make in your catkin workspace directory to generate the binary files. This will create the library file in the lib directory ~/catkin_ws/devel/lib/librelaxed_astar_lib. Observe that “lib” is appended to the library name relaxed_astar_lib declared in the CMakeLists.txt

4.2 Writing Your Plugin

Basically, it is important to follow all the steps required to create a new plugin as explained in the plugin description page [17]. There are five steps:

Plugin Registration First, you need to register your global planner class as plugin by exporting it. In order to allow a class to be dynamically loaded, it must be marked as an exported class. This is done through the special macro PLUGINLIB_EXPORT_CLASS. This macro can be put into any source (.cpp) file that composes the plugin library, but is usually put at the end of the .cpp file for the exported class. This was already done above in RAstar_ros.cpp with the instruction

figure s

This will make the class RAstar_planner::RAstarPlannerROS registered as plugin for nav_core::BaseGlobalPlanner of the move_base.

Plugin Description File The second step consists in describing the plugin in a description file. The plugin description file is an XML file that serves to store all the important information about a plugin in a machine readable format. It contains information about the library the plugin is in, the name of the plugin, the type of the plugin, etc. In our case of global planner, you need to create a new file and save it in certain location in your package and give it a name, for example relaxed_astar_planner_plugin.xml. The content of the plugin description file (relaxed_astar_planner_plugin.xml), would look like this:

figure t

In the first line:

figure u

we specify the path to the plugin library. In this case, the path is lib/librelaxed_astar_lib, where lib is a folder in the directory ~/catkin_ws/devel/ (see Compilation section above).

figure v

Here we first specify the name of the global_planner plugin that we will use later in move_base launch file as parameter that specifies the global planner to be used in nav_core. It is typically to use the namespace (RAstar_planner) followed by a slash then the name of the class (RAstarPlannerROS) to specify the name of plugin. If you do not specify the name, then the name will be equal to the type, which is in this case will be RAstar_planner::RAstarPlannerROS. It recommended to specify the name to avoid confusion.

The type specifies the name of the class that implements the plugin which is in our case RAstar_planner::RAstarPlannerROS, and the base_class_type specifies the name of the base class that implements the plugin which is in our case nav_core::BaseGlobalPlanner.

figure w

The \(<\) description \(>\) tag provides a brief description about the plugin. For a detailed description of plugin description files and their associated tags/attributes please see the documentation in [18].

Why Do We Need This File? We need this file in addition to the code macro to allow the ROS system to automatically discover, load, and reason about plugins. The plugin description file also holds important information, like a description of the plugin, that doesn’t fit well in the macro.

Registering Plugin with ROS Package System In order for pluginlib to query all available plugins on a system across all ROS packages, each package must explicitly specify the plugins it exports and which package libraries contain those plugins. A plugin provider must point to its plugin description file in its package.xml inside the export tag block. Note, if you have other exports they all must go in the same export field. In our RA* global planner example, the relevant lines would look as follows:

figure x

The ${prefix}/ will automatically determine the full path to the file relaxed_astar_planner_plugin.xml. For a detailed discussion of exporting a plugin, interested readers may refer to [19].

Important Note: In order for the above export command to work properly, the providing package must depend directly on the package containing the plugin interface, which is \(nav\_core\) in the case of global planner. So, the \(relaxed\_astar\) package must have the line below in its relaxed_astar/package.xml:

figure y

This will tell the compiler about the dependency on the nav_core package.

4.2.1 Querying ROS Package System for Available Plugins

One can query the ROS package system via rospack to see which plugins are available by any given package. For example:

figure z

This will return all plugins exported from the nav_core package. Here is an example of execution:

figure aa

Observe that our plugin is now available under the package relaxed_astar and is specified in the file /home/turtlebot/catkin_ws/src/relaxed_astar/relaxed_astar_planner_plugin.xml. You can also observe the other plugins already existing in nav_core package, including carrot_planner/CarrotPlanner and navfn, which implements the Dijkstra algorithm.

Now, your plugin is ready to use.

4.3 Running the Plugin

There are a few steps to follow to run your planner in turtlebot. First, you need to copy the package that contains your global planner (in our case relaxed_astar) into the catkin workspace of your Turtlebot (e.g. catkin_ws). Then, you need to run catkin_make to export your plugin to your turtlebot ROS environment.

Second, you need to make some modification to move_base configuration to specify the new planner to be used. For this, follow these steps:

  1. 1.

    In Hydro, go to this folder /opt/ros/hydro/share/turtlebot_navigation/launch/includes

    figure ab
  2. 2.

    Open the file move_base.launch.xml (you may need sudo to open and be able to save) and add the new planner as parameters of the global planner, as follows:

    figure ac

    Save and close the move_base.launch.xml. Note that the name of the planner is RAstar_planner/RAstarPlannerROS the same specified in relaxed_astar_planner_plugin.xml. Now, you are ready to use your new planner.

  3. 3.

    You must now bringup your turtlebot. You need to launch minimal.launch, 3dsensor.launch, amcl.launch.xml and move_base.launch.xml. Here is an example of launch file that can be used for this purpose.

    figure ad

    Note that changes made in the file move_base.launch.xml will now be considered when you bring-up your turtlebot with this launch file.

4.4 Testing the Planner with RVIZ

After you bringup your turtlebot, you can launch the rviz using this command (in new terminal).

figure ae

5 ROS Environment Configuration

One important step before using the planners is tuning the controller parameters as they have a big impact on the performance. The controller parameters can be categorized into several groups based on what they control such as: robot configuration, goal tolerance, forward simulation, trajectory scoring, oscillation prevention, and global plan.

The robot configuration parameters are used to specify the robot acceleration information in addition to the minimum and maximum velocities allowed to the robot. We are working with the Turtlebot robot, and we used the default parameters from \(turtlebot\_navigation\) package. The configuration parameters are set as follow: \(acc\_lim\_x=0.5,\) \(acc\_lim\_theta=1,\) \(max\_vel\_x=0.3,\) \(min\_vel\_x=0.1,\) \(max\_vel\_theta=1\) \(min\_vel\_theta=-1\) \(min\_in\_place\_vel\_theta=0.6\).

The goal tolerance parameters define how close to the goal we can get. \(xy\_goal\_tolerance\) represents the tolerance in meters in the x and y distance and should not be less than the map resolution or it will make the robot spin in place indefinitely without reaching the goal, so we set it to 0.1. \(yaw\_goal\_tolerance\) represents the tolerance in radians in yaw/rotation. Setting this tolerance very small may cause the robot to oscillate near the goal. We set this parameter very high to 6.26 as we do not care about the robot orientation.

In the forward simulation category, the main parameters are: \(sim\_time\), \(vx\_samples\), \(vtheta\_samples\), and \(controller\_frequency\). The \(sim\_time\) represents the amount of time (in seconds) to forward-simulate trajectories, and we set it to 4.0. The \(vx\_samples\) and \(vtheta\_samples\) represent the number of samples to use when exploring the x velocity space and the theta velocity space respectively. They should be set depending on the processing power available, and we use the value recommended in ROS web-site for them. So, we set 8 to the \(vx\_samples\) and 20 to \(vtheta\_samples\). The \(controller\_frequency\) represents the frequency at which this controller will be called. Setting this parameter a value too high can overload the CPU. Setting it to 2 work fine with our planners.

The trajectory scoring parameters are used to evaluate the possible velocities to the local planner. The three main parameters on this category are: \(pdist\_scale\), \(gdist\_scale\), and \(occdist\_scale\). The \(pdist\_scale\) represents the weight for how much the controller should stay close to the global planner path. The \(gdist\_scale\) represents the weight for how much the controller should attempt to reach its goal by whatever path necessary. Increasing this parameter will give the local planner more freedom in choosing its path away from the global path. The \(occdist\_scale\) represents the weight for how much the controller should attempt to avoid obstacles. Because the planners may generate paths very close to the obstacles or dynamically not feasible, we set the \(pdist\_scale=0.1\), \(gdist\_scale=0.8\) and \(occdist\_scale=0.3\) when testing our planners. Another parameter named dwa is used to specify whether to use the DWA when setting it to true, or use the Trajectory Rollout when setting it to false. We set it to true because the DWA is computationally less expensive than the Trajectory Rollout.

6 Experimental Validation

For the experimental study using ROS, we have chosen the realistic Willow Garage map (Fig. 3), with dimensions 584 * 526 cells and a resolution 0.1 m/cel. In the map, the white color represents the free area, the black color represents the obstacles, and the grey color represents unknown area.

Fig. 3
figure 3

Willow Garage map

Three performance metrics are considered to evaluate the global planners: (1) \(the\ path\ length\), it represents the length of the shortest global path found by the planner, (2) \(the\ steps\), it is the number of the steps in the generated paths. (3) \(the \ execution \ time\), which represents the amount of time that the planner spend to find its best path.

To evaluate the planners, we consider two tours each with 10 random points. Figure 3 shows the points for one of the tours, where the red circle represents the start location, the blue circle is the goal location, and the green circles are the intermediate waypoints. We run each planner 30 times for each tour. Figures 4, 5, 6 and 7 show the global plans for that tour generated by the RA*, ROS-A*, and ROS-Dijkstra for grid path and gradient descent method respectively.

Fig. 4
figure 4

RA* planner

Fig. 5
figure 5

ROS A* (grid path)

Fig. 6
figure 6

ROS Dijkstra (grid path)

Fig. 7
figure 7

ROS Dijkstra (gradient descent)

Tables 1 and 2 shows the path length and the execution time of the planners for the complete tour.

Table 1 Execution time in (microseconds) and path length in (meters) for tour 1
Table 2 Execution time in (microseconds) and path length in (meters) for tour 2

The ROS-Dijkstra with gradient descent method generates paths with more steps but little shorter in length than A* paths, this is because it has smaller granularity (more fine-grain exploration), so it has more freedom in the movements and more able to take smaller steps.

Fig. 8
figure 8

Detailed execution time for tour 1

Fig. 9
figure 9

Detailed execution time for tour 2

Other planners work at cell level (grid path), so they consider each cell as a single point, and they have to pass the whole cell in each step. As the resolution of the map is 10 cm, so the distance in each step is at least 10 cm. Comparing the execution time, the RA*, extremely superior the other planners in all simulated cases. Using RA*, the execution time was reduced by more than 78 % from the ROS-A*. Figures 8 and 9 shows the average execution time for 30 run between each two points from the tour.