IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS, VOL. 49, NO. 6, DECEMBER 2002
1
A Propagating Interface Model Strategy for Global Trajectory Planning Among Moving Obstacles Kao-Shing Hwang, Member, IEEE, and Ming-Yi Ju
Index Terms—Collision-trend index, potential field, propagating interface model, trajectory planning.
I. INTRODUCTION
T
[4]. Another method which uses the concept of “Freeways” to represent the environment was proposed by Brooks [5]. This method defines the space between obstacles as freeways, with a centerline (called a “spline”) that is used to navigate along the freeway. For path planning with moving obstacles, Shih et al. presented another approach using a proper free-space representation based on polytypes [6]. After a global graph search has been employed, a family of feasible trajectories is generated, and a constrained optimization problem is formulated to obtain a final near-optimal trajectory. A collision front approach has also been introduced to deal with motion planning of a point robot amidst moving obstacles [7]. This approach defines a boundary segment of the collision front represented by a moving edge to facilitate selection of internal points iteratively for time-minimal motion. To generate a safer path using the collision front approach, it has been suggested that the internal points be shifted away from the vertices of obstacles by some distance, which is determined by a random number generator controlled by a number dependent on the size of the environment [8]. These above-mentioned methods all consider the path-planning problem as one involving high-level control. On the other hand, the artificial potential method primarily regards the problem as one of lower level control [9]. Due to its simplicity and elegance, the artificial potential method is one of the most efficient approaches to obstacle avoidance in the field of robots and mobile robots. By representing the goal with an attractive potential and obstacles with repulsive potentials, the potential field is able to generate paths by following the negative gradient of the potential function. These virtual potentials can eventually be assigned to interact with the dynamics of the robot [10]. However, for a cluttered environment, local minima may occur in the resultant potential field and may trap the robot before it reaches its goal. The well-known example of this situation is that in which the attractive potential guides the robot’s path into a C-obstacle concavity. In order to avoid the problem of local minima in potential fields, several potential field methods have been developed to reduce the number of local minima and/or the size of attractive wells in order to prevent the path from terminating at a point other than the goal. An approach which uses elliptical repulsive potentials to reduce the number and the size of the local minima of the potential function was proposed in [11]. The basic idea is to define the repulse potential around an obstacle in such a way that the equipotential contours converge toward the boundary of the obstacle. Nevertheless, elliptical potentials have several drawbacks; e.g., they can only be generalized to simple convex shapes; no obstacle can be located at a point such that its potentials interact
IE E Pr E oo f
Abstract—A global trajectory planning method which employs a collision-trend index and a propagating interface model to perform mobile robot navigation is presented in this paper. To simplify the mathematical representation and geometrical approximation, all the objects in the workspace are modeled as ellipses. Using a series of geometrical transformations between the ellipses, which represent the mobile robot and obstacles, the computational complexity of collision detection in trajectory planning can be reduced tremendously. To keep the front propagating in the normal direction with positive propagating speed, the collision-trend index plays an important role in determining the propagating speed for a front over workspace. The index is obtained by mapping the geometrical relationship between the ellipses into the profile of a Gaussian distribution. Several simulations to demonstrate the performance of the proposed method are given. The results reveal that the proposed method is always able to generate an optimal collision-free trajectory for a mobile robot navigating in an environment with dynamic and static obstacles.
RAJECTORY planning is an important research topic in the study of robots. Previous research efforts have been geared toward determining efficient methods for collision avoidance among static and dynamic obstacles in an environment. In general, classical collision avoidance can be stated as follows [1]. Given an arbitrary rigid moving object with multiple degrees of freedom, such as a robot, a continuous collision-free path taking the object from an initial configuration to a desired configuration should be found. This problem has motivated the development of a variety of methods. Lozano-Pérez and Wesley presented a general solution using free-space dynamics [2], [3]. In that approach, each obstacle in the environment is “grown” based on the dimensions of a robot. That robot is then effectively reduced to a dimensionless point. The algorithm is then simplified to finding a safe path for moving a point among obstacles. In addition, some researchers have shown that the problem of path planning for the Piano Movers problem is PSPACE-hard
Manuscript received February 27, 2000; revised July 24, 2002. Abstract published on the Internet September 13, 2002. K.-S. Hwang is with the Electrical Engineering Department, National Chung Cheng University, Chia-Yi , Taiwan, R.O.C. (e-mail:
[email protected]). M.-Y. Ju was with the Electrical Engineering Department, National Chung Cheng University, Chia-Yi , Taiwan, R.O.C. He is now with . Publisher Item Identifier 10.1109/TIE.2002.804985.
0278-0046/02$17.00 © 2002 IEEE
2
IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS, VOL. 49, NO. 6, DECEMBER 2002
(a)
(b)
(c)
Fig. 1. (a) Water waves. (b) Waves travel from the shallow end to the deep end. (c) Two objects are located in the space through which waves travel (the reflection behavior is not taken into consideration).
tions. Waves traveling from the shallow end to the deep end can be seen to refract, i.e., bend, increase in wavelength (the wave fronts become looser) and speed up (they take less time to travel the same distance). Besides refraction, reflection and diffraction are also well-known behaviors of water waves. Reflection involves a change in the direction of waves when they bounce off a barrier; diffraction also involves a change in the direction of waves as they pass through an opening or around a barrier in their path. Water waves have the ability to travel around corners and obstacles, and through openings. An example is shown in Fig. 1. This ability is most obvious for water waves with longer wavelengths. The level set method is one of the numerical techniques used to track the evolution of a wave front.
IE E Pr E oo f
with those of other obstacles; the definition of the method does not provide a direct way to compute the potential under a given configuration. These drawbacks make the application of elliptical potentials to practical problems difficult. The application of harmonic functions to path-planning problems has been addressed in [12] and [13]. Harmonic functions are solutions to Laplace’s equation and have some useful properties for application to robotics. Harmonic potentials reach extreme values on the boundary of their domain. Since the superposition of harmonic potentials is also harmonic, the harmonic constraint guarantees that there will be no local minima. Based on the concept of deforming complex obstacles, navigation functions are introduced to remove the local minima from potential fields by smoothly deforming various shapes of obstacles into spherical ones [14]. For example, in [15], obstacles with different shapes in a configuration space were mapped into a topologically equivalent “sphere world.” However, these approaches only focus on resolving the obstacle avoidance problem and ignore path optimality. As a result, paths generated by some of these potentials may be far from optimal. In this paper, a global trajectory planning strategy is proposed. This method was inspired by the method of interface propagation, which provides a computational way of modeling the evolution of moving boundaries of wave fronts in computer graphics. From the viewpoint of search problems, a propagating front can be regarded as the scout of a searching team exploring in all directions from the starting point. To implement the proposed method, a one-side second-order difference scheme called the fast marching method is used to compute the travel time for a propagating front. When the moving front reaches the target position, the time which elapsed as the front propagated through the workspace can be regarded as the potentials and used to plan a collision-free trajectory. Since the travel time for a front increases monotonically, there is no local minimum in the potential field constructed by means of the travel time function. Physically, the propagating speed changes as the front travels from one medium to another. The collision-free space and the region occupied by obstacles can be regarded as different types of media, then the constraints for trajectory planning can be considered in terms of the propagating speed of the moving front. In order to make use of this property, the collision-trend index, a measurement used to describe the characteristics of different media, is defined by representing the geometrical relationship between ellipses as the composed profiles of Gaussian distributions. Furthermore, using the defined jeopardizing collision index, the collision-trend index also can be applied to determine whether two ellipses/circles overlap or not. II. PROPAGATING INTERFACE MODEL In recent years, propagating interface model strategies have been applied to a wide variety of problems [16]. The underlying concept is the evolution of a simple closed curve whose points move in the normal direction at a prescribed velocity. Take a water wave as an example; a rock tossed into water will create a circular disturbance which travels outwards in all direc-
A. Level Set Formulation
, where is time and , Consider a closed curve moving at a speed normal to itself in a two-dimensional enbe a closed and nonintersecting front in a vironment. Let defined based Euclidean plane and construct a function to such that the level set { } is the front , on that is, (1)
, appropriate In order to construct such a function and an associated partial differential initial conditions must be supplied. equation for the time evolution of is initialized by (2)
is the signed distance from to the initial front . In order to derive the partial differential equation for the time evolution of , consider the motion of some level }. Let be the trajectory of some particle set { located on this level set such that
where
(3) The particle velocity level set is given by
in the direction
normal to the
(4) Differentiating (3) with respect to and combining with (4) yields
HWANG AND JU: GLOBAL TRAJECTORY PLANNING AMONG MOVING OBSTACLES
given Equation (5) yields the motion of the interface ; thus, level set
(5) as the
Since (8) is a quadratic equation, one can iterate until convergence is obtained by solving the equation at each grid point. However, this scheme is very time consuming. Therefore, a more efficient method called the fast marching method is applied to solve this quadratic equation. This method is based on the observation that the upwind difference structure of (8) means that information propagates from small values of to larger values. Hence, the algorithm is based on the idea of building a solution of (8) outwards from the smallest value. Motivated by the methods given in [20], the “building zone” is confined to a narrow band around the front. The idea is to sweep the front ahead in an upwind manner by considering a set of points in the narrow band around the current front, and to then march this narrow band forward. The fast marching method is divided into two stages, the initialization stage and the marching forward stage. In the initial, ization stage, the initial front starts from a grid point with while the candidate points in the set of the narrow band are selected from the eight points around the initial starting point. Since the narrow band region is only one cell away from the starting point, it is easy to calculate the distance between the starting point and the eight neighboring points. The propagating speed associated with the grid point ( ) is fixed since the speed function depends only position. The values of the travel time needed for the wave front to reach the eight neighboring points in the narrow band are initialized by distance/speed. Finally, it is assumed that the travel times for the other points are infinite. After the initialization stage, the points in the narrow band are selected for with the smallest value of travel time marching forward, and its neighbors with infinite travel time are added into the set of the narrow band. The travel times for the front to propagate to the points which are listed in the narrow band are recomputed then according to (8). It should be noted that two or more points may have the smallest value simultaneously, and that their neighbors of travel time may overlap each other while the concave front is marching forward. In order to satisfy the Huygens’ principle [21], [22], the smallest value of travel time is selected because the front with the smallest value will propagate across the point first. The marching forward phase terminates when the expanding front reaches the target.
IE E Pr E oo f
Equation (5) is referred to as the level set formulation. It is noted that a level set formulation is a distance function if . An important advantage for this technique stems from the fact that since the front propagation uses a fixed coordinate system in the physical domain, discrete mesh points used in the numerical update equations do not move, resulting in stable computation. Consider the special case of a monotonically advancing front; i.e., an interface moves with propagating speed , which is always positive, and no reflection behavior is taken into consideration. The level set function, which is a distance function, can be reformulated as advecting normal to itself for a specific time . In other words, all the points in the zero level set are located at a distance from the initial propagating interface. Then, a level set equation for the travel time can be given by
3
(6)
As mentioned above, the propagating speed is a function of position only; therefore , in fact, (6) is an Eikonal equation [17], [18], namely, (7)
To solve (7), an approximation that uses the finite operator on the fixed Cartesian grid map is needed. An upwind approximation [19] of the gradient leads to
(8)
where the forward and the backward operators are
III. COLLISION-TREND INDEX
and are the values of the travel time and the propis the disagating speed at the grid point ( ), respectively; is the distance tance between two grid points on the axis; between two grid points on the axis. The problem encountered here is that of solving for the travel time in order to obtain a gradient magnitude that is inversely proportional to the propagating speed at ( ). B. Fast Marching Method
Solving for the travel time given in (8) efficiently is the most important problem for the propagating interface model.
The collision-trend index is a measure of the risk of collision. The index is evaluated by mapping the geometrical relationship between objects into a Gaussian distribution. In order to compute the measurement, an object modeling method and necessary coordinate transformation are also employed and will be introduced in this section. A. Object Modeling Efficient collision detection is crucial to collision-free path planning. To reduce the computation time required for intersection checking, complex objects are usually modeled as simpler primitives in order to simplify the mathematical or geometrical representations. Appropriate primitives should reflect a good balance between the efficiency of primitive–primitive intersec-
4
IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS, VOL. 49, NO. 6, DECEMBER 2002
tion detection and the number of primitives required to adequately represent the world model. Usually, circles have been used as the primary components in previous researches [23], [24]. Since distance computation or collision detection are replaced with calculation of the collision-trend index in the proposed approach, both circles and ellipses are used as primitives for the purpose of object representation in this work. This is due to the fact that mapping of circles or ellipses to two–dimensional (2-D) Gaussian distributions can produce similar formulation with different covariance matrices. The superquadratic inside–outside function [25] and ellipsoid algorithm [26] are well-known methods for computing an enclosing ellipse for a convex polygon.
C. Definition of the Collision-Trend Index Equation (10) can be represented in the form
(13) After expanding (11), it can be rewritten as
where the procedure for deriving of through geometrical calculations is too trivial to include here. ) can be In this way, the collision-trend index at the point ( defined as follows:
B. 2-D Gaussian Function A 2-D Gaussian distribution function is represented as (9) (14) , the expectation vector
Therefore, the jeopardizing collision index, which represents the case in which the point is on the contour of the ellipse, can be defined by setting
IE E Pr E oo f
where the position vector
, and the covariance matrix
.
The covariance matrix plays an important role in expressing the shape of the distribution. In other words, different covariance matrices show different features of distributions. Focusing will make features with difon the term ferent covariance matrices much clearer. Suppose the variable is equal to the value of the term represented by the following equation:
(10)
If the covariance matrix is a diagonal matrix and , then we can get a standard circular equation with a radius at the center of ( ). If the covariance matrix is of , a standard elliptic equation with the diagonal but and , respectively, at the center of ( ) will radii be generated. The other cases in which the covariance matrix is not diagonal but symmetric also generate a rotated elliptic ). This type of covariance can equation at the center of ( be expressed as
where is the diagonal eigenvalue matrix and is the eigenvector matrix. Since the matrix is a diagonal eigenvalue matrix after covariance matrix transformation, the determinant of is the same as that of , namely, (11) Therefore, (9) can be rewritten as
where
(12) is the position vector of the general elliptic equation.
(15)
To sum up, if the coordinate of a point in the workspace is given, the collision-trend index associated with this point can be computed by (14) and collision detection can be easily performed by means of the following test: collision
D. Fast Collision-Detection Algorithm
The relative position between a point and a primary compo, then nent can be easily verified based on (10): if ) is outside the primary component; otherwise, it the point ( is located inside the primary component. Therefore, the result of (10) obtained by providing the coordinates of a point as the arguments can be regarded as one of the collision occurrence indexes. Therefore, a simple detection algorithm can be derived easily if the mobile robot and the obstacles in the working space can be represented geometrically in the form of a point and several obstacles. Unfortunately, the problem encountered here is not that of a point colliding with a set of obstacles; rather, it is related to the fact that the robot is also modeled as a primary component. Intersection checking between two ellipses is time consuming and rather difficult [27]. Therefore, in order to take advantage of the simplicity of detecting the geometrical relationship between a point and a primary component, a series of transformations must be applied to the primary components that represent the mobile robot and the obstacles in the workspace. As shown in Fig. 2, this approach initially changes the reference coordinate system from the world coordinate system to the mobile robot’s coordinate system. Then, a scaling operation deforms the moving primary component, which represents the mobile
HWANG AND JU: GLOBAL TRAJECTORY PLANNING AMONG MOVING OBSTACLES
(a)
(b)
5
(c)
Fig. 2. (a) Three-step transformation for collision detection before scaling. (b) Three-step transformation for collision detection after scaling. (c) Three-step transformation for collision detection after enlarging by one unit.
robot, into a unit circle, while the obstacles are transformed into other shapes. The problem is, thus, simplified to one between a point and transformed primary components. The mathematical procedure is discussed in the following. The primary component that is used to model the mobile robot can be expressed in polar vector form. The vector can also be regarded as a circle scaled along the - axes
where is the relative coordinate of the obstacle with respect to the mobile robot’s coordinate system. The transformed ellipse/circle polar form equation of the primary component represented by the obstacle at time also can be expressed in the standard form as
(20) (16)
and
IE E Pr E oo f
where
, and through where the procedure for deriving , , geometrical calculation is too trivial to include here. The detailed process for deriving these parameters can be found in [28]. If the primary component representing the mobile robot must be reduced to a point, then a straightforward method is to expand the radii of the primary component in proportion to the radius of the circle. As the circle (the mobile robot) shrinks to a point, the other primary components in the same working space should be deformed by the same scaling transformation with respect to the same coordinate system. Meanwhile, to prevent the robot from coming into contact with the surfaces of the obstacles while it passes through them, the transformed ellipses which are used to model obstacles should be expanded slightly
is the unit circular vector
is a scaling transformation
where and are the scaling factors along the and axes, respectively. Therefore, a series of transformations applied to the vector of the primary component beginning at the initial time can describe the instantaneous pose (position and orientation) of a moving ellipse, which represents the mobile robot, at time
(17)
is the initial position with respect to the base where is the sequential transforframe before the motion; mation. Similarly, the instantaneous pose of the primary component used to model the obstacle can be expressed as to
(18)
where is the index of the primary component in the working is a position transformation w.r.t. the base coorspace; dinate system. Therefore, with respect to the mobile robot’s coordinate, the instantaneous pose of the primary component at time can be represented by the following equation: (19)
(21)
Therefore, the problem of collision detection is simplified to test if the point (0,0), which represents the origin of the mobile robot’s coordinate system, resides inside or outside the function at time , i.e., collision occurs
(22)
However, real geometrical dilation transformation is not so easy. A small error is caused by the topological differences between the ellipse expanded along the two axes by one unit and the real one expanded radially. This small error can be reduced if the object is modeled just slightly larger than it should be. Therefore, the jeopardizing collision index, which represents the case in which the point is on the contour of the ellipse, can be defined by setting
Therefore, if collision, where is the associated collision-trend index at time for ). the mobile robot at position (
6
IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS, VOL. 49, NO. 6, DECEMBER 2002
IV. EMBEDDING THE COLLISION-TREND INDEX INTO THE FAST MARCHING ALGORITHM FOR OPTIMAL TRAJECTORY GENERATION The propagating interface model strategy used in this work relies on embedding (or extension) of the front’s propagating speed to a higher dimensional level set function. Therefore, much of the challenge in applying the propagating interface model stems from the need to produce an adequate model for the propagating speed function . Since the propagating speed of the interface plays an important role, determining the propagating speed is another research topic related to the propagating interface model. A. Propagating Speed
given
target point
until the starting point is reached. The optimal trajectory constructed using the proposed method has the properties of the minimal travel time for the wave front to reach the target and the minimal cumulative value of the collision-trend index. In the proposed case, since the travel time is inversely proportional to the propagating speed, the propagating speed is proportional to the collision-trend index, and the propagation speed is proportional to the moving speed of a mobile robot; therefore, in some sense, the constructed trajectory is also a time-optimal trajectory. V. SIMULATIONS To demonstrate the performance of the proposed method when applied to trajectory planning problems, several simulations were conducted in environments with dynamic obstacles. In the following simulations, the shape of the mobile robot was assumed to be isometric in all its axes; i.e., the mobile robot was modeled geometrically as a disk. Since the controller of a mobile robot is a discrete system, it is convenient to set the frozen time of the fast marching method equal to the sampling time of the discrete system. Furthermore, this assignment leads to a simple way to determine the speed command for each sampling time. It is worth noting that the speed of a mobile robot can be viewed as a function of the propagating speeds of wave fronts. , For example, a simple linear relation is given as is the maximum speed where is the current speed and allowed for the mobile robot, respectively. Without loss of was set as 1.0 in the simulations. Due to the generality, natural characteristics of a propagating interface, the front always expanded in the direction normal to itself. Therefore, when the front reached the target point, there was at least one trajectory that could be found extending from the source point to the target with minimal propagating time. After the interface propagation stage was finished, the backward tracing method was applied to find an optimal trajectory for navigation. In the following simulations, obstacles with one degree of freedom, e.g., rotation or translation, were considered. The workspace was represented as a 200 200 graph. The starting and target points were located at (20,20) and (180 180), respectively. As shown in Fig. 3(a), the first case involved two translating obstacles between the starting position and target in the workspace. Fig. 3(b) depicts the relationship between the mobile robot and two obstacles after the scaling process. Both obstacles moved toward the other at the same speed. After collision occurred, they reversed their direction of movement. Fig. 3(c) shows the level sets constructed by the propagating interface model. The results obtained when the backward tracing method was applied to the level sets to generate a collision-free trajectory are shown in Fig. 3(d). Fig. 3(e) shows the travel time needed for the propagating front to reach the target in the workspace. The speed profile of the mobile robot
IE E Pr E oo f
A special case in applying the propagating interface model assumes that the propagating speed of an evolving front is always equal to unity in order to generate the minimal geodesic distance between points. Based on this assumption, the propagating interface model strategy can be applied to find a distance optimal path for mobile robot navigation. It is worth noting that this depends heavily on correct modeling of obstacles. In the proposed method, the collision-trend index is used to determine propagating speeds for front evolution. It is common sense that the wave front travels faster in deep water than in shallow water. If the workspace is imaged as a ripple tank, then the depth of the water can be regarded to be a function of the collision-trend index. Therefore, the speed required for a front to propagate to a specific position in the workspace is also a function of the collision-trend index. Based on the assumption that a mobile robot should slow down as it approaches an obstacle, a position with a larger collision-trend index value should have a slower propagating speed. Furthermore, in order to prevent collisions between the mobile robot and the obstacles, the propagating speed should fall to zero in the region occupied by obstacles. Based on the above two con) at straints, the normalized propagating speed of position ( time is given as
gradient at a point is perpendicular to the level set which passes through this point, a collision-free path can be generated by solving the ordinary differential equation
if otherwise.
(23) Therefore, as a new grid point is added into the narrow band in the fast march algorithm, (23) is applied to determine the propagation speed for front evolution at this position. B. Optimal Trajectory Generation
From the viewpoint of level set theory, the travel-time set constructed using the interface propagation method is the set of points in two dimensions that can be reached with the same cost, i.e., travel time, . Therefore, the fact that the minimal geodesic is perpendicular to the contour of a level set is applied to generate an optimal path. This result is obtained by extending the Gaussian Lemma [29]. It is used to track the optimal trajectory by starting from the destination points that have been touched by an equal travel-time level set and proceeding backward using the orthogonal property of the optimal path and the contours of the level set. Since the gradient of a function is in the direction of most local descent, and the
HWANG AND JU: GLOBAL TRAJECTORY PLANNING AMONG MOVING OBSTACLES
(b)
(c)
(e)
(g)
(d)
IE E Pr E oo f
(a)
7
(h)
(f)
(i)
(j)
(k)
(l)
Fig. 3. (a) Original environment for this simulation. (b) Scaling the mobile robot to a point. (c) Constructing equal travel-time level sets using the propagating interface model. (d) Generating a piecewise-optimal trajectory using the backward tracing method. (e) The travel time needed for the wave front to reach the target and the planned collision-free trajectory. (f) Speed profile of the planned trajectory. (g)-(l) Snapshots of the mobile robot moving along the planned trajectory.
shown in Fig. 3(f) reveals that as the mobile robot approached an obstacle, it slowed down smoothly to prevent collision. As an obstacle moved away, the mobile robot accelerated to approach the target. Fig. 3(g)–(l) shows that the mobile robot moved along the collision-free trajectory for which the cumulative value of the collision-trend index was a minimum. The second simulation was similar to the first one except that the two obstacles rotated at the same angular speeds of 1.0 /time unit. As shown in Fig. 4(d), instead of moving through the middle free space between the two rotating obstacles, which would result in collision, the mobile robot reached the target using an alternate trajectory generated by the proposed method. Fig. 4(e) shows the travel time needed for the propagating front to reach the target in the workspace. The speed command for each sampling time is shown in Fig. 4(f). The third simulation was similar to the second one. The only difference between the two simulations was in the angular
speeds of the moving obstacles. The angular speeds of the two obstacles were 0.2 /time unit and 1.5 /time unit, respectively. The results are shown in Fig. 5. In this case, a collision-free trajectory, which went through the middle free space between the two rotating obstacles, was generated for mobile robot navigation. Based on the results of those simulations, the proposed method, which embeds the collision-trend index in the propagating interface model, is able to generate a safe trajectory necessary for a mobile robot to approach a target without collision in an environment with different types of moving obstacles. VI. CONCLUSION A global trajectory planning method has been introduced in this paper. By modeling objects of various shapes using
8
IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS, VOL. 49, NO. 6, DECEMBER 2002
(b)
(c)
(d)
IE E Pr E oo f
(a)
(e)
(f)
(g)
(h)
(i)
(j)
(k)
(l)
(m) Fig. 4. (a) Original environment for this simulation. (b) Scaling the mobile robot to a point. (c) Constructing equal travel-time level sets using the propagating interface model. (d) Generating a piecewise-optimal trajectory using the backward tracing method. (e) Travel time needed for the wave front to reach the target and the planned collision-free trajectory. (f) Speed profile of the planned trajectory. (g)-(m) Snapshots of the mobile robot moving along the planned trajectory.
ellipses/circles, obstacles can be efficiently represented in terms of mathematical description and geometrical approx-
imation. Based on elliptic representation, a collision-trend index is generated by geometrically mapping the ellipses onto
HWANG AND JU: GLOBAL TRAJECTORY PLANNING AMONG MOVING OBSTACLES
(b)
(c)
(e)
(g)
(d)
IE E Pr E oo f
(a)
9
(h)
(f)
(i)
(m)
(j)
(k)
(l)
(n)
Fig. 5. (a) Original environment for this simulation. (b) Scaling the mobile robot to a point. (c) Constructing equal travel-time level sets using the propagating interface model. (d) Generating a piecewise-optimal trajectory using the backward tracing method. (e) Travel time needed for the wave front to reach the target and the planned collision-free trajectory. (f) Speed profile of the planned trajectory. (g)-(n) Snapshots of the mobile robot moving along the planned trajectory.
a Gaussian distribution for the purpose of collision detection. The collision-trend index also plays a role which is analogous to the densities of the media which make up the traveling front. The proposed method searches among all the possible robot movements to find a suitable trajectory by minimizing the value of the cumulative collision-trend index. However, it is far from trivial to employ the proposed method in a computationally efficient way. Since the proposed method works on a grid system, it is easy to implement the algorithm in parallel using each mesh point as a small calculating device which communicates
with its neighbors. In addition, by combining the propagating interface model with the configuration space representation [3], it also possible to use the proposed method to plan a collision-free path for a multi-degree of freedom manipulator. It is noted that using only one ellipse to represent an elongated object will result in a larger representation error and generate an inefficient solution for path planning. To overcome this problem, it is feasible to use a set of ellipses/circles to represent an elongated object. Therefore, our future work will include de-
10
IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS, VOL. 49, NO. 6, DECEMBER 2002
veloping a way to systematically model an object using a set of ellipses. REFERENCES
Kao-Shing Hwang received the B.S. degree in industrial design from National Cheng Kung University, Taiwan, R.O.C., in 1981, and the M.M.E. and Ph.D. degrees in electrical and computer engineering from Northwestern University, Evanston, IL, in 1989 and 1993, respectively. In August 1993, he joined National Chung Cheng University, Chia-Yi, Taiwan, R.O.C., where he is currently a Professor in the Electrical Engineering Department. He is also the Director of the Information Management Division at the university computer center. He was a Design Engineer with Sanyo Electric Company, Taipei, Taiwan, R.O.C., during 1983–1985. Between 1987–1988, he was a System Programmer with C & D Microsystem Company, Plastow, NH, where he designed PC drivers and graphic animation. His areas of interest are soft computing, robotics, and embedded system design.
IE E Pr E oo f
[1] V. J. Lumelsky, “Algorithmic and complexity issues of robot motion in an uncertain environment,” J. Complexity, vol. 3, pp. 146–182, 1987. [2] T. Lozano-Pérez and M. A. Wesley, “An algorithm for planning collision-free paths among polyhedral obstacles,” Commun. ACM, vol. 22, no. 10, pp. 560–570, 1979. [3] T. Lozano-Pérez, “Spatial planning: A configuration space approach,” IEEE Trans. Comput., vol. C-32, pp. 108–120, 1983. [4] J. E. Hopcroft, J. T. Schwartz, and M. Sharir, “On the complexity of motion planning for multiple independent objects: PSPACE-hardness of the warehouseman’s problem,” Int. J. Robot. Res., vol. 3, no. 4, pp. 76–88, 1984. [5] R. A. Brooks, “Solving the find-path problem by good representation of free space,” IEEE Trans. Syst., Man, Cybern., vol. SMC-13, pp. 190–197, 1983. [6] C. L. Shih, T. Lee, and W. A. Gruver, “A unified approach for robot motion planning with moving polyhedral obstacles,” IEEE Trans. Syst., Man, Cybern., vol. 20, pp. 903–915, 1990. [7] K. Fujimura, “Motion planning amidst dynamic obstacles in three dimensions,” in Proc. IEEE/RSJ Int. Conf. Intelligent Robots and Systems, 1993, pp. 1387–1392. [8] J. Lu and K. Fujimura, “Shape transformation in space-time,” Vis. Comput., vol. 12, pp. 455–473, 1996. [9] Khatib, “Real-time obstacle avoidance for manipulators and mobile robots,” Int. J. Robot. Res., vol. 1, pp. 65–78, 1986. [10] W. S. Newman and N. Hogan, “High speed control and obstacle avoidance using dynamic potential functions,” in Proc. IEEE Int. Conf. Robotics and Automation, 1987, pp. 131–141. [11] R. Volpe and P. Khosla, “Artificial potential with elliptical isopotential contours for obstacle avoidance,” in Proc. 26th IEEE Conf. Decision and Control, 1987, pp. 180–185. [12] J. O. Kim and P. K. Khosla, “Real-time obstacle avoidance using harmonic potential functions,” IEEE Trans. Robot. Automat., vol. 8, pp. 338–349, 1992. [13] C. I. Connolly, J. B. Burns, and R. Weiss, “Path planning using Laplace’s equation,” in Proc. IEEE Int. Conf. Robotics and Automation, 1990, pp. 2102–2106. [14] D. E. Koditschek, “Exact robot navigation by means of potential functions: Some topological considerations,” in Proc. IEEE Int. Conf. Robotics and Automation, 1987, pp. 1–6. [15] E. Rimon and D. E. Koditschek, “Exact robot navigation using artificial functions,” IEEE Trans. Robot. Automat., vol. 8, pp. 501–518, 1992. [16] J. A. Sethian, “A review of the theory, algorithms and applications of level set methods for propagating interface,” in Acta Numerica. Cambridge, U.K.: Cambridge Univ. Press, 1996. [17] F. Qin, Y. Luo, K. B. Olsen, W. Cai, and G. T. Schuster, “Finite-difference solution of the Eikonal equation along expanding wavefronts,” Geophysics, vol. 57, pp. 478–487, 1992. [18] J. van Trier and W. W. Symes, “”Upwind finite-difference calculation of travel-times,” Geophysics, vol. 56, pp. 812–821, 1991. [19] E. Rouy and A. Tourin, “A viscosity solutions approach to shape-fromshading,” SIAM J. Numer. Anal., vol. 29, no. 3, pp. 867–884, 1992. [20] D. L. Chopp, “Computing minimal surface via level set curvature flow,” J. Comput. Phys., vol. 106, pp. 77–91, 1993.
[21] P. Veselov, “Huygens’ principle and integrable systems,” Physica, vol. D87, no. 1, pp. 9–13, 1995. [22] S. A. Wymer, A. Akhlesh, and R. S. Engel, “The Huygens’ principle for flow around an arbitrary body in a viscous incompressible fluid,” Fluid Dyn. Res., vol. 17, no. 4, pp. 213–223, 1996. [23] S. Quinlan, “Efficient distance computation between nonconvex objects,” in Proc. IEEE Int. Conf. Robotics and Automation, 1994, pp. 3324–3329. [24] A. P. del Pobil, M. Perez, and B. Martinez, “A practical approach to collision detection between general objects,” in Proc. IEEE Int. Conf. Robotics and Automation, 1996, pp. 779–784. [25] F. Solina and R. Bajcsy, “Recovery of parametric models from range images: The case for superquadrics with global deformation,” IEEE Trans. Pattern Anal. Machine Intell., vol. 12, pp. 131–147, 1990. [26] M. Grotschel, L. Lovasz, and A. Schrijver, Geometric Algorithms and Combinatorial Optimization, 2nd ed. Berlin, Germany: Springer-Verlag, 1993. [27] C. J. Wu, “On the representation and collision detection of robots,” J. Intell. Robot. Syst., vol. 16, pp. 151–168, 1996. [28] K. S. Hwang and M. D. Tsai, “On-line collision-avoidance trajectory planning of two planar robots based on geometric modeling,” J. Inform. Sci. Eng., vol. 15, pp. 131–152, 1999. [29] T. C. Gard, Introduction to Stochastic Differential Equations. New York: Marcel Dekker, 1987.
Ming-Yi Ju received the B. S. degree from Tatung University, Taiwan, R.O.C., in 1993, and the Ph.D. degree from National Chung Cheng University, Chia-Yi, Taiwan, R.O.C.. in 2001, both in electrical engineering. From 1998 to 2000, he was with the Institute of Information Science, Academia Sinica, where he participated in research projects on robotics and computer graphics. Currently, he is serving as a Second Lieutenant in the Navy of Taiwan. His research interests include robotics, embedded systems, neural networks, and optimization.