1. Introduction
Since the occurrence of the Fukushima nuclear disaster in Japan in 2011, there has been an increasing need for autonomous robots that can cope with hazardous situations. In particular, concerns for the development of practical robots that can work in severe environments have increased. The DARPA (US Defense Advanced Research Projects Agency) Robotics Challenge (DRC) has been initiated as an effort to achieve this goal and held every year since 2012.
The design of autonomous mobile robots should focus more on their safe navigation than on their travel time or distance. The safety of robots has been an issue that has been addressed for a long time in the field of mobile robots, and most works have focused on the task of collision avoidance [1, 2].
The potential field method presented by Borenstein and Koren creates a path based on the attraction and repulsion forces, which facilitates convenient mathematical analyses and application and thus makes it useful for being employed as an obstacle avoidance method [3]. The VFH (vector field histogram) method was developed to improve the practical application of the potential field method and to solve the local minimum problem [4-6].
The abovementioned methods exhibited excellent obstacle avoidance capabilities in static environments. However, in dynamic environments, they could not secure the safety of mobile robots. Fujimura and Samet proposed a static analysis method for avoiding dynamic obstacles [7]. Further, Ko and Lee presented a method that considers only the speed of moving obstacles [8]. Ge and Cui proposed a new potential field method by considering the speeds of the robot and obstacles [9]. The DWA (dynamic window approach) method has been widely used for obstacle avoidance and fast driving in local path planning [10].
However, these methods cannot secure the safety of robots in real environments, because of the partial information on the environment obtained through the limited FoV (field of view) of the sensor. With respect to the problem of the limited FoV, Fraichard and Asamark discussed the safety issue on the basis of the ICS (inevitable collision states) in a static environment [11]. Krishna et al. performed the speed decomposition of a path in a dynamic environment [12].
The braking ICS approach method proposed recently by Bouraine et al. became the basis for safety-based driving [13]. In their study, Donald et al. added physical analyses and proposed a kinodynamics approach [14, 15]. Studies related to ICS were inspiring achievements for safety issues; however, the major disadvantage of this approach is that the operation time increases in a complex environment. Therefore, it does not secure safe navigation in real time.
In this paper, we propose SGPP (safe global path planning) by considering the safe configuration space. This space is the passive safety space of a mobile robot. Passive safety implies that the robot is guaranteed to be at rest in the event of a collision. To secure the safe path planning of a mobile robot, the stopping distance (free running distance, braking distance) and hazard point (i.e., vertex point) are used in this work. The limited velocity for SGPP is also determined by considering the safety space. SGPP is performed using the A* algorithm with limited velocity.
The paper is organized as follows. In section 2, a safe configuration space is defined in a global environment. In section 3, the proposed SGPP method implemented using the A* algorithm based on the concept of safety space is presented. In section 4, the feasibility of the proposed method is validated through a simulation. In section 5, the proposed SGPP method is validated through comparisons of its performance with those of other methods in actual experiments in a real-world environment. Finally, conclusions of this study on SGPP for a mobile robot are presented in section 6.
2. Definition of Safe Space
A safety space includes all the possible kinematic positions of the robot that would ensure its safe distance from the surrounding obstacles, it also refers to all the spaces that would allow maintenance of minimum safety distances of the robot from the obstacles. Finally, the definition of safe space contains the minimum space required for stopping of the mobile robot to prevent its collision with an obstacle.
2.1 Safe configuration space
A safe configuration space is generated in order to ensure the passive safety of a mobile robot in its path planning. This passive safety is aimed at securing the minimum safety of the robot in a limited FoV [16]. The configuration space (C) of a mobile robot in two-dimensional (2D) space can be divided into a free space (Cfree) and configuration space obstacles (CO) [17]. The configuration space is the space of the robot that includes all possible configurations of its position. Therefore, the position of the robot represents a point in the workspace. Then, the path planning problem is simplified regardless of the kinematic condition of the robot. The configuration space obstacle is given as
where R(q) is the position of the robot, Oi are the obstacles, and k is the number of obstacles. COi will be an extension of obstacles in the configuration space according to the size of the robot. The remaining area, i.e., the area excluding the area of the obstacles in the configuration space, is termed the free space, and it can be expressed as
where Cfree is the set of configurations in which the robot does not intersect any obstacles. In this free space, the robot can move around freely; however, the safety of the robot in this space cannot be guaranteed. This is because in free space, the robot would need space to stop or space to avoid obstacles before it collides with them [13]. Moreover, such a space should be expanded further if no space were available for sensor information. This area is called the risk space Rs, and the remaining space, i.e., the space excluding the risk space, is called the safe space Ss. The following Eq. (3) relates the risk space and the safe space.
The space of the risk area should be generated by considering two distance concepts. The first is the stopping distance of the robot when it is moving at its highest speed, and the second is the risk distance of the robot on account of an unavailable FoV.
2. Calculation of Risk Distance via Stopping Distance
The stopping distance (ds) can be expressed by using the free running distance (df) and the braking distance (db). The free running time is the time required by a robot to recognize obstacles and to start the braking action; the distance that the robot moves during this time is called the free running distance. The distance that the robot moves from the start of braking until coming to a complete stop is called the braking distance. The stopping distance of robot moving at its maximum velocity can be calculated as
where ts is the time required to acquire sensor information, t tp is the time taken to process the information in the processor, vmax is the maximum velocity of the mobile robot, f is the friction force, and a is the acceleration.
The value of df is dependent on the characteristics of the sensor and the performance of the processor of the robot, whereas the value of db is dependent on the speed of the mobile robot, friction force of the surface, and performance of the brake. The value of ds increases with an increase in the speed of the mobile robot. To prevent the collision of the robot with unidentified objects encountered in the area of a limited FoV or corners, the additional concept of risk distance is required.
2.3 Hazard point
Although the mobile robot might be equipped with the sensors required for driving, there exist spaces where the sensor information cannot be obtained. Examples of such spaces include the corner areas of buildings in an urban space. In such spaces, there is a potential risk of collision, and therefore, slow driving or a safe bypass plan is needed. Fig. 1 below illustrates an example of a limited FoV of the mobile robot.
Fig. 1.Limited field of view of mobile robot
The mobile robot can handle a collision with obstacles in the space secured by the FoV, as illustrated in Fig. 1; however, the space that is outside the FoVc(complement of FoV), which is the space unavailable for sensor information, is termed hazardous space, in which a mobile robot might collide with unidentified obstacles.
The FoV is the space that a robot could reach with its view, whereas the FoVc is the space that is beyond the FoV of a robot, i.e., where the robot cannot reach.
Vertex R(p) denotes the risk points in the workspace. The robot may collide with a UMO (unidentified moving obstacle) that appears in the FoVc. Fig. 2 shows the stopping and risk distances from obstacles in the configuration space.
Fig. 2.Safe distances from obstacle
Connecting the vertices perpendicular to the vertical segment ds extended from the segment yields the segment , which is parallel to the segment . Further, connecting the vertices perpendicular to the vertical segment ds extended from the segment yields the segment , which is parallel to the segment .
The intersection of segments and is called the virtual risk point (). The risk distance dh from Rp to can be termed the hazard distance.
where η is the safety gain. With a decrease in the interior angle Rp, the risk distance dh increases, and vice versa. The risk distance can be calculated in accordance with the magnitude of the corner angle. The range of the interior angle is 0° < ∠B° < 180°.
Algorithm 1 described below is an algorithm for checking the risk space, with the global map given in vector format.
Algorithm 1.Check of risk space in configuration space
Configuration space obstacles are created with all kinds of polygonal shapes with regards to the size of a mobile robot. For all kinds of configuration space obstacles, R_p is sized up and the risk space is checked.
2.4 Limited velocity according to risk space
The risk distance is calculated in the configuration space as described in section 2.3. It is then possible to calculate the limited velocity of the mobile robot. The risk area R_s (x) can be defined as
Where D is the distance between the risk point and the position of the robot. denotes a specified risk point, which is necessary to secure at least the minimal safety of the robot. The value of Rs(x) lies in the interval of 0 < Rs(x) < 1.
Fig. 3 shows the risk space of a rectangular obstacle. This figure shows a 2D map for path planning. The cell decomposition method is used to generate a risk map according to Algorithm 1 and Eq. (6).
Fig. 3.Risk space of rectangular obstacle
A safe cell is a free space from the conflict. it takes the value of 0, an obstacle cell takes the value of 1, and a risk cell takes a value of 0 < Rs(x) < 1. The risk values are 1 in a corner of the obstacle and they converge to zero as the robot moves farther from the corner. In particular, the risk value indicates a wider area at the vertices. The risk space of the mobile robot given in Eq. (6) can be used to express the limited velocity of the robot as follows:
where Vmax is the maximum velocity of the mobile robot. Fig. 4 below shows results of simulation of the limited velocity of the mobile robot for various shapes of the obstacle.
Fig. 4.Limited velocity according to risk space
3. SGPP using A* Algorithm
Next, we perform safety path planning by using a grid map considering the risk index. Algorithm 2 below is the SGPP method implemented using the A* algorithm in consideration of the safety cost.
Algorithm 2.SGPP method implemented using A*
Algorithm 2 will find the safest and most optimal path by using a grid map containing the risk information. The input is a graph of the coordinates of the robot. The coordinates of the robot are termed nodes n, which lie in the free space. n_best denotes the current node. OpenList refers to the priority queue, and ClosedList contains all processed nodes. The safety cost function is expressed as
where c(nbest) is the sum of safety costs from the start node to the current node and g(nbest (Ss = 1 − Rs) ∗ Ed) is the estimated safety cost from the start node to the target node. Here, Ed denotes the value of the Euclidean distance from the current node to the target node.
The estimated safety cost from the current node to the target node will be a product of the safety cost and the value of the Euclidean distance. A node will be created by exploring the safest peripheral nodes, from the start node to the target node. Fig. 5 shows a comparison of the global path results of the SGPP method with those of the classical A* algorithm.
Fig. 5.Comparison of global paths generated by classical A* algorithm and SGPP method
4. Simulation Results
The MATLAB and ARIA simulators were adopted for the mobile robot Pioneer3DX (Mobile Robots Inc.). The applied maximum speed, maximum acceleration, and maximum deceleration were 1 m/s, 0.3 m/s^2, and 0.6 m/s^2, respectively. The map employed was a 2D map with a 100×100 resolution, and the lattice size was set as 30 cm/grid.
In this study, the SGPP method was implemented using the A* algorithm based on the concept of safety space, as described in section 3. Here, we present an extensive simulation study conducted for evaluating the efficiency of the proposed method.
The objective of this simulation is two-fold: first, we wanted to compare the performances of the proposed method, classical A* algorithm, and the PRM (probabilistic roadmap) algorithm [18] in safety space. The DWA (dynamic window approach) [19] has commonly been used for local path planning.
Fig. 6 shows the results of global path planning performed by each of these three methods in safety space. Fig. 7 shows the navigation paths of the mobile robot using the created waypoints shown in Fig. 6.
Fig. 6.Global path planning with limited velocity (safety space)
Fig. 7.Results of paths generated by the three considered methods
As shown in Figs. 6 and 7, all three methods rendered paths for the mobile robot to drive from the starting point (8, 95) to the destination point (90, 27) without collision.
The classical A* algorithm (Fig. 7(a)) employed for the simulation created the shortest path for driving the robot; however, the robot reduced its speed in the corner area (Fig. 7(a) c1-c4). In the classical A* algorithm, the navigation time increased because the robot reduced its speed whenever it encountered a corner, as illustrated by the red dashed line in Fig. 8.
Fig. 8.Velocity profiles for paths created by the three methods
The PRM algorithm shown in Fig. 7(b) also yielded a path that reduced the speed of the robot in the corner areas (Fig. 7(b) c1, c4), and owing to the somewhat longer path, it also resulted in a longer navigation time.
Fig. 7(c) shows the created path simulated by the proposed method, where the robot also reduced its speed in the first corner area (Fig. 7(c) c1); however, it then drove at maximum velocity.
As illustrated in Table 1, the proposed method rendered more favourable outcomes than the PRM method in all respects. The length of the path created by the proposed method increased by 3% compared to that created by the classical A* algorithm; however, in the case of the proposed method, the robot drove 26% faster, with an average moving speed of 0.87 m/s. The proposed method was shown to perform the safest and fastest navigation to the goal.
Table 1.Comparison of performance of the three considered algorithms in safety space. (The risk value is the sum of the risk values of the path of the mobile robot on the map. The risk values are as mentioned in Eq. 6.)
5. Experiments
We attempted to experimentally demonstrate the feasibility of the proposed safe path planning method through its real-world implementation in mobile robots. The method was implemented in C++ using Microsoft Visual Studio and tested on the Pioneer3DX robot, operating under a version of Windows CE.
Table 2.Comparison of simulated results for the three considered methods
A snapshot of the experimental environment is shown in Fig. 9. We conducted experiments in an indoor environment (5.6 m × 5.6 m). The five obstacles in this environment were static. Fig. 9 shows the comparative results obtained from an experiment in which the three methods — the proposed SGPP method, PRM algorithm, and classical A* algorithm were executed separately from the start point (0, 0) to the targeted destination point (50, 50). Even though a conclusion may review the main results or contributions of the paper, do not duplicate the abstract or the introduction. For a conclusion, you might elaborate on the importance of the work or suggest the potential applications and extensions.
Fig. 9.Experiment with rectangular obstacles
The proposed method created paths that were 21% and 12% longer than those created by the classical A* algorithm and PRM algorithm, respectively; however, it enabled comparatively faster driving that reduced the running time by 11.5% and 28.7%, respectively, compared to these two methods. It also allowed for safe navigation, with the safety cost reduced in the risk area in the experiment.
As shown by the results of these experiments, the proposed method exhibited better outcomes in terms of the navigation time and safe driving.
Fig. 10 shows the velocity profiles obtained from the three methods employed in the experiment. The average speeds obtained for the classical A* algorithm, PRM algorithm, and proposed method were 0.23 m/s, 0.16 m/s, and 0.27 m/s, respectively; that is, the proposed method rendered the fastest average velocity.
Fig. 10.Velocity profiles for the three methods
The path created by the proposed method was somehow longer than those created by the other two methods. However, the path created by the proposed method allowed safe driving with the highest speed, which reduced the overall running time.
6. Conclusion
In this paper, a safe and fast path planning method was presented that employed the concept of safety space and the A* algorithm. The stopping distances and the risk information at corner points were generated quantitatively, and a safe path was created by incorporating the A* algorithm.
In the planning of a global path, paths that bypass corner areas or crossroads can be created to reduce the risk of collision with obstacles and to secure a safe and fast path to the destination.
This method would specifically be useful for robots that employ inexpensive sensors or for occasions in which places of increased uncertainty might be encountered.
In this study, the performance of the developed SGPP method in terms of bypassing of spaces such as corners and reducing the running speed of mobile robots was validated through simulations and experiments. The SGPP method showed superior performance to the other considered algorithms in terms of the safety cost and navigation time.
The next research step is to employ the proposed safe local path planning method in performing tasks that are more complex, such as navigation in dynamic environments.
참고문헌
- Ullah, I., et al., Integrated tracking and accident avoidance system for mobile robots. International Journal of Control, Automation and Systems, 2013. 11(6): p. 1253-1265 https://doi.org/10.1007/s12555-012-0057-6
- Becker, M., C.M. Dantas, and W.P. Macedo. Obstacle avoidance procedure for mobile robots. in ABCM Symposium series in Mechatronics. 2006.
- Borenstein, J. and Y. Koren, Real-time obstacle avoidance for fast mobile robots. Systems, Man and Cybernetics, IEEE Transactions on, 1989. 19(5): p. 1179-1187. https://doi.org/10.1109/21.44033
- Borenstein, J. and Y. Koren, The vector field histogram-fast obstacle avoidance for mobile robots. Robotics and Automation, IEEE Transactions on, 1991. 7(3): p. 278-288. https://doi.org/10.1109/70.88137
- Ulrich, I. and J. Borenstein. VFH+: Reliable obstacle avoidance for fast mobile robots. in Robotics and Automation, 1998. Proceedings. 1998 IEEE International Conference on. 1998. IEEE.
- Mabrouk, M. and C. McInnes, Solving the potential field local minimum problem using internal agent states. Robotics and Autonomous Systems, 2008. 56(12): p. 1050-1060. https://doi.org/10.1016/j.robot.2008.09.006
- Fujimura, K. and H. Samet, A hierarchical strategy for path planning among moving obstacles [mobile robot]. Robotics and Automation, IEEE Transactions on, 1989. 5(1): p. 61-69. https://doi.org/10.1109/70.88018
- Nak Yong, K. and L. Bum Hee. Avoidability measure in moving obstacle avoidance problem and its use for robot motion planning. in Intelligent Robots and Systems '96, IROS 96, Proceedings of the 1996 IEEE/RSJ International Conference on. 1996.
- Ge, S.S. and Y. Cui, Dynamic motion planning for mobile robots using potential field method. Autonomous Robots, 2002. 13(3): p. 207-222. https://doi.org/10.1023/A:1020564024509
- Fox, D., et al. A hybrid collision avoidance method for mobile robots. in Robotics and Automation, 1998. Proceedings. 1998 IEEE International Conference on. 1998. IEEE.
- Fraichard, T. and H. Asama, Inevitable collision states — a step towards safer robots? Advanced Robotics, 2004. 18(10): p. 1001-1024. https://doi.org/10.1163/1568553042674662
- Madhava Krishna, K., R. Alami, and T. Siméon, Safe proactive plans and their execution. Robotics and Autonomous Systems, 2006. 54(3): p. 244-255. https://doi.org/10.1016/j.robot.2005.10.008
- Bouraine, S., T. Fraichard, and H. Salhi, Provably safe navigation for mobile robots with limited field-of-views in dynamic environments. Autonomous Robots, 2012. 32(3): p. 267-283. https://doi.org/10.1007/s10514-011-9258-8
- Donald, B., et al., Kinodynamic motion planning. Journal of the ACM (JACM), 1993. 40(5): p. 1048-1066. https://doi.org/10.1145/174147.174150
- LaValle, S. M. and J. J. Kuffner, Randomized kinodynamic planning. The International Journal of Robotics Research, 2001. 20(5): p. 378-400. https://doi.org/10.1177/02783640122067453
- Park, J.-H., J.-H. No, and U.-Y. Huh. Safe Global Path Planning of Mobile Robots Based on Modified A* Algorithm. in The 8th International Conference on Robotic, Vision, Signal Processing & Power Applications. 2014. Springer.
- Lozano-Perez, T., Spatial planning: A configuration space approach. Computers, IEEE Transactions on, 1983. 100(2): p. 108-120.
- Denny, J., et al. A Region-Based Strategy for Collaborative Roadmap Contruction. in Algorithmic Foundations of Robotics XI, Proceedings of the Eleventh Workshop on the Algorithmic Foundations of Robotics (WAFR 2014), Springer Tracts in Advanced Robotics, to appear. 2014.
- Fox, D., W. Burgard, and S. Thrun, The dynamic window approach to collision avoidance. Robotics & Automation Magazine, IEEE, 1997. 4(1): p. 23-33. https://doi.org/10.1109/100.580977
피인용 문헌
- A geometrical path planning method for unmanned aerial vehicle in 2D/3D complex environment vol.11, pp.3, 2018, https://doi.org/10.1007/s11370-018-0254-0