Next Article in Journal
Effects of a Personalized Exercise Rehabilitation Device on Dynamic Postural Balance for Scoliotic Patients: A Feasibility Study
Previous Article in Journal
Electrical Properties and Biological Synaptic Simulation of Ag/MXene/SiO2/Pt RRAM Devices
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Time Minimization of Rescue Action Realized by an Autonomous Vehicle

by
Zdzisław Gosiewski
* and
Konrad Kwaśniewski
Department of Automatics and Robotics, Faculty of Electrical Engineering, Bialystok University of Technology, 15-351 Białystok, Poland
*
Author to whom correspondence should be addressed.
Electronics 2020, 9(12), 2099; https://doi.org/10.3390/electronics9122099
Submission received: 27 October 2020 / Revised: 28 November 2020 / Accepted: 4 December 2020 / Published: 9 December 2020
(This article belongs to the Section Systems & Control Engineering)

Abstract

:
In rescue operations, the full time of action plays important role. It is the sum of the planning, travel, and manipulation (in the action place) phase times. The time minimization of the first two phases by autonomous vehicle for remote action is considered in the paper. For a known a priori map, the path planning consists of local optimal decisions collected next in the general algorithm of the optimal path. Such an approach significantly reduces time of path planning. The robot features and known sparse obstacles reduce the allowable robot speeds. The time of travel is calculated from an allowable velocity profile. Therefore, it can be used to estimate the travel performance. Genetic algorithm and random search-based methods for path finding with travel time optimization are used and compared in the paper. All the proposed time optimization solutions of rescue operations are checked during computer simulations, and results of the simulations are presented.

1. Introduction

Mobile robotics is a still growing field of scientific research. Every year it brings new challenges and areas in which mobile robots can help people in dangerous or just simple tasks. These could be a rescue patrol (e.g., searching for earthquake or avalanche victims, people who get lost in a rough terrain), goods transport, medicine transport, or patrol in large areas. All of those tasks are often performed in a rough terrain and the fast movement is frequently needed. Therefore, the robots not only have to be able to move fast mechanically, but also algorithmically. It is obvious that time of travel highly depends on the shape of path, which is chosen.
Many methods are developed to solve the path finding problem. One of the most known is the A* algorithm [1]. It needs the map to be represented as a graph. The result path is discrete and has to be processed to be useful for rover-like robots. Other proposed methods in the literature use artificial neural networks [2,3]. Their main disadvantages are the teaching process and the modelling problem, so they are difficult to use for global path optimization. Other optimization methods are also frequently used for path finding. Genetic algorithms [4,5,6,7,8], evolutionary algorithms [9], particle swarm optimization [10,11], and ant colony optimization [12] can be indicated as examples. Some popular methods used for path finding are fuzzy logic [13], potential fields [14], and combining these [15,16] or other hybrid ones [17]. The methods mentioned above often look for the shortest path or are strictly focused on the avoidance of obstacles. As the shortest path is not always the fastest one, the problem of finding paths under the shortest travel time criterion remains an interesting field for the research, whose importance can increase with the increasing global usage of mobile robots.
The typical rescue action can be divided into two parts: search for the victim and transporting the victim. In this paper, we consider the second case, where the location of the victim and the map of the area are known a priori. This information can be obtained by, for example, UAV. Then, the most important thing to do is go to the victim and come back as fast as possible. The considered areas that the proposed method is suitable for are, for example, plain fields, forests, and open spaces in urban areas. It can also be used inside buildings, but only with the map. It can be assisted with an area searching algorithm; in which case, the first stage would be search for the victim with simultaneous mapping of the area, and next, the presented method would be used for fast return to the rescue headquarters or hospital.
In the literature, the recent research is focused on searching for the victim and on the travel in general [18,19,20,21]. The problem often is not considered under the travel time condition. The aim of the research is to develop a fast method to obtain travel time-optimized paths in an a priori known environment or in an environment previously mapped by the robot itself. Two path finding methods are presented in the paper. The first one is based on a genetic algorithm and the second one on a random search algorithm. Each method is described in two versions: with path fitness estimation and with travel time obtained from a velocity profile generator. Both methods are designed in a specified hierarchy, which is presented in Figure 1. It resulted from the analysis of effects presented in the paper [4], which showed the limitations of the methods that operate directly on the path shape. The main limitation is a constant complexity of the path (i.e., constant control points number). To overcome that inconvenience, another approach was chosen: the optimization method, which does not operate on path parameters itself, but on the parameters of a whole path generation algorithm (WPGA). The WPGA creates the path from parts of primary paths that are chosen as locally optimal. An important aspect about the primary path generation algorithm (PPGA) is that the path is chosen by the algorithm from a discrete set of paths. This reduction of a solution space significantly improves the performance of the method.
The reason for making a comparison between a genetic algorithm and a random search algorithm is a result of the fact that the previously proposed GA-based method [22] has very long times of execution. The previous GA was used only for the estimation of fitness. Since the velocity profile generator has been invented, it has brought an interesting opportunity to compare the effectiveness of the methods based on the fitness estimation and approximated travel time. Moreover, the comparison also shows how well the proposed fitness estimation method describes the quality of the path under the travel time condition.
Another improvement described in the paper is the robot velocity reduction near the obstacles. As a part of the velocity profile generator, it is based on the heuristic knowledge of humanity gained through the ages, that slower motion allows for more precise movement. It is important in the obstacle avoidance problem, because even movement along a proper path can lead to collision if the robot does not follow the path precisely enough. Summarizing, the aims of the research are as follows:
  • find short execution time of path finding algorithms on embedded computers;
  • realize travel time optimization for robot operating in the area whose map is known a priori.

2. Map Model

The algorithm is executed as soon as the environment map was obtained. Due to the long execution time, the work on an a priori known map is acceptable only. It is unfit for real time use. The map is modelled as a binary bitmap with terrain approximated as a flat space (Figure 2). The raster of the map is marked by red grid lines. In the maps presented in the paper, as well as the axes, it will be hidden for clarity. The dark pixels are considered as obstacle-free and the bright ones as inaccessible for a robot. It is assumed that size of one pixel is large enough to be able to contain the whole robot with a safety margin. However, the raster maps have a large disadvantage—their size is usually constant. To overcome it, fields with obstacles are firstly saved as a list of points. Then, it is rasterized. It allows to the map size to be adjusted for all the obstacles. Of course, the point list could be used without rasterization, although the collision detection in this case needs to check the whole obstacles list for every pixel of rasterized path or to do the geometrical collision detection for every path segment. The collision detection on raster map needs much fewer tests. It affects performance significantly.
Other ways of map modelling are not used since only the raster map gives a fast way of collision detection. Even though it needs the path to be rasterized, which is time-consuming, it is still more effective than e.g., obstacle lists, because in that case every segment of the path has to be tested for intersection with all the obstacles. This makes it very inefficient for long complex paths. The 3D map models are unnecessary in the considered case as the problem can be reduced to 2D problem.
Someone could ask how to obtain the map of the area in the case of, for example, earthquake, because it can make large changes in the environment that makes the previously obtained maps obsolete. The answer is that it can be provided by UAVs or aeroplanes. The robot can also actualize the map it has got saved in the memory. However, as long as this problem is not the aim of the paper, this question will not be discussed further.

3. Genetic Algorithm for Path Finding

The genetic algorithm for path finding was presented in [22] and its execution time was long. The main feature of the proposed algorithm is that it does not work on the trajectory shape directly but through the path generation algorithm. It is more efficient, due to large solution space when the GA modifies the path control point coordinates. Longer paths create longer chromosomes and expand greatly a solution space, while the path generation algorithm reduces chromosome size to just a few values (dependently on the chosen method of a path generation). Another advantage of this approach is no limitation of a length of the path. If a chromosome contains control point coordinates, their number cannot be increased.
Generally, the proposed method can be described in the form seen in Figure 3.

3.1. Properties of the GA

The GA for path finding has to, apart from good convergence, return results as fast as possible. To achieve this, the following shape of the GA was chosen:
  • Chromosome of floating-point numbers;
  • Arithmetical crossing;
  • Small population: 30 individuals;
  • Roulette selection;
  • Elitism: six best individuals remain after each epoch;
  • Termination after given number of epochs;
  • Minimization of the fitness values.
For the path generation task, the whole path generation algorithm is used. To reduce the parameters number, the lists of parameters are generated. It is described further in Section 6.2.

3.2. Chromosome

A chromosome consists of three values: maximal radius (floating point value), maximal angle range (floating point value), and maximal search point number (unsigned integer value). They describe a set of parameters for WPGA (whole path generation algorithm). For details, please look in Section 6.3.

4. Random Search Algorithm for Path Finding

During tests of the GA pathfinding method it has been noticed that continuously changing parameters do not result in similar paths, i.e., the function represented by whole path generation algorithm (see Section 6.3) is discontinuous. Thus, the GA can have problems in achieving satisfying results, especially in acceptable time. Therefore, the random search method that can be used to solve problems, even in discontinuous spaces, was tested.
The random search algorithm (Figure 4) is simple. At the first step, the solution parameters are chosen randomly. Then, the fitness of the solution is calculated. Those parameters and fitness values are saved as current ones. At the second step, the process of getting parameters randomly for a new set and fitness calculation for it is done again. If the new solution has better fitness than the current one, it is set as a current. The last step is repeated until the given number of epochs will be satisfied. Then, the current solution is returned as a result.
As it was in the case of the GA, the whole path generation algorithm is used for the path generation task. The number of parameters is reduced by using the parameter generator. Solutions of the random search algorithm are described in the same way as chromosomes in the GA. Three parameters (maximal radius, maximal angle range, and maximal point number) are used by the parameters generator to get parameters set suitable for the WPGA.

5. Path Model

The path processing is the most time absorbing part of computation. A proper model of a path is fundamental to obtain good robot performance. In the literature, various models are in use. The most popular are polylines of straight segments, b-splines, and NURBS curves [23]. The first one is fast to compute, but before setting it in, a robot it needs to be smoothed. On the other hand, b-splines and NURBS curves provide smooth paths. However, they are much more computationally complex and some parameters like radius have to be computed in the form of discrete set with some given resolution. For our application, a model is chosen that is free from these disadvantages. It is a polyline, built of arc and straight-line segments, later referred for clarity as arcline (as long as a straight segment can be considered as an arc of infinite radius).
The arcline can be defined as a list of control points P 1 ,   P 2 , and an initial tangent vector t 1 . All of the tangent vectors of the arcline are unit vectors. The A n arc is always tangential to the A n 1 arc at the point P n .

5.1. Arcline Computation

The arcline is computed by calculating sequent segments. Every segment is entirely described by three parameters (Figure 5):
  • Start point P i ;
  • End point P i + 1 ;
  • Initial tangent vector t i .
Let’s call the i -th segment as A i . Then, the segment can be defined by formula:
A i = segment ( P i , P i + 1 , t i )
for 1 i n 1 where n is a number of arcline control points. Thus, the arcline L   is the list of following segments:
L = [ A 0 , A 1 , , A n 1 ]
Before computation of each segment, it needs to be check, whether the segment belongs to straight or to arc segment category. It is done by comparison of two unitized vectors: tangent vector (Equation (4)) and vector of start and end point (Equation (3)). For A i segment they are described as follows:
t p 1 p 2 = normalize ( P i P i + 1 )
t t n = normalize ( t i )
If those two vectors are equal, i.e., their corresponding coordinates are equal, the segment is straight. Otherwise, it is an arc segment.

5.2. Straight Segment Computation

Computation of a straight segment is simple. The only property that can be computed is its length (Equation (5)). The tangent vector at the end point is equal to the initial tangent vector of the segment (Equation (6)).
A l = | P i P i + 1 |
t i + 1 = t i

5.3. Arc Segment Computation

The arc segment (Figure 6) parameters that can be calculated are:
  • Arc radius A r (Equation (9));
  • Arc length A l (Equation (11));
  • Arc angle β (Equation (10));
  • Arc circle centre point A C (Equation (12));
  • End tangent vector t i + 1 (Equation (8)).
They are described by following formulae:
α = angle _ signed ( t P i P i + 1 , t t n )
t i + 1 = rotate ( t t n , 2 α )
A r = abs ( | P i P i + 1 | 2 sin α )
β = 2 α
A l = abs ( β A r )
A C = P i + A r   normalize ( rotate ( t i ,   π 2 sign ( α ) ) )
where the normalize   ( t ) is a function that unitizes the t vector, rotate   ( t , α ) is a function that rotates the t vector by the α angle, the abs ( a ) function returns the absolute value of a , sign ( a ) returns the sign of the a and angle _ signed ( t 1 ,   t 2 ) returns the angle with a sign between vectors t 1 and t 2 .
The angle β of the arc is a dubled angle between vectors t i and P i P i + 1 . The sign of the angle β defines the side, on which the arc is built. The end tangent vector t i + 1 is obtained by rotation of the start tangent vector by angle β .

6. Path Generation

To make the process of path optimization faster, the optimization methods should not work on the path shape itself. High path complexity expands the solution space significantly, which decreases algorithm efficiency. The solution for that problem is to design an algorithm that sequentially generates a path based on just few parameters. This approach reduces the solution space and allows to operate on the paths of different complexity.
The idea is to look for the locally best short path, then move along it some distance and, if it is not a target point, repeat the process. The path generation algorithm consists of two parts: primary path generation algorithm (PPGA) and whole path generation algorithm (WPGA). The first part returns the local path and the second one uses the PPGA to make a path from start to end point. The WPGA flowchart is presented in Figure 7.

6.1. Collision Detection

An important part of the path generation is detection of collisions. As the map model is a raster map, a collision occurs when the rasterized path has at least one common pixel with obstacle pixels of the map.

6.2. Primary Path Generation Algorithm—Local Path

There exist almost infinite number of paths that can be built in some area (actually, it is limited by hardware capabilities). As was shown in [20] the process of finding path in that wide solution space can take a long time. However, it can be improved by using a discrete solution space instead of the continuous one. What is more, the discrete set can be reduced to few paths that cover only a part of the area around the start point, within which physical constraints allow the robot to move. The number of the prototype paths affects the quality and performance of the algorithm. More prototype paths increase quality and unfortunately increase the computation time, while fewer do exactly the opposite. The prototype path number has to be adjusted to the computation platform performance and to the quality requirements. The sensitivity study of the PPGA will be presented in the further research.
In the method proposed in this paper, the prototype path exploits the control points that lie on the circular layers (Figure 8) around the start point and are distributed equidistantly on both sides of the initial tangent vector.
The number of layers is equal to number of control points that build the arcline. The first layer has only one point, which is the robot position. The initial tangent vector defines the orientation of the robot. Every next layer has to have an equal or larger amount of points. Points on every layer are distributed inside of the angle range (Figure 8 and Figure 9). The angle ranges can vary freely. They are adjusted experimentally, depending on the environment in which the robot will operate.
After determination of positions of the points on the layers, they have to be gathered into control point lists that describe each path from the prototype paths set. Shorter layers are stretched to agree in length with the widest layer, as can be seen in Figure 10. The example of the set of the prototype paths is presented in Figure 11.
Finally, the best path is selected from the set (Figure 10). It is done under two criteria: obstacle avoidance fitness and distance fitness. The distance fitness is the Cartesian distance between the global target point and the final point of the prototype path. It ensures that the path leads to the destination point. To obtain the obstacle avoidance fitness, the rasterization of the path is needed since it is described parametrically. A mechanism of security margin is applied by increasing path width by 2 pixels—1 for each side of the path. Then, the map status of corresponding pixels is checked. If any of path pixels collides on the map, the whole path is considered as an incorrect path. The algorithm returns the path from correct paths that has the lowest distance fitness value. It has to be noted that this method is very computationally efficient and can be used as standalone algorithm for pathfinding in unknown environment.

6.3. Whole Path Generation Algorithm—Global Path

The whole path generation algorithm builds the path using the primary path generation algorithm. The PPGA is used for setting the path in local area. Then, the current robot position is moved along the local path by a given distance. The length of the local path has to be equal or longer than the distance of the movement. This process repeats until the distance to the target point is shorter than or equal to the maximum radius of the PPGA radii layers. Then, the layers radii are scaled down to make the maximum radius equal to the distance to the target point. The execution of the algorithm ends when the destination point is reached within the given tolerance range. The points obtained at every step are sequentially added to the way point list. The WPGA is presented below in the form of a list of steps.
  • Until the destination point is reached:
    1.1.
    Scale the radii of the layers of PPGA if the maximal radius is equal to or less than distance between current position and target point to match to this distance.
    1.2.
    Execute the PPGA for current position.
    1.3.
    Set a point at given step distance on the obtained local path.
    1.4.
    Add the obtained point to the way point list.
    1.5.
    Set the obtained point as a new current point and the tangent vector at this point as a new robot orientation.
  • Return the result path as way point list.
The WPGA needs the following set of parameters to work:
  • Start and destination points
  • Start orientation
  • Search radii list
  • Search angle ranges list
  • Point number on each layer list
  • Obstacle list

6.4. Parameter Set Generation

The WPGA parameters such as start and destination points, start orientation, and obstacle list are fundamental for every path definition and remain unmodified during the optimization process because they are environment conditions. The rest of them are used for the path shape definition. However, they are not suitable for use in optimization methods like the GA, due to the fact that they are lists and their length can vary. Moreover, more parameters mean a wider solution space, which affects the performance negatively. To overcome this inconvenience, the parameter list should be generated. It has to be based on as small as possible a number of its parameters and be fast and easy to compute.
Thus, the number of layers is set as three. The parameter lists are computed according to formulae given in Equations (13)–(15). Layers of radii S r a d i i are described by Equation (13), layers of angle ranges S r a n g e s by Equation (14), and layers of point numbers S p o i n t s by Equation (15).
S r a d i i = [ 0 , R m a x 2 , R m a x ]
S r a n g e s = [ π 4 , δ m a x 2 , δ m a x ]
S p o i n t s = [ 1 ,   round ( 0.8 P m a x ) , P m a x ]
As can be seen, only three parameters are needed to generate these lists. They are maximum radius R m a x , maximum angle range δ m a x , and maximum point number P m a x .

7. Evaluation of Path Fitness

Evaluation of path fitness can be done in two ways. The first one is the generation of a velocity profile and then using the obtained travel time as a fitness value. The second one is the estimation of quality of the path based on its shape. In experiments, both methods are compared.

7.1. Estimation of Path Fitness

One of the possibilities of computation time reduction is the simplification of the most frequently used parts of the method. Heuristic and meta-heuristic optimization methods do not need the exact physical values. They need just to compare solutions and choose the best ones. Hence, the approximation of fitness can be used as well. The proposed estimation is based on three parts, which describe how fast a given path can be (Equation (16)). The first one is distance—a shorter path is assumed to be faster than longer one. Thus, the quantity of distance of the path is equal to the sum of lengths of all path segments (Equation (17)). The second part is speed. As can be seen in Equation (18), it depends on one path parameter only: radius. A larger radius means higher maximum speed on the path segment. Therefore, the quantity of speed equals the sum of the radii of all path segments (Equation (18)). The last part that affects travel time is acceleration. The acceleration quantity is approximated by adding up differences between every pair of radii of the next segments (Equation (19)).
f ( o ) = d ( o ) c d + s ( o ) c s + a ( o ) c a
d ( o ) = i A l o i
s ( o ) = i A r o i
a ( o ) = i A r o i + 1 A r o i
In Equation (16) c d ,   c s ,   c a are coefficients of distance, speed, and acceleration, respectively. In Equations (17)–(19) A l o i means the length of i -th segment of the o path and A r o i means the radius of i -th segment of the o path.

7.2. Velocity Profile Generation

Another method is the generation of the velocity profile for the path. This method gives simulated travel time, not approximated fitness. The velocity profile generation algorithm is presented below as a list of steps.
  • Calculate maximum speed on arcs (Equation (20)).
  • Decrease the speed on slower parts (obtained from obstacle closeness detection, see Section 7.3) by 50%.
  • Set maximum robot speed for arcs, whose maximum speed is higher than max robot speed.
  • Find the points where higher speed changes to lower speed ( P H L ).
  • Initialize robot position on the path (distance 0 m) and speed (0 m/s). Initialize robot speeds list as an empty list and simulation time list as a list with first element equal to 0.
  • Repeat until the end of the path is not reached:
    6.1.
    Calculate deceleration distances ( d d i s t a n c e , see Equations (21)–(23)) to every P H L point for current speed.
    6.2.
    If any of the deceleration distances covers current robot position on the path and speed is higher than corresponding maximum speed of the arc of P H L point then enable deceleration. Otherwise, if current speed is lower than maximum speed on current path arc then enable deceleration.
    6.3.
    If, after acceleration, speed will not exceed current maximum speed and acceleration is enabled then accelerate.
    6.4.
    If, after deceleration, speed will not exceed 0 m/s and deceleration is enabled then decelerate.
    6.5.
    Update robot speed and position on the path. Update simulation time. Add robot speed to the end of the speeds list and add current simulation time to the simulation time list.
Maximum speed on arc is computed for each path segment. For the straight segments it is equal to maximum robot speed. For arc segments it is computed by Equation (20). Maximum velocity for arcs is formulated from friction and centrifugal forces. It is a square root of friction coefficient μ , standard gravity g and arc radius A r . The ground is assumed to be always flat.
v m a x = μ g A r
Deceleration distances are calculated using the following Equations (21)–(23). The Δ a is given acceleration, the Δ t is given step size, the v c is current step speed, and the v t is target speed.
a Δ = Δ a Δ t
t Δ = v c v t a Δ Δ t
d d i s t a n c e = Δ a t Δ 2 2 + v c t Δ
The resulting travel time is the value of the last element of the simulation time list. The robot speeds list contains the velocity profile for the given path. In Figure 12 can be seen an example of a velocity profile, in which can be easily recognized the parts of acceleration, constant speed, and deceleration.

7.3. Closeness Ranges Detection

Closeness ranges are ranges on the path length in which the obstacles lay close to the path. Basing on the heuristic knowledge gained by humanity by centuries, it is better to slow down, when the human or vehicle passes close to an obstacle. This behaviour provides more rigidity to errors in driving when the possibility of collision is higher. In the velocity profile generation, this approach is used. The maximum velocity in closeness ranges is reduced by 50% to maximum speed implied from the path properties.
In the proposed method, the closeness ranges are detected by obstacles detection on the map in the window of a given size (larger than 1 × 1). The window is moved along a rasterized path pixel by pixel, and when an obstacle is detected in the window, the current point is saved as a start point of the range. Then, the window continues the movement, and when it reaches the window with no obstacles, the position is saved as end point of the range. Finally, both positions are added together to the list of closeness ranges. The process continues until the end of the path is reached by the window. As a result, the list of closeness ranges is obtained.

8. Computer Simulations

To compare efficiency of the described methods, the computer tests were carried out.

8.1. Methodology

For the purpose of the test, three different maps are used (Figure 13). The first map simulates the forest environment with the randomly distributed trees. The second simulates an area with some buildings or boxes. The third map is designed to test the methods in some kind of complex environment, in which it is necessary to produce a complex path with many bends. The start point is marked by blue cross inside of the blue circle and the target point is marked by yellow cross inside of the yellow circle. In the maps with paths, the start and target points markings are omitted.
There are two methods: the genetic algorithm and the random-search, each in two versions: first, using an estimated path fitness, and second, using travel time fitness from velocity profile generator. It gives four algorithms to be tested. For each test, two values are saved: time of algorithm execution and result travel time. The travel time is computed using the above-mentioned velocity profile generator. All the tests were performed on the same platform: PC computer with AMD Ryzen 5 3600X processor (TSMC, Hsinchu, Taiwan). The algorithms are implemented in Python 3.6. All the computations are performed in single thread. The robot always starts in the middle of the top of the map and the target point is in the middle of the bottom of the map. Each map is of the same dimensions—100 × 200 px.
The robot maximum speed was set to v m a x = 10   m / s and the friction coefficient is set to 0.3. Other significant parameters of the methods are collected in the Table 1 and Table 2. For the GA, the parameters: population size and number of epochs greatly affect the computation time and have to be as low as possible, maintaining a low number of cases, when the algorithm returns no correct path (correct path is a path that leads to the target). The parameters: step size and maximum points number affect the path flexibility. Too large maximum points number also increases computation time. They have to be tuned adequately to the expected complexity of the map. The maximum angle range describes the mechanical constraints of the robot (the maximal turning radius).

8.2. Results

The results are collected in Table 3. Table 4 shows average times of execution and travel for each map. In Table 5, the standard deviations of execution and travel times are presented. In Table 6 and Table 7, the percentage difference in times can be seen. The times of genetic algorithm-based method in fitness estimation variant are used as a reference. The following abbreviations are used in the tables: ‘GA’—genetic algorithm, ‘ex.’—execution, ‘VP’—velocity profile, ‘RS’—random search.
Figure 14 shows example paths on maps 1, 2, and 3 obtained by random search with velocity profile method. Figure 15, Figure 16 and Figure 17 present velocity profiles for those paths, respectively.
Values in the Table 6 and Table 7 are computed by using of Equation (24), where d f is difference in percent, t c is time to be compared, t G A is time of the GA method. Thie formula is used for both execution and travel times.
d f = t c t G A t G A 100 %
The first observation is that random search methods are generally much more time efficient than genetic algorithm-based ones. As can be seen in Table 7, the execution times are better for more than 90%. In comparison to the GA algorithm with fitness estimation, for simple maps such as map 1, the quality of the results of other methods do not differ much. The difference is more significant as the map complexity increases. The methods that use the velocity profile generator gives better results. Although the RS method with fitness estimation gives worse results for maps 1 and 2, for map 3 it is better for over 10% and the result quality is almost the same as for the GA VP method. What is surprising is that the RS VP result for the most complex map is worse than the two mentioned methods and is better than the GA for only approximately 4%. Generally, it can be said, that the best method according to travel time is the GA VP. Unfortunately, it is also the method with the worst performance. For the most complex map, its execution time is worse for almost 130% than the GA, when the random search-based methods are better for over 90%. It is worth noting that the RS-based methods have more stable execution times (see Table 3) than the GA-based ones. Comparing that with absolute times of execution from Table 4, it can be seen that execution times of the RS methods are from range 2–3.5, when those of the GA are up to 50 times longer. In the case of the RS-based methods, the difference between execution times of the fitness estimation and travel time are not significant. In the GA-based ones however, average execution times differ even for over 100%.

9. Conclusions and Future Work

The random search-based methods provide much better performance than genetic algorithm-based ones. What is interesting is that there is no large difference between using estimation of fitness and travel time from velocity profile generator. The difference is significant (over 10%) in case of GP VP; however, a similar difference is found with the RS method, which uses estimation. Ergo, the quality of optimization depends more on optimization method than on fitness obtaining method. It also shows that proposed method of estimation gives a proper knowledge of path properties. It is surprising that, in the most complex case, the estimated fitness (in RS) gave results close to the GP based on travel time, because estimated fitness does not take closeness ranges into consideration. Another interesting fact is a large gap between execution times of GA-based methods and RS-based ones. It will be investigated; whether it depends on method character only, or maybe there are implementation issues that slow it.
The next step of the research is to conduct experiments in real environment. For this purpose, an ATV-based mobile platform is under construction. It is powered by a combustion engine and will be able to operate in various environments, such as forests. The goal is to make it move through quite a rough terrain as fast as possible.

Author Contributions

Investigation, K.K.; methodology, Z.G. and K.K. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Acknowledgments

The authors would like to acknowledge the support of Bialystok University of Technology. The present study is supported by the Polish Ministry of Science and Higher Education, grant No WZ/WE-IA/4/2020.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Szczerba, R.J.; Galkowski, P.; Glicktein, I.S.; Ternullo, N. Robust algorithm for real-time route planning. IEEE Trans. Aerosp. Electron. Syst. 2000, 36, 869–878. [Google Scholar] [CrossRef] [Green Version]
  2. Duan, H.; Huang, L. Imperialist competitive algorithm optimized artificial neural networks for UCAV global path planning. Neurocomputing 2014, 125, 166–171. [Google Scholar] [CrossRef]
  3. Bozek, P.; Karavaev, Y.L.; Ardentov, A.A.; Yefremov, K.S. Neural network control of a wheeled mobile robot based on optimal trajectories. Int. J. Adv. Robot. Syst. 2020, 17, 1–10. [Google Scholar] [CrossRef] [Green Version]
  4. Kwaśniewski, K.K.; Gosiewski, Z. Genetic Algorithm for Mobile Robot Route Planning with Obstacle Avoidance. Acta Mech. Autom. 2018, 12, 151–159. [Google Scholar] [CrossRef] [Green Version]
  5. Roberge, V.; Tarbouchi, M.; Labonté, G. Fast Genetic Algorithm Path Planner for Fixed-Wing Military UAV Using GPU. IEEE Trans. Aerosp. Electron. Syst. 2018, 54, 2105–2117. [Google Scholar] [CrossRef]
  6. Liu, Y.; Guo, C.; Weng, Y. Online Time-Optimal Trajectory Planning for Robotic Manipulators Using Adaptive Elite Genetic Algorithm with Singularity Avoidance. IEEE Access 2019, 7, 146301–146308. [Google Scholar] [CrossRef]
  7. Jiang, A.; Yao, X.; Zhou, J. Research on path planning of real-time obstacle avoidance of mechanical arm based on genetic algorithm. J. Eng. 2018, 11, 1579–1586. [Google Scholar] [CrossRef]
  8. Lee, H.-Y.; Shin, H.; Chae, J. Path Planning for Mobile Agents Using a Genetic Algorithm with a Direction Guided Factor. Electronics 2018, 7, 212. [Google Scholar] [CrossRef] [Green Version]
  9. Lo, C.; Yu, S. A two-phased evolutionary approach for intelligent task assignment & scheduling. In Proceedings of the 11th International Conference on Natural Computation (ICNC), Zhangjiajie, China, 15–17 August 2015; pp. 1092–1097. [Google Scholar] [CrossRef]
  10. Zhang, H.; Liu, Z. 3D path planning for micro air vehicles based on quantum-behaved particle swarm optimization algorithm. J. Cent. South Univ. 2013, 44, 58–62. [Google Scholar]
  11. Zhang, J.; Zhang, Y.; Zhou, Y. Path Planning of Mobile Robot Based on Hybrid Multi-Objective Bare Bones Particle Swarm Optimization With Differential Evolution. IEEE Access 2018, 6, 44542–44555. [Google Scholar] [CrossRef]
  12. Yi, Z.; Yanan, Z.; Xiangde, L. Path Planning of Multiple Industrial Mobile Robots Based on Ant Colony Algorithm. In Proceedings of the 16th International Computer Conference on Wavelet Active Media Technology and Information Processing, Chengdu, China, 13–15 December 2019; pp. 406–409. [Google Scholar] [CrossRef]
  13. Zhang, W.; Gong, X.; Han, G.; Zhao, Y. An Improved Ant Colony Algorithm for Path Planning in One Scenic Area with Many Spots. IEEE Access 2017, 5, 13260–13269. [Google Scholar] [CrossRef]
  14. Jahanshahi, H.; Jafarzadeh, M.; Sari, N.N.; Pham, V.-T.; Huynh, V.V.; Nguyen, X.Q. Robot Motion Planning in an Unknown Environment with Danger Space. Electronics 2019, 8, 201. [Google Scholar] [CrossRef] [Green Version]
  15. Xiang, C.; Fen, Z. A fuzzy-based potential field hierarchical reinforcement learning approach for target hunting by multi-AUV in 3-D underwater environments. Int. J. Control 2019. [Google Scholar] [CrossRef]
  16. Li, G.; Yamashita, A.; Asama, H.; Tamura, Y. An efficient improved artificial potential field based regression search method for robot path planning. In Proceedings of the 2012 IEEE International Conference on Mechatronics and Automation, Chengdu, China, 5–8 August 2012; pp. 1227–1232. [Google Scholar] [CrossRef]
  17. Orozco-Rosas, U.; Picos, K.; Montiel, O. Hybrid Path Planning Algorithm Based on Membrane Pseudo-Bacterial Potential Field for Autonomous Mobile Robots. IEEE Access 2019, 7, 156787–156803. [Google Scholar] [CrossRef]
  18. Denker, A.; İşeri, M.C. Design and implementation of a semi-autonomous mobile search and rescue robot: SALVOR. In Proceedings of the 2017 International Artificial Intelligence and Data Processing Symposium (IDAP), Malatya, Turkey, 16–17 September 2017; pp. 1–6. [Google Scholar] [CrossRef]
  19. Feng, F.; Li, D.; Zhao, J.; Sun, H. Research of Collaborative Search and Rescue System for Photovoltaic Mobile Robot Based on Edge Computing Framework. In Proceedings of the 2020 Chinese Control and Decision Conference (CCDC), Hefei, China, 23–25 May 2020; pp. 2337–2341. [Google Scholar] [CrossRef]
  20. Chen, X.; Zhang, H.; Lu, H.; Xiao, J.; Qiu, Q.; Li, Y. Robust SLAM system based on monocular vision and LiDAR for robotic urban search and rescue. In Proceedings of the 2017 IEEE International Symposium on Safety, Security and Rescue Robotics (SSRR), Shanghai, China, 11–13 October 2017; pp. 41–47. [Google Scholar] [CrossRef]
  21. Wang, H.; Zhang, M.; Wang, J. Design and implementation of an Emergency Search and Rescue System based on mobile robot and WSN. In Proceedings of the 2010 2nd International Asia Conference on Informatics in Control, Automation and Robotics (CAR 2010), Wuhan, China, 6–7 March 2010; pp. 206–209. [Google Scholar] [CrossRef]
  22. Kwaśniewski, K.K.; Gosiewski, Z. Wheeled Robot Path Planning in Natural Environment. In Proceedings of the 2020 International Conference Mechatronic Systems and Materials (MSM), Bialystok, Poland, 1–3 July 2020; pp. 1–6. [Google Scholar] [CrossRef]
  23. Piegl, L.; Tiller, W. The NURBS Book; Springer: Berlin/Heidelberg, Germany, 1997. [Google Scholar]
Figure 1. General algorithms hierarchy.
Figure 1. General algorithms hierarchy.
Electronics 09 02099 g001
Figure 2. Raster map model. Black fields are obstacle-free, white ones contain obstacles.
Figure 2. Raster map model. Black fields are obstacle-free, white ones contain obstacles.
Electronics 09 02099 g002
Figure 3. General algorithm flowchart [22].
Figure 3. General algorithm flowchart [22].
Electronics 09 02099 g003
Figure 4. The random search algorithm.
Figure 4. The random search algorithm.
Electronics 09 02099 g004
Figure 5. The arcline model [22].
Figure 5. The arcline model [22].
Electronics 09 02099 g005
Figure 6. The i-th arc model.
Figure 6. The i-th arc model.
Electronics 09 02099 g006
Figure 7. The Whole Path Generation algorithm (WPGA) flowchart.
Figure 7. The Whole Path Generation algorithm (WPGA) flowchart.
Electronics 09 02099 g007
Figure 8. Layers description [22].
Figure 8. Layers description [22].
Electronics 09 02099 g008
Figure 9. Layers parameters: P—number of points, A—angle ranges, L—layers radii [22].
Figure 9. Layers parameters: P—number of points, A—angle ranges, L—layers radii [22].
Electronics 09 02099 g009
Figure 10. Point layers to control points conversion [22].
Figure 10. Point layers to control points conversion [22].
Electronics 09 02099 g010
Figure 11. Examples of paths crossing the generated control points [22].
Figure 11. Examples of paths crossing the generated control points [22].
Electronics 09 02099 g011
Figure 12. An example of a velocity profile obtained by proposed velocity profile generator.
Figure 12. An example of a velocity profile obtained by proposed velocity profile generator.
Electronics 09 02099 g012
Figure 13. Maps used for the tests: (a) Forest-like map; (b) Buildings-like map; (c) Some complex environment.
Figure 13. Maps used for the tests: (a) Forest-like map; (b) Buildings-like map; (c) Some complex environment.
Electronics 09 02099 g013
Figure 14. Examples of generated paths for maps presented in Figure 13: (a) Path in forest-like map; (b) Path in buildings-like map; (c) Path in some complex environment.
Figure 14. Examples of generated paths for maps presented in Figure 13: (a) Path in forest-like map; (b) Path in buildings-like map; (c) Path in some complex environment.
Electronics 09 02099 g014
Figure 15. Velocity profile for the example path for the map 1.
Figure 15. Velocity profile for the example path for the map 1.
Electronics 09 02099 g015
Figure 16. Velocity profile for the example path for the map 2.
Figure 16. Velocity profile for the example path for the map 2.
Electronics 09 02099 g016
Figure 17. Velocity profile for the example path for the map 3.
Figure 17. Velocity profile for the example path for the map 3.
Electronics 09 02099 g017
Table 1. The parameters of the GA-based methods.
Table 1. The parameters of the GA-based methods.
ParameterValue
Population size20
Step size10
Epochs10
Maximum radius50
Maximum angle range π 1.2
Maximum points number50
Table 2. The parameters of RS-based methods.
Table 2. The parameters of RS-based methods.
ParameterValue
Epoch number5
Step size10
Maximum radius50
Maximum angle range π 1.2
Maximum points number50
Table 3. Experiments results: times of execution and result times of the result paths.
Table 3. Experiments results: times of execution and result times of the result paths.
MapGA Ex. Time [s]GA Travel Time [s]GA VP Ex. Time [s]GA VP Travel Time [s]RS Ex. Time [s]RS Travel Time [s]RS VP Ex. Time [s]RS VP Travel Time [s]
134.3641.6558.4441.483.2741.753.24541.49
29.04341.5580.1741.481.87442.012.60641.53
49.58541.5465.2941.472.48841.493.8141.5
33.27141.6278.6241.552.4241.762.87841.49
39.66641.5772.2641.493.12541.532.49141.62
268.0451.44112.5250.962.4552.631.60552.04
87.45851.4188.7749.033.54856.262.20247.02
55.2651.9874.0751.51.92948.837.74149.67
31.61154.83151.5750.842.98854.622.69156.15
54.9452.24132.2651.351.83353.442.16647.16
347.9860.7629.852.032.37950.551.60951.64
25.49946.48120.4851.821.67843.473.5549.68
32.71254.61110.3842.823.07751.042.52949.37
61.07551.9682.9650.732.65354.032.06353.4
29.75569.51112.1451.193.77850.551.37566.14
Table 4. Average times of algorithm execution and travel.
Table 4. Average times of algorithm execution and travel.
MapGA Ex. Time [s]GA Travel Time [s]GA VP Ex. Time [s]GA VP Travel Time [s]RS Ex. Time [s]RS Travel Time [s]RS VP Ex. Time [s]RS VP Travel Time [s]
137.18541.58670.95641.4942.635441.7083.00641.526
259.461852.38111.83850.7362.549653.1563.28150.408
339.404256.66491.15249.7182.71349.9282.225254.046
Table 5. Standard deviation of times of algorithm execution and travel.
Table 5. Standard deviation of times of algorithm execution and travel.
MapGA Ex. Time [s]GA Travel Time [s]GA VP Ex. Time [s]GA VP Travel Time [s]RS Ex. Time [s]RS Travel Time [s]RS VP Ex. Time [s]RS VP Travel Time [s]
17.900.059.140.030.570.210.540.06
220.441.4131.440.990.722.782.523.81
314.798.8337.093.890.783.890.866.95
Table 6. Percentage difference between travel times of the methods. The genetic algorithm with approximation (GA) times as a reference.
Table 6. Percentage difference between travel times of the methods. The genetic algorithm with approximation (GA) times as a reference.
MethodMap 1Map 2Map 3
GA0%0%0%
GA VP−0.22%−3.14%−12.26%
RS0.29%1.48%−11.89%
RS VP−0.14%−3.76%−4.62%
Table 7. Percentage difference between execution times of the methods. genetic algorithm with approximation GA times as a reference.
Table 7. Percentage difference between execution times of the methods. genetic algorithm with approximation GA times as a reference.
Method.Map 1Map 2Map 3
GA0%0%0%
GA VP90.82%88.08%131.33%
RS−92.91%−95.71%−93.11%
RS VP−91.92%−94.48%−94.35%
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Gosiewski, Z.; Kwaśniewski, K. Time Minimization of Rescue Action Realized by an Autonomous Vehicle. Electronics 2020, 9, 2099. https://doi.org/10.3390/electronics9122099

AMA Style

Gosiewski Z, Kwaśniewski K. Time Minimization of Rescue Action Realized by an Autonomous Vehicle. Electronics. 2020; 9(12):2099. https://doi.org/10.3390/electronics9122099

Chicago/Turabian Style

Gosiewski, Zdzisław, and Konrad Kwaśniewski. 2020. "Time Minimization of Rescue Action Realized by an Autonomous Vehicle" Electronics 9, no. 12: 2099. https://doi.org/10.3390/electronics9122099

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