Next Article in Journal
Optimal Inequalities for Hemi-Slant Riemannian Submersions
Next Article in Special Issue
Control of a Hydraulic Generator Regulating System Using Chebyshev-Neural-Network-Based Non-Singular Fast Terminal Sliding Mode Method
Previous Article in Journal
Recovery Analysis and Maintenance Priority of Metro Networks Based on Importance Measure
Previous Article in Special Issue
Collision Avoidance Problem of Ellipsoid Motion
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Dynamic Path Planning for the Differential Drive Mobile Robot Based on Online Metaheuristic Optimization

by
Alejandro Rodríguez-Molina
1,*,
Axel Herroz-Herrera
1,
Mario Aldape-Pérez
2,*,
Geovanni Flores-Caballero
3 and
Jarvin Alberto Antón-Vargas
4
1
Tecnológico Nacional de México/IT de Tlalnepantla, Research and Postgraduate Division, Tlalnepantla de Baz 54070, Mexico
2
Instituto Politécnico Nacional, CIDETEC, Computational Intelligence Laboratory (CIL), Ciudad de México 07700, Mexico
3
División Tecnológica de Diseño, Universidad Aeronáutica en Querétaro, Querétaro 76278, Mexico
4
Department of Computer Science, Universidad de Sancti Spíritus “José Martí Pérez”, Sancti Spíritus 60100, Provincia de Sancti Spíritus, Cuba
*
Authors to whom correspondence should be addressed.
Submission received: 21 September 2022 / Revised: 17 October 2022 / Accepted: 23 October 2022 / Published: 27 October 2022

Abstract

:
Mobile robots are relevant dynamic systems in recent applications. Path planning is an essential task for these robots since it allows them to move from one location to another safely and at an affordable cost. Path planning has been studied extensively for static scenarios. However, when the scenarios are dynamic, research is limited due to the complexity and high cost of continuously re-planning the robot’s movements to ensure its safety. This paper proposes a new, simple, reliable, and affordable method to plan safe and optimized paths for differential mobile robots in dynamic scenarios. The method is based on the online re-optimization of the static parameters in the state-of-the-art deterministic path planner Bug0. Due to the complexity of the dynamic path planning problem, a metaheuristic optimization approach is adopted. This approach utilizes metaheuristics from evolutionary computation and swarm intelligence to find the Bug0 parameters when the mobile robot is approaching an obstacle. The proposal is tested in simulation, and well-known metaheuristic methods are compared, including Differential Evolution (DE), the Genetic Algorithm (GA), and Particle Swarm Optimization (PSO). The dynamic planner based on PSO generates paths with the best performances. In addition, the results of the PSO-based planner are compared with different Bug0 configurations, and the former is shown to be significantly better.

1. Introduction

The use of mobile robots is now widespread in a number of applications, including the transport of people and goods [1,2], border surveillance, rescue and monitoring [3,4,5], health and rehabilitation [6], and even entertainment [7]. The growth of this type of robot can be attributed to its ability to operate in extended environments compared to the classic fixed-base robots [8].
Mobile robots can be distinguished by the environment in which they operate (i.e., terrestrial, aquatic, aerial, or hybrid), the type of element that produces their motion (e.g., legs, wheels, caterpillars, propellers, etc.), or the ability to change direction (unidirectional, multidirectional, or omnidirectional) [9]. Among the great diversity of mobile robots, the differential drive one stands out for its ability to move on a plane with only two wheels, the ease with which its movement can be described, the simplicity of its control, its relative low cost, and its universality as it is present in a wide variety of applications [10].
One of the main problems faced by the differential mobile robot and, in general, by any type of mobile robot is path planning [11]. Without loss of generality, path planning refers to the task of getting the mobile robot from an initial configuration (this may include its position and orientation in space) to a final one safely (i.e., avoiding obstacles or threats) and with the least possible cost (e.g., using the least energy, traveling the shortest distance, or with the greatest speed) [12].
Path planning, by its nature, is a complex task [9]. Depending on the features of the robot and its operating environment, this task can be further complicated. Here, it is worth distinguishing two cases: (1) When the operating environment includes static obstacles (i.e., when the obstacles maintain their original configuration over time) and (2) when these obstacles are dynamic (i.e., when the obstacles are moving).
Case (1) has been widely studied in the specialized literature from different approaches. This has given rise to well-known and currently used path planners. In [13], four main types of planners are distinguished. Among these are reactive-computing-based, which can plan the next maneuver quickly and continuously as they receive information from the operating environment. Relevant planners include Bug algorithms [14] and artificial potential fields [15]. For their part, soft-computing-based planners use soft-computing algorithms to approximate paths that meet certain performance criteria. In this field, evolutionary computation and swarm intelligence algorithms [16], neural networks [17], and fuzzy logic [18] stand out. On the other hand, C-space-search-based methods discretize the operation space to reduce the number of possible paths and make planning more efficient. The A* [19] and Rapidly Random Tree (RRT) [20] algorithms are representative of this category. Finally, in the Optimal-Control-Based methods, the path is the solution to the optimal control problem [21].
As for case (2), it adds difficulty to the planning problem inherent to dynamic obstacles. In this case, the methods conceived to solve the path planning problem considering case (1) are not sufficiently effective and require additional mechanisms to handle the environment’s dynamism [13]. Some approaches to handling case (2) that have been successfully tested consist of hybridization of different path planners [22], continuous re-planning of paths as soon as a change in the operating environment is detected [23], or inclusion of new operators in existing planning methods [24]. Thus, many of the planners proposed to date for case (2) are very sophisticated and require advanced theoretical and practical tools to be implemented. Some of these have high computational costs that may be unfeasible, and in many cases, their operation may be limited to conditions that are difficult to meet in practice.
Some recent works regarding cases (1) and (2) are described next. The work in [25] proposes a minimum-time path-planning approach for mobile robots in dynamic environments. For this, the authors establish an optimization problem to find the path points that minimize the realization time, produce a valid speed profile, and avoid collisions. The problem is solved through the Resilient Propagation algorithm periodically, and the resulting paths reduce the number of collisions and time in a simulated soccer game. In [26], an improved variant of the RRT is proposed to handle static scenarios with a mobile robot. The new proposal reduces the complexity of the search trees of the original RRT and produces suitable paths for realistic environments. The research in [27] performs the mobile robot path planning using a pseudo-spectral method to solve an optimal control problem. That method discretizes the path planning problem to transform it into a nonlinear optimization one. The solution to the above problem contains global polynomial approximations of the path for static scenarios. Similarly, the work in [28] transforms the optimal control problem into a nonlinear optimization one and then solves it through the nonlinear trapezoidal collocation programming method. The obtained paths adequately avoid static obstacles and have a reduced length. A multi-agent version of the A-heuristic, a C-space-search algorithm, is proposed in [29] to reduce the time in computing feasible paths for mobile robots in static and dynamic scenarios. A hybrid Genetic Algorithm (GA) is proposed in [30] to solve the path optimization problem with static obstacles. The problem considers the minimization of the path length defined in terms of Bezier curves. As a result, the GA obtains smooth paths for mobile robots. A variant of GA is also used in [31] to solve the path planning problem in dynamic scenarios, this time through a multi-objective optimization approach. The problem consists of finding the best motion command that improves the goal reachability, increases the path smoothness, reduces the realization time, and guarantees the robot’s safety. In [32], the path planning for a mobile robot is performed over the CG-Space, a space conformed by all gravity center positions of the robot considering different terrains. Different approaches, including reactive computing, C-space search, and soft computing, are considered to solve the derived path planning problem. The approach from soft computing based on the Particle Swarm Optimization (PSO) algorithm obtains better paths in terms of smoothness and reduced length. Another work that utilizes soft computing in path planning for static and dynamic scenarios is [33]. In that paper, the grasshopper algorithm is complemented with a sensing system to solve the path optimization problem. The problem considers the maximization of the distance to the obstacles and the minimization of the distance to the goal. Finally, in [34], a soft computing algorithm, the variable-length vector Differential Evolution (DE), is proposed to solve the path planning optimization problem for robots considering static obstacles. In that work, the optimization problem is to find a variable number of points in the path that minimize the length and ensures obstacle avoidance. The obtained results are better than A* and an RRT variant.
As noted, a common thread in many recent works on path planning for mobile robots in static and dynamic environments is formulating an optimization problem. This may be because the desired path requirements can be expressed naturally and explicitly through mathematical language in an optimization problem. Most of the problems addressed in these works are complex due to their features, such as high non-linearity, non-continuity, or non-differentiability, induced by the mobile robot’s behavior or the scenarios’ dynamism. Due to these complications, previous works opt for approximate solution approaches to these problems, many based on soft computing techniques known as metaheuristics, which can provide outstanding results compared with other path-planning methods.
Metaheuristics are computational techniques that can provide high-performance approximate solutions to complex optimization problems at a reasonable computational cost without requiring them to meet specific features [35]. Most metaheuristics are soft computing methods derived from evolutionary computing and swarm intelligence [36], i.e., they are inspired by the behavior of natural systems or phenomena.
Based on the above, this work proposes a new, simple, reliable, and affordable method to plan safe and optimized paths for the differential mobile robot in dynamic scenarios. The method is based on a simple and efficient Bug-type planner known as Bug0 [13]. This proposal re-optimizes the Bug planner online through three well-known metaheuristics: Differential Evolution, the Genetic Algorithm, and Particle Swarm Optimization. This new planner is tested in simulation using a scenario with several moving obstacles and is compared to the original Bug0 algorithm with fixed parameters.
The rest of the paper is organized as follows. Section 2 describes the differential drive mobile robot. Section 3 introduces the features of deterministic path planners with a special focus on Bug methods and Bug0. The proposed dynamic path planner based on the online optimization of a Bug-type method through metaheuristics is developed in Section 4. The experimental details and results are discussed in Section 5. Conclusions are drawn in Section 6.

2. Differential Drive Mobile Robot

The differential drive mobile robot is a mechanical system with the ability to move in the plane X Y by using two identical wheels placed on the same axis of rotation. The orientation and position of this robot depend on the difference in the rotation speeds of the two wheels. The above configuration can be described by three generalized coordinates as seen in Figure 1. These coordinates include the position x, y of the robot on the plane, and the angular position θ measured concerning the axis X.

2.1. Kinematic Model

The kinematic model describes the robot’s motion in terms of the generalized coordinates and the input rotation speeds of the wheels without considering the forces or torques that produce the motion. This model can be utilized to simulate the behavior of the robot. To determine the kinematic model of the differential mobile robot, the geometrical elements that influence its positioning and orientation must be considered. These elements are the radius of the wheels r and the length of the axis separating them L. Thus, this model is derived below.
When both wheels rotate at given speeds, the robot platform travels with tangential velocity v, and rotates with angular speed ω and radius R around the Instantaneous Center of Rotation ( I C R ). Then, from Figure 1, it is easy to observe that:
x ˙ = v cos ( θ ) y ˙ = v sin ( θ ) θ ˙ = ω
where x ˙ = d x / d t and y ˙ = d y / d t are the components of the velocity v at X and Y, respectively, and θ ˙ = d θ / d t is the rotational speed of the robot, with t as the time.
Both v and ω in (1) can be considered as the inputs of the robot since they can be expressed in terms of the rotational speeds of the two wheels, as described next.
From Figure 1, the velocity v can be determined as:
v = R ω
Likewise, the tangential velocities v l and v r of the wheels can be expressed in terms of R, L, and ω as:
v l = R l ω = R L 2 ω v r = R r ω = R + L 2 ω
where R l and R r are the rotation radius of each wheel with respect to I C R .
Solving the equation system given in (3) for ω and R leads:
ω = v r v l L R = L 2 v l + v r v r v l
Substituting ω and R in (2) gives:
v = v r + v l 2
From (4) and (5), it is clear that v and ω depend on the tangential velocities of the wheels v l and v r . In turn, the above velocities can be determined if one knows the rotation speeds of the wheels ω l and ω r as v l = r ω l and v r = r ω r .

2.2. State-Space Kinematic Model

Simulating the differential mobile robot’s kinematic behavior requires defining the state concept first. The state of a system is a vector with a minimum set of variables that define its behavior for any instant of time. In the case of mechanical systems, including the differential mobile robot, the states that define their kinematic behavior can be given by the generalized coordinates. Therefore, the vector of states for this robot is:
z ( t ) = [ x ( t ) , y ( t ) , θ ( t ) ] T
Based on the above state vector, it is possible to define a state equation as follows:
z ˙ ( t ) = f ( z , u , t )
where z ( t ) is the state vector, u ( t ) includes the system inputs (these are v ( t ) and w ( t ) , which allow the differential robot to move), and t is the time.
Thus, the state equation can be obtained using the results from the previous kinematic analysis:
z ˙ = x ˙ y ˙ θ ˙ = v cos ( θ ) v sin ( θ ) ω

2.3. Dynamic Model

The differential robot’s dynamic model describes this system’s behavior in terms of its generalized coordinates and also considers the forces or torques that generate its motion. This model allows for more realistic simulations of the system compared to the kinematic model. The Euler–Lagrange approach, a generalization of Newton’s laws for mechanical systems that requires an analysis of energies [37], was used to obtain this model. This approach requires the formulation of the Lagrangian for mechanical systems:
L = K U
where K and U are, respectively, the system’s total kinetic and potential energies.
Based on the Lagrangian in (9), the equations of motion of a non-holonomic system such as the differential mobile robot can be calculated as [38]:
d d t L q ˙ i L q i = f i j = 1 m λ j a j i
where q i is the i-th generalized coordinate in q = [ x , y , θ ] T , and f i is its corresponding generalized input torque or force, m is the number of non-holonomic constraints on the robot’s motion, λ j is the Lagrange multiplier associated with each constraint, and a j i is the component of the motion constraint for the i-th generalized coordinate.
The total kinetic energy of the robot, due to its translational and rotational motions, can be calculated as:
K = 1 2 m x ˙ 2 + 1 2 m y ˙ 2 + 1 2 I z θ ˙ 2
where m is the mass of the robot and I z is its inertia tensor around the vertical rotation axis.
On the other hand, the potential energy of the mobile robot is U = 0 because it operates in the horizontal plane and is not affected by the acceleration of gravity on Earth.
To determine the robot’s generalized input forces and torques, it is worthwhile to look at Figure 2. As observed in the figure, the forces and torques that move the robot are F and τ θ . The components of these two elements for each generalized coordinate are:
f 1 = F cos ( θ ) = 1 r τ l + τ r cos ( θ )
f 2 = F sin ( θ ) = 1 r τ l + τ r sin ( θ )    
f 3 = τ θ = L 2 r τ r τ l    
where τ l and τ r are the torques of the right and left wheels, respectively, that generate the tangential forces F l = r τ l and F r = r τ r in Figure 2. The wheel torques are considered the system inputs.
At this point, it is important to note that the differential mobile robot has only one non-holonomic constraint (i.e., m = 1 ) that can be observed in Figure 2. That constraint refers to the fact that the robot cannot move laterally. For this constraint to be satisfied, the lateral velocities must be equal y ˙ l = y ˙ r , or else:
x ˙ sin ( θ ) + y ˙ cos ( θ ) = 0
in a matrix form:
A T q ˙ = 0
with A = [ a 11 , a 12 , a 13 ] T = [ sin ( θ ) , cos ( θ ) , 0 ] T .
Based on the above, the equations of motion in (10) can be expressed in the closed form observed in (17).
M q q ¨ = E q u A T q λ
where:
M q = m 0 0 0 m 0 0 0 I z
E q = 1 r cos θ cos θ sin θ sin θ L 2 L 2
u = [ τ l , τ r ] T
and λ is the Lagrange multiplier associated with the constraint on (15).

2.4. State-Space Dynamic Model

In the closed-form equation in (17), the system’s physical parameters (e.g., the mass m or the inertia J) can be measured or estimated in some way. However, the same cannot be said for the Lagrange multiplier λ . This variable can be eliminated if a state vector such as the following is chosen:
z ( t ) = [ x ( t ) , y ( t ) , θ ( t ) , v ( t ) , ω ( t ) ] T
Thus, the equation of state for the differential mobile robot is as follows:
z ˙ = f ( z , u , t ) = B ( z ) + C ( z ) u
with:
B ( z ) = [ v cos ( θ ) , v sin ( θ ) , ω , 0 , 0 ] T
C ( z ) = 0 0 0 1 m r 1 2 I z L r 0 0 0 1 m r 1 2 I z L r T
u = [ τ l , τ r ] T
The complete development of the above equation can be found at [39].

2.5. Robot Simulation

State equations such as (8) and (22) are ordinary differential equations whose independent variable is t. If an initial condition z 0 (i.e., an initial mobile configuration with an initial position x 0 , y 0 , and orientation θ 0 ) is imposed on these differential equations, initial value problems are obtained. When these problems are solved, e.g., through a numerical integration method, the result includes the robot’s predicted future states z ( t + d t ) after a short time interval d t when the input u ( t ) is considered. This prediction simulates the mobile robot for a given time window.

3. Deterministic Path Planning

Without losing generality, path planning is a task that allows taking a mobile robot from an initial configuration to a final one with the lowest possible risk and cost.
The above task is performed by a path planner. Deterministic path planners are algorithms that can always find the same paths under the same operating conditions [40]. This type of planner is effective when dealing with static environments. Moreover, its implementation is relatively simple and low-cost, so it is widely used. Nevertheless, deterministic planners are less effective when a mobile robot operates within a dynamic scenario due to its changing conditions and the unpredictable behaviors of its obstacles.
Among the wide variety of available deterministic path planners, the Bug-type is one of the simplest and most affordable [13].

3.1. Bug-Type Path Planners

Bug-type planners are simple state-of-the-art alternatives as they only require feedback from the environment (via sensors or transducers) and do not require a complete map of it [39], i.e., the path is planned based on the scenario information that they can acquire within a given radius.
The operation of this type of path planner can be summarized in two simple behaviors [39]:
  • The mobile robot always moves straight from its current position towards the goal.
  • The mobile robot changes its moving direction only when it approaches an obstacle.
Mobile robots using Bug-type algorithms can avoid obstacles and move toward the goal. These algorithms require low memory and processing, and the obtained path is often not optimal, but is generally effective in reaching the final configuration without collision [39].

3.2. The Bug0 Path Planner

Among the Bug-type planners, different variants are distinguished by the complexity of their operations and how they perform the two activities mentioned above. All of them have different benefits and limitations. The simplest of these algorithms is known as Bug0 and has two basic behaviors [39]:
  • The robot moves towards the goal until an obstacle is detected or the final configuration is reached. A variable-gain linear speed controller and a fixed-gain angular speed controller are used for this, where the variable gain depends on the distance between the robot and the goal.
  • If a nearby obstacle is detected, the robot turns π / 2 or π / 2 (only one choice) concerning the collision direction and follows the contour of the obstacle until it can follow a straight line to the goal. In this case, fixed-gain linear and angular speed controllers are utilized.
Algorithm 1 describes Bug0. At fixed time intervals while moving the differential mobile robot, Bug0 uses the distance to the nearest obstacle d o b s , the orientation of the nearest obstacle concerning the robot θ o b s , the position of the goal ξ g = [ x g , y g ] T , and the current position and orientation of the robot, respectively ξ ( t ) = [ x ( t ) , y ( t ) ] T and θ , to calculate the control inputs v and ω (linear and angular velocities) that take the robot closer to the goal avoiding obstacles in the path. For this, it is assessed whether the distance to the nearest obstacle is safe enough using an appropriate threshold μ (line 2). In that case, the robot must steer toward the goal using a variable gain for the linear velocity controller v and a fixed gain for the angular speed controller ω (lines 3 to 7). The variable gain depends on the distance to the goal. Otherwise, the robot will go around the nearest obstacle using fixed-gain linear and angular speed controllers in the direction θ o b s + s ( π / 2 ) , i.e., to the left or right of the obstacle direction (when s = 1 or s = 1 , respectively), but always in the same direction (lines 9 to 12). Using the control gains (fixed or variable), Bug0 calculates the inputs v and ω (lines 14 to 16) that move the robot toward the goal, avoiding obstacles in the path.
Here, it is important to note that the output of Algorithm 1 includes the control inputs v and ω for the differential mobile robot. During a kinematic simulation, i.e., using the model in (8), v and ω can be used directly as the inputs to the robot. In the case of a more realistic simulation with the model in (22) or in practice, it is necessary to determine the torques of the two wheels on the robot. This can be achieved using an inverse dynamics controller [41] by solving the system of equations in (22) for τ l and τ r . Thus, the inverse dynamic control for the differential mobile robot using a linear proportional compensator is:
τ l = k p v e v m r 2 k p ω e ω I z r L τ r = k p v e v m r 2 + k p ω e ω I z r L
where e v and e ω are the difference between the tangential and angular velocities calculated by Bug0 and the current robot velocities, with k p v and k p ω as the proportional control gains.
Algorithm 1: Bug0 path planner
Mathematics 10 03990 i001

4. Proposed Dynamic Path Planner

As mentioned above, the Bug0 algorithm effectively handles the path planning problem for static scenarios. If the environment is dynamic, Bug0 may encounter some difficulties related to its fixed parameters:
  • In this algorithm, when the robot is near an obstacle, it always evades it in the same direction (to the left or to the right, i.e., at ± π / 2 from the collision direction). Therefore, there may be scenarios where the distance traveled increases, where the robot fails to reach the goal, or where there is a collision with obstacles going to the same place;
  • In addition, Bug0 uses a fixed gain control when approaching an obstacle. Consequently, there may be scenarios where the movements generated by the fixed gain control (these could be too slow or too fast) do not allow for evading dynamic obstacles on time.
The proposed dynamic path planning method is based on the Bug0 algorithm for its simplicity and low cost and it aims to address the above difficulties through a metaheuristic online optimization approach. In this sense, it is necessary to formulate a formal dynamic optimization problem whose solution includes the Bug0 parameters that help it handle dynamic scenarios. The problem should be solved continuously, whenever necessary (when a threat is near the robot, i.e., when d o b s < μ ).
The elements of the dynamic optimization problem and the metaheuristic solution approach are described below.

4.1. Dynamic Optimization Problem

In general, a formal dynamic optimization problem can be defined as follows:
min J ( p , t ) = [ J 1 ( p , t ) , J 2 ( p , t ) , , J m ( p , t ) ] T
s.t.:
g i ( p , t ) 0 , i = 1 , 2 , , n g
h j ( p , t ) = 0 , j = 1 , 2 , , n h
The above problem is to find the value of the design variables in the vector p that minimizes the m objective functions in J, as seen in (27). Solutions to this problem can be conditioned by n g inequality constraints in (28) or n h equality constraints in (29). The objective functions quantify the fulfillment of different performance indicators. On the other hand, inequality constraints (also known as soft constraints) are conditions that can be met with some degree of slack. Finally, equality constraints (also known as hard constraints) are conditions that must be met exactly. Additionally, the search space, i.e., the possible values that the vector p can acquire, is limited by the box constraints, which include each design variable’s minimum and maximum values.
In a dynamic optimization problem as the one in (27)–(29), the time t introduces dynamism. Thus, at each instant of time, the objective functions and constraints can change their value for the same vector of design variables p.

4.1.1. Design Variables

Since one of the problems of Bug0 lies in its fixed parameters, as described above, it is proposed to use a vector of design variables as follows:
p = [ s , g 1 , g 2 ] T
where s is the direction of avoidance (either left or right by π / 2 ) in case of detecting a nearby obstacle, and g 1 , g 2 are the gains of the mobile speed controllers (see Algorithm 1).

4.1.2. Objective Function

The objective function must quantify the quality of the paths generated by the differential mobile robot when using a given p.
An essential aspect of path planning is that the paths developed by the mobile robot should be low-cost. This may be related to traveling the greatest possible distance in the shortest time or using the least amount of energy.
Therefore, it is proposed to use the objective function in (31). This function considers the Euclidean distance between the goal position ξ g = [ x g , y g ] T and the robot position ξ ^ ( t + h d t ) = [ x ^ ( t + h d t ) , y ^ ( t + h d t ) ] T estimated by the kinematic model for the instant t + h d t by using Bug0 with the parameters in p, with h as the future prediction horizon, i.e., the number of future steps of d t that are simulated by the kinematic model.
J ( p , t ) = ( x g x ^ ( t + h d t ) ) 2 + ( y g y ^ ( t + h d t ) ) 2
Therefore, the dynamic planner will be able to perform a simulation of the robot’s behavior using the kinematic model from its current configuration. The above aims to determine the parameters of Bug0 that best bring it closer to the goal.

4.1.3. Constraints

The operation of the differential mobile robot is limited to collision-free paths with moving obstacles in the environment.
In the dynamic path planning problem, the constraints count the number of collisions the robot could have when using a given vector p in Bug0 within the same prediction horizon h discussed in the previous section. Then, the dynamic optimization problem only considers equality constraints as follows:
h j ( p , t ) = 1 , if d k ( t + l d t ) < L 2 + L k 2 0 , otherwise , j = 1 , 2 , , n o b s h , k = 1 , 2 , , n o b s , l = 1 , 2 , , h
where d k ( t + l d t ) is the Euclidean distance between robot position ξ ^ ( t + l d t ) = [ x ^ ( t + l d t ) , y ^ ( t + l d t ) ] T (estimated by the kinematic model for the instant t + l d t by using Bug0 with the parameters in p) and the k-th obstacle location ξ ^ k ( t + l d t ) = [ x ^ k ( t + l d t ) , y ^ k ( t + l d t ) ] T (predicted or calculated for the instant t + l d t ), L k is the length of the k-th obstacle, and n o b s is the number of dynamic obstacles. It is assumed that the location of every dynamic obstacle ξ ^ k ( t + l d t ) can be predicted or calculated [42,43].
With the above, the planner can simulate the mobile robot’s kinematic behavior and use the positional information of the dynamic obstacles to determine whether a configuration p of the Bug0 algorithm can avoid collisions.

4.2. Solving a Dynamic Optimization Problem

As discussed above, a dynamic optimization problem is one in which the objective function and/or constraints change over time. Typically, there are two ways to solve this type of problem [44]:
  • Using an optimizer that solves the problem from scratch each time a change is detected;
  • Incorporating additional mechanisms in the optimizer to adapt the solutions found so far without solving the problem from scratch.
The solution approach (1) is adopted in this work to maintain the simplicity of the proposal.

4.3. Metaheuristic Optimizers

The optimization problem in (30)–(32) includes highly nonlinear, discontinuous, and non-differentiable elements, which makes it difficult to solve by traditional search or optimization methods. For this reason, approximate optimization techniques, such as metaheuristics, may be suitable alternatives to find good solutions to this kind of problem [45].
Although a wide variety of metaheuristics are currently available [36], no single one of them is capable of providing the best solutions to all types of optimization problems, according to the No Free Lunch theorems [46]. One way to select the best alternative among these techniques for a specific problem is to do so empirically, by testing different metaheuristics of proven effectiveness. This approach is adopted in this work. Among the available metaheuristics, three alternatives have a proven track record of successful use in various science and engineering contexts. Differential Evolution, the Genetic Algorithm, and Particle Swarm Optimization are these techniques. Many recent metaheuristics are based on the above techniques or propose improvements at an additional computational cost.
The general performance of these three metaheuristic optimizers is described below.

4.3.1. Differential Evolution

Differential Evolution (DE) [47] is a metaheuristic optimization technique inspired by natural evolution. This algorithm has a population of individuals that searches for the approximate solution to a complex optimization problem. DE has several variants, and one of the simplest and most effective is rand/1/bin [48]. The general operation of DE rand/1/bin is described in Algorithm 2. In DE, each D-dimensional vector p i = [ x i 1 , p i 2 , , p i D ] T , i = 1 , 2 , , N P (also called individual) in a population with N P vectors is used to represent a candidate solution to the optimization problem. At the beginning of the algorithm, the initial population includes individuals randomly generated in the search space delimited by d m i n and d m a x (lines 1 and 2). During a maximum of G m a x generations, each of the base individuals in the current population P generates first a mutant with the rand/1 operator, which uses the scaling factor F and three random individuals from P (lines 5 and 6). Then, the base individual and its mutant are recombined to obtain an offspring through the b i n operator and the crossover rate C R (line 7). Finally, the base individual competes with its offspring to determine the fittest solution, which persists in P (line 8). For this, the performance of each individual is measured in terms of their ability to solve the optimization problem. At the end of the last generation, the best individual from the population P is selected as the approximated solution to the optimization problem (lines 10 and 11).
Algorithm 2: Differential Evolution
Mathematics 10 03990 i002

4.3.2. Genetic Algorithm

As DE, the Genetic Algorithm (GA) is a metaheuristic technique based on natural evolution, but at chromosome level [49]. Currently, several variants of GA have been proposed and are distinguished by the approaches adopted in the evolutionary operations of crossover, mutation, selection, and the codification of the chromosomes. One popular and effective GA, widely used to solve multi-objective optimization problems, is the Non-dominated Sorting Genetic Algorithm II (NSGAII) [50]. The Algorithm 3 describes the operation of a single-objective version of NSGAII referred to as GA only. In the GA in Algorithm 3, the chromosomes are D-dimensional vectors p i = [ x i 1 , p i 2 , , p i D ] T , i = 1 , 2 , , N P that represent possible solutions to an optimization problem. GA starts with a population with N P chromosomes randomly generated in the search space given by d m i n and d m a x (lines 1 and 2). During G m a x generations, N P / 2 couples of chromosomes are selected from the population through a binary tournament (line 4). The contestants of each tournament are chosen randomly from the population. Next, each couple of chromosomes can be recombined through the Simulated Binary Crossover (SBX) operator with the distribution index η c [51] and based on a given probability P c (line 5). SBX generates two offspring chromosomes that can be mutated at the given rate P m through the Polynomial Mutation (PM) operator with the distribution index η m [52] (line 6). The resulting new chromosomes are included in the population P (line 7). By the end of each generation, only the N P fittest chromosomes are preserved in the population P (line 8). After the maximum number of generations G m a x is reached, the best chromosome in the population is taken as the solution to the optimization problem (lines 10 and 11).
Algorithm 3: Genetic Algorithm
Mathematics 10 03990 i003

4.3.3. Particle Swarm Optimization

Unlike the evolutionary algorithms DE and GA, Particle Swarm Optimization (PSO) is a representative swarm intelligence method. This kind of metaheuristic is inspired by the collaborative nature of species in search of survival [53]. PSO considers a swarm of particles (e.g., individuals of any species) whose positions change over time to find a beneficial location (e.g., with the greatest amount of resources). A universally used variant of PSO considers a swarm with fully connected topology (i.e., each particle knows the others) and assumes that the particles have a memory of their best positions and the best position of the swarm. Furthermore, using a linearly decreasing inertia factor while updating particle positions has been shown to be beneficial in many PSO applications [54]. Algorithm 4 describes the operation of the above PSO variant. In PSO, D-dimensional vectors p i = [ x i 1 , p i 2 , , p i D ] T , i = 1 , 2 , , N P represent the position of each particle in a swarm of N P . Each position is a candidate solution to the optimization problem. These positions are generated randomly in the search space bounded by d m i n and d m a x (lines 1 and 2). In addition, each particle keeps a record of its best-known position (line 3) and the best-known position by the swarm (line 4). At each iteration, PSO updates the velocity of each particle using an inertia weight, its current position, its best-known position (also known as personal best), and the best-known position of the swarm (also known as global best) using the constants C 1 and C 2 that ponders the local and global knowledge respectively, with C 1 + C 2 < 4 (line 8). The inertia weight w starts in a maximum value w m a x and decreases linearly on each iteration until w m i n (line 6). The calculated velocity updates the particle position (line 7). Every time a particle position is obtained, the personal and global best positions are updated (lines 10 and 11). When the last iteration G m a x is reached, the global best position is selected as the solution to the optimization problem.
Algorithm 4: Particle Swarm Optimization
Mathematics 10 03990 i004

4.4. Additional Considerations on the Metaheuristic Optimizers

The original versions of the aforementioned algorithms consider unconstrained single-objective optimization problems with continuous variables. In this section, we present the aspects that must be considered in the metaheuristic optimizers to be able to handle the dynamic path planning problem for the differential mobile robot.

4.4.1. Handling Hard Constraints

For unconstrained optimization problems, whenever it is necessary to discriminate a solution in DE, GA, or PSO, only the value of the objective function J is considered. In the case of problems with constraints, such as dynamic path planning, it is necessary to incorporate a mechanism that considers the feasibility of the solutions (i.e., the extent to which they comply with the constraints). Deb’s rules mechanism is a simple and efficient alternative to handle constrained problems [55]. For this purpose, the rules first weigh the feasibility and then the optimality when comparing two solutions.
Deb’s feasibility rules establish the following [55]:
  • If a feasible solution is compared against a non-feasible solution, then the former is preferred;
  • If two feasible solutions are compared, the one with the best objective function value is preferred;
  • If two infeasible solutions are compared, the one with the lowest constraint violation sum is preferred.
The constraint violation sum is represented as follows for a dynamic optimization problem:
ϕ ( p , t ) = i = 1 n g max 0 , g i ( p , t ) 2 + j = 1 n h | h j ( p , t ) |
The above rules are included in the metaheuristics to handle the constraints of the dynamic path planning problem.

4.4.2. Handling Box Constraints

Another problem faced by these metaheuristics is to ensure that the solutions generated during their operation remain within the search space given by d m i n and d m a x (i.e., the box constraints). The metaheuristics used in this work adopt a simple mechanism to handle box constraints. This mechanism consists of regenerating the variable randomly when it exceeds the bounds d m i n and d m a x :
p i , j = p i , j , if d m i n , j p i , j d m a x , j d m i n , j + r a n d ( 0 , 1 ) ( d m a x , j d m i n , j ) , otherwise

4.4.3. Handling Mixed Variables

As could be observed in the problem in (30)–(32), the design variables considered are mixed [56]. This is because the control gains g 1 and q 2 in (30) are continuous, while the avoidance direction s { 1 , 1 } . By their very nature, the metaheuristics considered in this work can handle only continuous variables. However, a simple mechanism is incorporated to handle mixed variables to solve the dynamic planning problem. The mechanism consists of mapping the value of s to the values in the set { 1 , 1 } with (35) each time the problem needs to be evaluated or when the solution is used in Bug0.
s = 1 , if s 0 1 , otherwise

5. Experiments and Results

The dynamic path planner described in the previous section is tested in simulation.

5.1. Experiments Details

For the experimentation, the robot is simulated with the dynamic model in (22) to provide results closer to reality. In that model, the kinematic parameters of the mobile robot are L = 15 (cm) and r = 2.4 (cm), while the dynamic ones are m = 0.75 (kg) and I z = 0.001 (kg·m2), as proposed in [39]. The mobile robot simulation is performed using the numerical Euler integration method with a step size d t = 0.03 (s). Additionally, the proportional gains of the inverse dynamics controller in (26) are chosen as k p v = 50 and k p ω = 50 to govern the robot wheels based on the input commands v and ω . On the other hand, the scenario is not bounded and matches the horizontal X Y plane. Moreover, the start and goal points are fixed in the scenario. The start point is ξ 0 = [ 0 , 0 ] T (m) and the goal is ξ g = [ 4 , 0 ] T (m). The initial orientation of the differential mobile robot is θ 0 = 0 ( r a d ) . Seven dynamic obstacles are considered within the scenario ( n o b s = 7 ), each of them with the same size of the mobile robot, i.e., L k = L , k = 1 , 2 , , n o b s . The dynamic behavior of each obstacle in the scenario is described in Table 1. The threshold used in Bug0 is set as μ = 0.25 (m).
Concerning the dynamic optimization problem, the box constraints used to limit the values of the design variables are as follows: d m i n = [ 0.0 , 0.0 , 1.0 ] T and d m a x = [ 1.0 , 10.0 , 1.0 ] T . As for the kinematic simulation of the mobile robot required to make future predictions, a sampling interval d t , a prediction horizon h = 10 , and Euler’s numerical integration method are used.
In the case of the metaheuristics DE, GA, and PSO, their parameters are selected based on the suggestions in the specialized literature. The parameters of DE are the scaling factor F generated randomly in [ 0.3 , 0.9 ] at each generation and the crossover rate C R = 0.5 [48]. In the case of GA, the crossover and mutation probabilities are P c = 1 (this value ensures that the same number of evaluations of the optimization problem are always carried out per generation) and P m = 1 / 3 , while their distribution indexes are η c = 20 and η m = 20 [50]. Finally, in PSO, the local and global knowledge constants are C 1 = 2 and C 2 = 2 , and the bound of the inertia weight are v m i n = 0.4 and v m a x = 0.9 [54]. The population/swarm size is established as N P = 25 and the maximum number of generations/iterations as G m a x = 100 for all metaheuristics. The above aims to ensure that the computational cost of the optimization can be affordable in possible physical experimentation. The optimization procedure with the metaheuristics is launched when d o b s < μ . Since the controller gains are not optimized by DE until the first time that d o b s < μ is fulfilled, then it is used at first the pair of fixed gains g 1 = 0.4 and g 2 = 5 proposed in [39].
All experiments are performed on a conventional personal computer and implemented in C++. The source code can be found at https://dr-rodriguez-molina.com/codes/ (accessed on 12 October 2022).

5.2. Results and Discussion

In order to generate simulation results and obtain sufficient evidence of the proposal’s performance (from now on, D-Bug0), 30 independent runs were performed with each metaheuristic optimizer under the experimental conditions described in the previous section. The versions of D-Bug0 using Differential Evolution, Genetic Algorithm, and Particle Swarm Optimization are named D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO, respectively.
Table 2 shows the summary statistics on the performance of the alternatives D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO considering different indicators: the total path length, the number of collisions with the dynamic obstacles, the time it took the differential mobile robot to reach the goal, its average speed, and the computational time to process both the proposed path planning algorithm and the simulation. The best results in this table are highlighted in boldface.
Based on Table 2, the proposed dynamic planner D-Bug0 can generate free-collision paths regardless of the adopted metaheuristic and despite the scenario having multiple moving obstacles. This is highly relevant because it could help safeguard the integrity of the actual differential mobile robot in a physical experimental environment to avoid unnecessary repair costs. Concerning the other indicators, significant differences can be noted in the performance of the three dynamic planners. The PSO-based alternative stands out from the others in terms of path length, time to goal, and execution time. On the other hand, D-Bug0/GA helps the mobile robot track the path at the highest speed. In the same table, the small value of the standard deviation, compared to the mean, for all indicators, indicates that the results obtained are very similar in each run, highlighting the reliability of D-Bug0.
Although the results in Table 2 provide an overview of the performance of the different D-Bug0 planners, it is necessary to confirm the results with a non-parametric statistical test due to the stochastic behavior of the metaheuristics, which generates non-normal distributions of results for each group of 30 independent runs [57]. The pairwise Wilcoxon rank-sum test was adopted for this purpose considering a two-sided alternative hypothesis (this establishes that two results distributions have significant differences) and a statistical significance α = 5 % (the minimum probability to accept the alternative hypothesis). The results of the Wilcoxon tests are in Table 3. This table includes information from the Wilcoxon tests performed for each indicator considered in Table 2. In addition, it describes the test performed and shows the sums of ranks R + and R (these indicate respectively the number of times the first method outperformed the second and vice versa). The p-value in the last column denotes the probability of accepting the alternative hypothesis and rejecting the null hypothesis (this establishes that two results distributions do not have significant differences). The winner of each pairwise test is shown in boldface. Table 4 summarizes the number of wins for each dynamic planner in the Wilcoxon test. Here, it can be confirmed that D-Bug0/PSO is the best alternative.
Having identified that the best dynamic planner is D-Bug0, it is appropriate to perform a more in-depth analysis of its performance. In this way, Table 5 shows the results obtained with the D-Bug0/PSO planner corresponding to its 30 independent runs. The first column includes the run number, while the following columns show the path length, collisions, arrival time, speed, and execution time. At the bottom of the table are the summary statistics for each of the above columns. The results in boldface refer to the best results of the 30 runs.
In Table 5, it can be observed that the difference between the minimum and maximum values is less than 0.01 (m) for the path length, approximately 0.01 (s) for the arrival time, and 0.003 (m/s) for the speed, which further denotes that such reliability in spite that D-Bug0/PSO is stochastic. On the other hand, D-Bug0/PSO shows efficiency since all the simulation runs are performed in an acceptable time in proportion to the arrival time. This is observed in the execution time column, where the results do not exceed 3.38 (s). In contrast, the standard deviation for this column is slightly higher in proportion to the mean concerning the rest of the columns. This is because the simulations are conducted on a conventional computer where, in addition, multiple processes derived from the operational functioning are executed at the same time.
At this point, making some observations regarding the execution time is important. One of the aspects that have a greater influence on the execution time in D-Bug0/PSO are the parameters of the PSO optimizer. In particular, G m a x and N P are the values that have the greatest impact on the time since they determine the number of evaluations of the optimization problem that the metaheuristics utilize (the number of evaluations is G m a x N P ). If the number of evaluations is insufficient, the optimizer may find solutions far from optimal. On the other hand, if the number of evaluations is excessive, time may prevent the practical implementation of the planner. One way to evaluate whether the number of evaluations is sufficient is through convergence plots such as those shown in Figure 3. This figure shows the evolution of objective function value J for the best solution in the swarm over the iterations in different optimization processes for an arbitrary run of D-Bug0/PSO. The figure shows that PSO needs about 50 iterations to obtain an unbeatable solution. Considering that, under the proposed experimental conditions, D-Bug0/PSO requires, on average, 96 optimization processes to complete the planning, the processing time for each process is affordable (i.e., less than d t ), with an adequate budget for problem evaluations. In the case of processing equipment with fewer resources than a conventional PC, the time window to obtain a solution with the metaheuristics can be longer, as it has been observed in other online optimization works [58], however, some parameters of the proposal, such as μ , must also be readjusted.
It is also interesting to observe a sketch of the behavior of D-Bug0/PSO. Figure 4 shows an arbitrary execution of D-Bug0/PSO. This figure plots the complete scenario every 1.5 (s). The red, green, black, and blue circles represent the obstacles, the goal, the robot, and the path’s starting point, respectively. This figure shows how D-Bug0/PSO changes the avoidance direction and robot speed to avoid collisions with dynamic obstacles.
In addition, the results of D-Bug0/PSO are compared with those obtained with the original Bug0 algorithm considering obstacle avoidance always to the left and to the right (from now on, Bug0+ and Bug0−, respectively). The fixed gains for the controllers in Bug0+ and Bug0− are the same as the initial ones for D-Bug0, i.e., g 1 = 0.4 and g 2 = 5 .
Table 6 and Table 7 include the results obtained with Bug0− and Bug0+ (i.e., Bug0 with fixed parameters and different obstacle avoidance directions), respectively, after 30 independent runs under the same experimental conditions as D-Bug0/PSO. The first column of these tables shows the number of the run, and the following columns show the travel distance, the number of times the robot collided with the dynamic obstacles, the time it took for the robot to reach the goal, the speed and the time it took for the computer to process each variant of the Bug0 algorithm as well as the simulation. As in Table 5, the lower part of these two tables shows the same statistical measures for each column, and, similarly, the best results are shown in boldface.
Table 6 and Table 7 show that the standard deviation is zero for path length, arrival time, and speed, highlighting the deterministic behavior of the Bug0 algorithms. Therefore, the same results of these columns are always observed in each of the 30 independent runs of the Bug0 algorithms. Small variations in execution time values are attributed to other tasks executed in the computer’s operating system. On the other hand, one of the most important findings in these two tables is that the paths generated by Bug0+ and Bug0− always collide with dynamic obstacles. In the case of Bug0−, Table 6 shows that the number of collisions is 19, while in the case of Bug0−, Table 7 indicates it is 16. The difference between the number of collisions is due to the fixed direction in which Bug0+ and Bug0− avoid obstacles. The above results indicate that although the null variation in the results of the runs could be desirable, the generated paths do not meet the objective of collision avoidance and may lead to additional costs during physical testing. For this reason, Bug0 with fixed parameters may not be suitable for path planning in dynamic environments.
Based on Table 5, Table 6 and Table 7, it can be noted that the paths generated by D-Bug0/PSO have, in all cases, reduced path lengths, collisions, and arrival times, and consequently, higher speed values. Based on the above, the paths generated by D-Bug0/PSO are better than those of the original Bug0 planning method. In particular, the fact that the number of collisions in the paths generated by D-Bug0 is zero, while in the paths obtained by Bug0+ and Bug0− it is different, indicates a great advantage of the first method since it can lead to significant savings in robot damage costs in a real scenario. Therefore, after observing the data yielded by the path planners, the high efficiency of the D-Bug0/PSO becomes clear since it obtains better results in all the aspects listed in the Table 5, Table 6 and Table 7, except for the simulation execution time, although the last one is still affordable for eventual experimentation with the physical device.
Finally, Figure 5 and Figure 6 describe the behavior of an arbitrary execution of Bug0− and Bug0+, respectively. These figures include plots of the full scenario every 1.5 (s). The red, green, black, and blue circles represent the obstacles, the goal, the differential mobile robot, and the start of the path, respectively. These figures show how the Bug0 path planner tries (and sometimes fails) to avoid dynamic obstacles by changing the robot’s direction to the left (for Bug0+) or right (for Bug0−) of the potential collision point, even when it might not be the most suitable direction. Moreover, it is observed that, for some obstacles, the speed with which the robot moves, related to the fixed gains g 1 and g 2 , is adequate.

6. Conclusions and Future Work

Path planning is an essential task for the differential mobile robot. This task is complex due to the environment features and the robot’s behavior. Planning is harder when the environment is dynamic and deterministic planners may fail to obtain safe and well-performing alternatives. Nevertheless, proposed advanced methods can resolve this kind of scenario, but their implementation complexity and cost may not be suitable for all applications.
For this reason, the proposed path planning method combines the performance of the deterministic planner Bug0 and metaheuristic techniques to optimize it in achieving optimized and collision-free paths with an affordable computational cost. In this sense, it is observed that Bug0 is effective in static scenarios where obstacles can always be avoided in the same direction. When the scenarios are dynamic, Bug0 may collide since it cannot predict a future interaction between the moving obstacles and the robot. Therefore, the proposal includes a predictive stage, which allows the planner to estimate the robot’s behavior within a future time window and thus determine the best speed control parameters and avoidance direction. To this end, three well-known metaheuristics, including Differential Evolution, the Genetic Algorithm, and Particle Swarm Optimization, are implemented in the proposal to test different combinations of the above values and determine the alternative that allows the robot to approach the goal without colliding.
Based on the results obtained in the simulation, the dynamic planner based on PSO (D-Bug0/PSO) obtains the best collision-free paths with reduced length and arrival time. Likewise, the computational time required by the proposal is affordable and can be used in a physical prototype. Compared to the original Bug0 with fixed parameters, D-Bug0/PSO is significantly better since the former caused the robot to collide several times and increases the path length due to its deterministic behavior.
Future work intends to implement a method to predict the paths of dynamic obstacles and use their information within the planner instead of assuming that their behaviors are known. In addition, online variants of the metaheuristics used are contemplated to avoid starting each optimization process from scratch and reduce computational time. This research can be tested with a physical object by managing these limitations.

Author Contributions

Conceptualization, A.R.-M.; Data curation, A.H.-H.; Formal analysis, A.R.-M.; Funding acquisition, M.A.-P.; Investigation, A.H.-H.; Software, G.F.-C.; Supervision, M.A.-P.; Validation, G.F.-C.; Visualization, J.A.A.-V.; Writing—original draft, A.R.-M., A.H.-H., M.A.-P., G.F.-C. and J.A.A.-V. All authors have read and agreed to the published version of the manuscript.

Funding

The authors acknowledge the support from the Secretaría de Investigación y Posgrado (SIP) of the Instituto Politécnico Nacional (IPN). Additionally, the first author would like to thank the support from the Dirección de Posgrado, Investigación e Innovación of the Instituto Tecnológico Nacional de México (TecNM) through projects No. 13585.22-P and No. 14301.22-P, the second author acknowledges support from the Consejo Nacional de Ciencia y Tecnología (Conacyt) through a scholarship to pursue graduate studies at TecNM, and the third author acknowledges the support of the SIP-IPN through the project 20220247.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Morales, Y.; Miyashita, T.; Hagita, N. Social robotic wheelchair centered on passenger and pedestrian comfort. Robot. Auton. Syst. 2017, 87, 355–362. [Google Scholar] [CrossRef]
  2. Yamashita, A.; Arai, T.; Ota, J.; Asama, H. Motion planning of multiple mobile robots for Cooperative manipulation and transportation. IEEE Trans. Robot. Autom. 2003, 19, 223–237. [Google Scholar] [CrossRef] [Green Version]
  3. Paola, D.D.; Milella, A.; Cicirelli, G.; Distante, A. An Autonomous Mobile Robotic System for Surveillance of Indoor Environments. Int. J. Adv. Robot. Syst. 2010, 7, 8. [Google Scholar] [CrossRef]
  4. Murphy, R.R.; Kravitz, J.; Stover, S.L.; Shoureshi, R. Mobile robots in mine rescue and recovery. IEEE Robot. Autom. Mag. 2009, 16, 91–103. [Google Scholar] [CrossRef]
  5. Matveev, A.S.; Wang, C.; Savkin, A.V. Real-time navigation of mobile robots in problems of border patrolling and avoiding collisions with moving and deforming obstacles. Robot. Auton. Syst. 2012, 60, 769–788. [Google Scholar] [CrossRef]
  6. Bolmsjo, G.; Neveryd, H.; Eftring, H. Robotics in rehabilitation. IEEE Trans. Rehabil. Eng. 1995, 3, 77–83. [Google Scholar] [CrossRef]
  7. Dieter Schraft, R.; Graf, B.; Traub, A.; John, D. A mobile robot platform for assistance and entertainment. Ind. Robot Int. J. 2001, 28, 29–35. [Google Scholar] [CrossRef] [Green Version]
  8. Wang, Y.; Lang, H.; de Silva, C.W. A Hybrid Visual Servo Controller for Robust Grasping by Wheeled Mobile Robots. IEEE/ASME Trans. Mech. 2010, 15, 757–769. [Google Scholar] [CrossRef]
  9. Rubio, F.; Valero, F.; Llopis-Albert, C. A review of mobile robots: Concepts, methods, theoretical framework, and applications. Int. J. Adv. Robot. Syst. 2019, 16, 1729881419839596. [Google Scholar] [CrossRef] [Green Version]
  10. Ben Jabeur, C.; Seddik, H. Design of a PID optimized neural networks and PD fuzzy logic controllers for a two-wheeled mobile robot. Asian J. Control 2021, 23, 23–41. [Google Scholar] [CrossRef]
  11. Hossain, M.A.; Ferdous, I. Autonomous robot path planning in dynamic environment using a new optimization technique inspired by bacterial foraging technique. Robot. Auton. Syst. 2015, 64, 137–141. [Google Scholar] [CrossRef]
  12. Bergman, K.; Ljungqvist, O.; Axehill, D. Improved Path Planning by Tightly Combining Lattice-Based Path Planning and Optimal Control. IEEE Trans. Intell. Veh. 2021, 6, 57–66. [Google Scholar] [CrossRef]
  13. Sánchez-Ibáñez, J.R.; Pérez-del Pulgar, C.J.; García-Cerezo, A. Path Planning for Autonomous Mobile Robots: A Review. Sensors 2021, 21, 7898. [Google Scholar] [CrossRef]
  14. Lumelsky, V.J.; Stepanov, A.A. Path-planning strategies for a point mobile automaton moving amidst unknown obstacles of arbitrary shape. Algorithmica 1987, 2, 403–430. [Google Scholar] [CrossRef] [Green Version]
  15. Warren, C. Global path planning using artificial potential fields. In 1989 IEEE International Conference on Robotics and Automation; IEEE Computer Society: Los Alamitos, CA, USA, 1989; pp. 316–321. [Google Scholar] [CrossRef]
  16. Aghababa, M.P.; Amrollahi, M.H.; Borjkhani, M. Application of GA, PSO, and ACO algorithms to path planning of autonomous underwater vehicles. J. Mar. Sci. Appl. 2012, 11, 378–386. [Google Scholar] [CrossRef]
  17. Glasius, R.; Komoda, A.; Gielen, S.C. Neural Network Dynamics for Path Planning and Obstacle Avoidance. Neural Netw. 1995, 8, 125–133. [Google Scholar] [CrossRef]
  18. Pandey, A.; Sonkar, R.K.; Pandey, K.K.; Parhi, D.R. Path planning navigation of mobile robot with obstacles avoidance using fuzzy logic controller. In Proceedings of the 2014 IEEE 8th International Conference on Intelligent Systems and Control (ISCO), Coimbatore, India, 10–11 January 2014; pp. 39–41. [Google Scholar] [CrossRef]
  19. Hart, P.E.; Nilsson, N.J.; Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  20. LaValle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning; Iowa State University: Ames, IA, USA, 1998. [Google Scholar]
  21. Martin, C.; Sun, S.; Egerstedt, M. Optimal control, statistics and path planning. Math. Comput. Model. 2001, 33, 237–253. [Google Scholar] [CrossRef]
  22. Sangeetha, V.; Krishankumar, R.; Ravichandran, K.S.; Cavallaro, F.; Kar, S.; Pamucar, D.; Mardani, A. A Fuzzy Gain-Based Dynamic Ant Colony Optimization for Path Planning in Dynamic Environments. Symmetry 2021, 13, 280. [Google Scholar] [CrossRef]
  23. Stentz, A. Optimal and efficient path planning for partially-known environments. In International Conference on Robotics and Automation; Springer: Boston, MA, USA, 1994; Volume 4, pp. 3310–3317. [Google Scholar] [CrossRef]
  24. Ge, S.S.; Cui, Y.J. Dynamic Motion Planning for Mobile Robots Using Potential Field Method. Auton. Robots 2002, 13, 207–222. [Google Scholar] [CrossRef]
  25. Okuyama, I.F.; Maximo, M.R.O.A.; Afonso, R.J.M. Minimum-Time Trajectory Planning for a Differential Drive Mobile Robot Considering Non-slipping Constraints. J. Control Autom. Electr. Syst. 2021, 32, 120–131. [Google Scholar] [CrossRef]
  26. Wang, J.; Li, B.; Meng, M.Q.H. Kinematic Constrained Bi-directional RRT with Efficient Branch Pruning for robot path planning. Expert Syst. Appl. 2021, 170, 114541. [Google Scholar] [CrossRef]
  27. Mao, R.; Gao, H.; Guo, L. Optimal Motion Planning for Differential Drive Mobile Robots based on Multiple-Interval Chebyshev Pseudospectral Methods. Robotica 2021, 39, 391–410. [Google Scholar] [CrossRef]
  28. Mao, R.; Gao, H.; Guo, L. Optimal motion planning of differential-drive mobile robots based on trapezoidal collocation method. J. Phys. Conf. Ser. 2019, 1341, 052007. [Google Scholar] [CrossRef]
  29. Gia Luan, P.; Thinh, N.T. Real-Time Hybrid Navigation System-Based Path Planning and Obstacle Avoidance for Mobile Robots. Appl. Sci. 2020, 10, 3355. [Google Scholar] [CrossRef]
  30. Luan, P.G.; Thinh, N.T. Hybrid genetic algorithm based smooth global-path planning for a mobile robot. Mech. Based Des. Struct. Mach. 2021, 1–17. [Google Scholar] [CrossRef]
  31. Cheng, K.P.; Mohan, R.E.; Khanh Nhan, N.H.; Le, A.V. Multi-Objective Genetic Algorithm-Based Autonomous Path Planning for Hinged-Tetro Reconfigurable Tiling Robot. IEEE Access 2020, 8, 121267–121284. [Google Scholar] [CrossRef]
  32. Katiyar, S.; Dutta, A. Comparative analysis on path planning of ATR using RRT*, PSO, and modified APF in CG-Space. Proc. Inst. Mech. Eng. Part C J. Mech. Eng. Sci. 2022, 236, 5663–5677. [Google Scholar] [CrossRef]
  33. Elmi, Z.; Önder Efe, M. Online path planning of mobile robot using grasshopper algorithm in a dynamic and unknown environment. J. Exp. Theor. Artif. Intell. 2021, 33, 467–485. [Google Scholar] [CrossRef]
  34. Rodríguez-Molina, A.; Solís-Romero, J.; Villarreal-Cervantes, M.G.; Serrano-Pérez, O.; Flores-Caballero, G. Path-Planning for Mobile Robots Using a Novel Variable-Length Differential Evolution Variant. Mathematics 2021, 9, 357. [Google Scholar] [CrossRef]
  35. Reeves, C.R. (Ed.) Modern Heuristic Techniques for Combinatorial Problems; John Wiley & Sons, Inc.: Hoboken, NJ, USA, 1993. [Google Scholar]
  36. Bansal, J.C.; Singh, P.K.; Pal, N.R. Evolutionary and Swarm Intelligence Algorithms; Springer: Cham, Switzerland, 2019; Volume 779. [Google Scholar]
  37. Ogata, K. System Dynamics/Katsuhiko Ogata, 4th ed.; Pearson/Prentice Hall: Upper Saddle River, NJ, USA, 2004. [Google Scholar]
  38. Greiner, W. Lagrange Equation for Nonholonomic Constraints. In Classical Mechanics: Systems of Particles and Hamiltonian Dynamics; Springer: Berlin/Heidelberg, Germany, 2010; pp. 301–310. [Google Scholar] [CrossRef]
  39. Klancar, G.; Zdesar, A.; Blazic, S.; Skrjanc, I. Wheeled Mobile Robotics: From Fundamentals towards Autonomous Systems; Butterworth-Heinemann: Oxford, UK, 2017. [Google Scholar]
  40. Tam, C.; Bucknall, R. Cooperative path planning algorithm for marine surface vessels. Ocean Eng. 2013, 57, 25–33. [Google Scholar] [CrossRef]
  41. Pedapati, P.K.; Pradhan, S.K.; Kumar, S. Kinematic Control of an Autonomous Ground Vehicle Using Inverse Dynamics Controller. In Advances in Smart Grid Automation and Industry 4.0; Reddy, M.J.B., Mohanta, D.K., Kumar, D., Ghosh, D., Eds.; Springer: Singapore, 2021; pp. 313–324. [Google Scholar]
  42. Peng, F.; Zheng, L.; Duan, Z.; Xia, Y. Multi-Objective Multi-Learner Robot Trajectory Prediction Method for IoT Mobile Robot Systems. Electronics 2022, 11, 2094. [Google Scholar] [CrossRef]
  43. Wang, C.; Ma, L.; Li, R.; Durrani, T.S.; Zhang, H. Exploring Trajectory Prediction Through Machine Learning Methods. IEEE Access 2019, 7, 101441–101452. [Google Scholar] [CrossRef]
  44. Peng, X.; Gao, X.; Yang, S. Environment identification-based memory scheme for estimation of distribution algorithms in dynamic environments. Soft Comput. 2011, 15, 311–326. [Google Scholar] [CrossRef] [Green Version]
  45. Xiong, N.; Molina, D.; Ortiz, M.L.; Herrera, F. A Walk into Metaheuristics for Engineering Optimization: Principles, Methods and Recent Trends. Int. J. Comput. Intell. Syst. 2015, 8, 606–636. [Google Scholar] [CrossRef] [Green Version]
  46. Wolpert, D.; Macready, W. No free lunch theorems for optimization. IEEE Trans. Evol. Comput. 1997, 1, 67–82. [Google Scholar] [CrossRef]
  47. Storn, R.; Price, K. Differential Evolution—A Simple and Efficient Heuristic for global Optimization over Continuous Spaces. J. Glob. Optim. 1997, 11, 341–359. [Google Scholar] [CrossRef]
  48. Mezura-Montes, E.; Velázquez-Reyes, J.; Coello Coello, C.A. A Comparative Study of Differential Evolution Variants for Global Optimization. In Proceedings of the GECCO ’06—8th Annual Conference on Genetic and Evolutionary Computation, Seattle, WA, USA, 8–12 July 2006; Association for Computing Machinery: New York, NY, USA, 2006; pp. 485–492. [Google Scholar] [CrossRef] [Green Version]
  49. Goldberg, D.E. Genetic Algorithms in Search, Optimization and Machine Learning, 1st ed.; Addison-Wesley Longman Publishing Co., Inc.: Boston, MA, USA, 1989. [Google Scholar]
  50. Deb, K.; Pratap, A.; Agarwal, S.; Meyarivan, T. A fast and elitist multiobjective genetic algorithm: NSGA-II. IEEE Trans. Evol. Comput. 2002, 6, 182–197. [Google Scholar] [CrossRef] [Green Version]
  51. Deb, K.; Agrawal, R.B. Simulated binary crossover for continuous search space. Complex Syst. 1995, 9, 115–148. [Google Scholar]
  52. Deb, K.; Deb, D. Analysing mutation schemes for real-parameter genetic algorithms. Int. J. Artif. Intell. Soft Comput. 2014, 4, 1–28. [Google Scholar] [CrossRef]
  53. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the ICNN’95—International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; Volume 4, pp. 1942–1948. [Google Scholar] [CrossRef]
  54. Shi, Y.; Eberhart, R. Empirical study of particle swarm optimization. In Proceedings of the 1999 Congress on Evolutionary Computation-CEC99 (Cat. No. 99TH8406), Washington, DC, USA, 6–9 July 1999; Volume 3, pp. 1945–1950. [Google Scholar] [CrossRef]
  55. Deb, K. An efficient constraint handling method for genetic algorithms. Comput. Methods Appl. Mech. Eng. 2000, 186, 311–338. [Google Scholar] [CrossRef]
  56. Wang, F.; Zhang, H.; Zhou, A. A particle swarm optimization algorithm for mixed-variable optimization problems. Swarm Evol. Comput. 2021, 60, 100808. [Google Scholar] [CrossRef]
  57. Derrac, J.; García, S.; Molina, D.; Herrera, F. A practical tutorial on the use of nonparametric statistical tests as a methodology for comparing evolutionary and swarm intelligence algorithms. Swarm Evol. Comput. 2011, 1, 3–18. [Google Scholar] [CrossRef]
  58. Rodríguez-Molina, A.; Villarreal-Cervantes, M.G.; Serrano-Pérez, O.; Solís-Romero, J.; Silva-Ortigoza, R. Optimal Tuning of the Speed Control for Brushless DC Motor Based on Chaotic Online Differential Evolution. Mathematics 2022, 10, 1977. [Google Scholar] [CrossRef]
Figure 1. The differential drive mobile robot.
Figure 1. The differential drive mobile robot.
Mathematics 10 03990 g001
Figure 2. Diagram of forces, torques, and non-holonomic constraints of the differential mobile robot.
Figure 2. Diagram of forces, torques, and non-holonomic constraints of the differential mobile robot.
Mathematics 10 03990 g002
Figure 3. PSO convergence plots for different optimization processes during an arbitrary D-Bug0/PSO run.
Figure 3. PSO convergence plots for different optimization processes during an arbitrary D-Bug0/PSO run.
Mathematics 10 03990 g003
Figure 4. Behavior of D-Bug0/PSO for an arbitrary run. The complete scenario is shown every 1.5 (s).
Figure 4. Behavior of D-Bug0/PSO for an arbitrary run. The complete scenario is shown every 1.5 (s).
Mathematics 10 03990 g004
Figure 5. Behavior of Bug0− for an arbitrary run. The complete scenario is shown every 1.5 (s).
Figure 5. Behavior of Bug0− for an arbitrary run. The complete scenario is shown every 1.5 (s).
Mathematics 10 03990 g005
Figure 6. Behavior of Bug0+ for an arbitrary run. The complete scenario is shown every 1.5 (s).
Figure 6. Behavior of Bug0+ for an arbitrary run. The complete scenario is shown every 1.5 (s).
Mathematics 10 03990 g006
Table 1. Dynamic behavior of obstacles in the test scenario for t [ 0 , 15 ] (s).
Table 1. Dynamic behavior of obstacles in the test scenario for t [ 0 , 15 ] (s).
Obstaclex (m)y (m)
1 1.0 0.1 sin t 2
2 2.0 + 0.2 cos t 2 0.2 + 0.2 sin t 2
3 3.0 0.1 cos t 2
4 1.0 + 0.5 cos t 2 0.25
5 3.0 + 0.5 sin t 2 0.25
6 2.0 + 2.0 sin 2 t 0.5
7 2.0 + 2.0 cos 2 t 0.5
Table 2. Descriptive statistics on the results of the 30 independent executions with D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO.
Table 2. Descriptive statistics on the results of the 30 independent executions with D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO.
MeasureIndicatorD-Bug0/DED-Bug0/GAD-Bug0/PSO
Path length (m)Mean4.09554.10854.0909
Std.0.00440.00570.0017
Min.4.08974.09764.0887
Max.4.10244.11834.0947
CollisionsMean0.00000.00000.0000
Std.0.00000.00000.0000
Min.0.00000.00000.0000
Max.0.00000.00000.0000
Arrival time (s)Mean12.189012.217012.1860
Std.0.01400.01290.0122
Min.12.180012.210012.1800
Max.12.210012.240012.2100
Speed (m/s)Mean0.33600.33630.3357
Std.0.00030.00030.0003
Min.0.33540.33560.3351
Max.0.33650.33700.3361
Execution time (s)Mean3.20643.22543.1925
Std.0.05080.04740.0390
Min.3.16103.17003.1510
Max.3.42603.42203.3800
Table 3. Pairwise Wilcoxon tests over the results of the 30 independent executions with D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO.
Table 3. Pairwise Wilcoxon tests over the results of the 30 independent executions with D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO.
MeasureTest R + R p-Value
Path lengthD-Bug0/DEvs.D-Bug0/GA46413.7252 × 10 9
D-Bug0/DEvs.D-Bug0/PSO434222.3666 × 10 5
D-Bug0/GAvs.D-Bug0/PSO04651.8626 × 10 9
CollisionsD-Bug0/DEvs.D-Bug0/GA001.0000
D-Bug0/DEvs.D-Bug0/PSO001.0000
D-Bug0/GAvs.D-Bug0/PSO001.0000
Arrival timeD-Bug0/DEvs.D-Bug0/GA25302.0342 × 10 5
D-Bug0/DEvs.D-Bug0/PSO48720.4578
D-Bug0/GAvs.D-Bug0/PSO03254.8413 × 10 6
SpeedD-Bug0/DEvs.D-Bug0/GA813840.0012
D-Bug0/DEvs.D-Bug0/PSO387780.0009
D-Bug0/GAvs.D-Bug0/PSO46239.3132 × 10 9
Execution timeD-Bug0/DEvs.D-Bug0/GA3101250.0466
D-Bug0/DEvs.D-Bug0/PSO136.5328.50.0494
D-Bug0/GAvs.D-Bug0/PSO434220.0001
Table 4. Summary of the pairwise Wilcoxon tests over the results of the 30 independent executions with D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO.
Table 4. Summary of the pairwise Wilcoxon tests over the results of the 30 independent executions with D-Bug0/DE, D-Bug0/GA, and D-Bug0/PSO.
MeasureD-Bug0/DED-Bug0/GAD-Bug0/PSO
Path length102
Collisions000
Arrival time101
Speed120
Execution time102
Total wins425
Table 5. Results of D-Bug0/PSO after 30 independent runs.
Table 5. Results of D-Bug0/PSO after 30 independent runs.
RunPath Length (m)CollisionsArrival Time (s)Speed (m/s)Execution Time (s)
14.0904012.18000.33583.3800
24.0901012.18000.33583.2160
34.0925012.18000.33603.1840
44.0925012.21000.33523.1880
54.0893012.18000.33573.2430
64.0897012.18000.33583.1800
74.0912012.18000.33593.1940
84.0894012.18000.33573.1780
94.0924012.21000.33523.1810
104.0947012.21000.33543.2050
114.0887012.18000.33573.1820
124.0908012.18000.33593.1770
134.0933012.21000.33523.1800
144.0893012.18000.33573.1770
154.0945012.21000.33533.1900
164.0900012.18000.33583.1730
174.0891012.18000.33573.1810
184.0898012.18000.33583.1960
194.0927012.18000.33603.1870
204.0904012.18000.33583.1830
214.0901012.18000.33583.1870
224.0898012.18000.33583.1790
234.0888012.18000.33573.1940
244.0898012.18000.33583.1780
254.0894012.18000.33573.1800
264.0936012.18000.33613.1510
274.0902012.18000.33583.1870
284.0923012.18000.33603.1560
294.0897012.18000.33583.2020
304.0919012.21000.33513.1850
Mean4.09090.000012.18600.33573.1925
STD0.00170.00000.01220.00030.0390
Min4.08870.000012.18000.33513.1510
Max4.09470.000012.21000.33613.3800
Table 6. Results of Bug0− after 30 independent runs.
Table 6. Results of Bug0− after 30 independent runs.
RunPath Length (m)CollisionsArrival Time (s)Speed (m/s)Execution Time (s)
15.35621919.11000.28030.0030
25.35621919.11000.28030.0020
35.35621919.11000.28030.0020
45.35621919.11000.28030.0020
55.35621919.11000.28030.0040
65.35621919.11000.28030.0030
75.35621919.11000.28030.0030
85.35621919.11000.28030.0030
95.35621919.11000.28030.0040
105.35621919.11000.28030.0030
115.35621919.11000.28030.0040
125.35621919.11000.28030.0040
135.35621919.11000.28030.0040
145.35621919.11000.28030.0030
155.35621919.11000.28030.0030
165.35621919.11000.28030.0030
175.35621919.11000.28030.0030
185.35621919.11000.28030.0030
195.35621919.11000.28030.0030
205.35621919.11000.28030.0030
215.35621919.11000.28030.0040
225.35621919.11000.28030.0040
235.35621919.11000.28030.0030
245.35621919.11000.28030.0030
255.35621919.11000.28030.0030
265.35621919.11000.28030.0040
275.35621919.11000.28030.0030
285.35621919.11000.28030.0030
295.35621919.11000.28030.0030
305.35621919.11000.28030.0080
Mean5.35621919.11000.28030.0033
Std.0.000000.00000.00000.0011
Min.5.35621919.11000.28030.0020
Max.5.35621919.11000.28030.0080
Table 7. Results of Bug0+ after 30 independent runs.
Table 7. Results of Bug0+ after 30 independent runs.
RunPath Length (m)CollisionsArrival Time (s)Speed (m/s)Execution Time (s)
15.04251616.35000.30840.0010
25.04251616.35000.30840.0030
35.04251616.35000.30840.0030
45.04251616.35000.30840.0020
55.04251616.35000.30840.0020
65.04251616.35000.30840.0020
75.04251616.35000.30840.0030
85.04251616.35000.30840.0030
95.04251616.35000.30840.0030
105.04251616.35000.30840.0030
115.04251616.35000.30840.0030
125.04251616.35000.30840.0030
135.04251616.35000.30840.0030
145.04251616.35000.30840.0020
155.04251616.35000.30840.0030
165.04251616.35000.30840.0030
175.04251616.35000.30840.0030
185.04251616.35000.30840.0030
195.04251616.35000.30840.0030
205.04251616.35000.30840.0030
215.04251616.35000.30840.0030
225.04251616.35000.30840.0030
235.04251616.35000.30840.0030
245.04251616.35000.30840.0030
255.04251616.35000.30840.0030
265.04251616.35000.30840.0030
275.04251616.35000.30840.0020
285.04251616.35000.30840.0030
295.04251616.35000.30840.0030
305.04251616.35000.30840.0030
Mean5.04251616.35000.30840.0028
Std.0.000000.00000.00000.0005
Min.5.04251616.35000.30840.0010
Max.5.04251616.35000.30840.0030
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Rodríguez-Molina, A.; Herroz-Herrera, A.; Aldape-Pérez, M.; Flores-Caballero, G.; Antón-Vargas, J.A. Dynamic Path Planning for the Differential Drive Mobile Robot Based on Online Metaheuristic Optimization. Mathematics 2022, 10, 3990. https://0-doi-org.brum.beds.ac.uk/10.3390/math10213990

AMA Style

Rodríguez-Molina A, Herroz-Herrera A, Aldape-Pérez M, Flores-Caballero G, Antón-Vargas JA. Dynamic Path Planning for the Differential Drive Mobile Robot Based on Online Metaheuristic Optimization. Mathematics. 2022; 10(21):3990. https://0-doi-org.brum.beds.ac.uk/10.3390/math10213990

Chicago/Turabian Style

Rodríguez-Molina, Alejandro, Axel Herroz-Herrera, Mario Aldape-Pérez, Geovanni Flores-Caballero, and Jarvin Alberto Antón-Vargas. 2022. "Dynamic Path Planning for the Differential Drive Mobile Robot Based on Online Metaheuristic Optimization" Mathematics 10, no. 21: 3990. https://0-doi-org.brum.beds.ac.uk/10.3390/math10213990

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop