Abstract

We have established a novel method of obstacle-avoidance motion planning for mobile robots in dynamic environments, wherein the obstacles are moving with general velocities and accelerations, and their motion profiles are not preknown. A hybrid system is presented in which a global deliberate approach is applied to determine the motion in the desired path line (DPL), and a local reactive approach is used for moving obstacle avoidance. A machine vision system is required to sense obstacle motion. Through theoretical analysis, simulation, and experimental validation applied to the Ohio University RoboCup robot, we show the method is effective to avoid collisions with moving obstacles in a dynamic environment.

1. Introduction

An omnidirectional robot is a holonomic robot that can move simultaneously in rotation and translation [1]. Most work on omnidirectional robots is in robot development; the few studies on dynamic models are Watanabe et al. [2], Moore and Flann [3], Williams et al. [4], and Kalmar-Nagy et al. [5]. These models all have decoupling between the wheels, which is not complete; thus, we first briefly summarize a new coupled nonlinear dynamics model for three-wheeled omnidirectional robots.

The potential field method was first suggested by Andrews and Hogan [6] and Khatib [7] for obstacle avoidance of manipulators and mobile robots. Obstacles exert a virtual repulsive force, while the goal applies a virtual attractive force to the robot. Koren and Borenstein [8] identify potential field limitations (robot trapped by local minima, oscillation in presence of obstacle, and the lack of passage between closely spaced obstacles). To overcome these problems, they developed the vector field histogram. Ge and Cui [9] mentioned an additional shortcoming, a nonreachable goal with an obstacle nearby, and presented a new repulsive function to overcome it, increasing complexity and computation. Adams [10] presented a simulation study using the potential field method considering low-level robot dynamics, with static obstacles. Guldner and Utkin [11] proposed a method that took the gradient of the potential field as the desired vector field for path planning. Tsourveloudis et al. [12] proposed an electrostatic potential field for an autonomous mobile robot in a planar dynamic environment; their method depends on obstacle prediction accuracy and slow environment changes.

The velocity space method to deal with moving obstacle avoidance in a preknown environment was suggested by Fiorini and Shiller [13], who discussed the velocity obstacle concept. This method lacks potential field simplicity and is effective only if the obstacle moves with constant speed. Chakravarthy and Ghose [14] and Tsoularis and Kambhampati [15] proposed methods which use relative speed to detect collisions. Fujimura and Samet [16] and Conn and Kam [17] presented studies of motion planning in a dynamic environment, but in both of their studies, the dynamic environments need to be completely preknown.

Chang et al. [18] presented a two-phase neural-network-based deliberate path-planning and reactive motion-planning hybrid navigation system for static obstacles. Xu et al. [19] proposed a reactive motion planner that uses local rather than global environment information for static obstacles.

Recently, other authors have presented works on moving obstacle avoidance for robots. Leng et al. [20] presented an improved artificial potential field method by introducing an Anisotropic-Function. The motion ability of an omnidirectional robot in different directions was considered to improve the motion planning and the moving obstacle velocity was preset. Belkhouche [21] presented reactive path planning for a dynamic environment. Der Berg and Overmars [22] presented kinematic and dynamic motion planning roadmaps for dynamic environments.

The potential field method is normally used for path planning and obstacle avoidance in a static environment; still relatively few papers deal with moving obstacle avoidance. The velocity space method applies relative robot/obstacle speed and position to detect a possible collision and plan a motion and normally requires preknown constant obstacle and robot speeds. No fixed time motion is found in the literature on obstacle avoidance. In the current paper, we present a new dynamic obstacle avoidance method with a hybrid (globally deliberate and locally reactive) navigation system and the concept of using relative velocity to detect possible collisions. We have established a novel method of obstacle-avoidance motion planning for mobile robots in dynamic environments, wherein the obstacles are moving with general velocities and accelerations and their motion profiles are not preknown. A hybrid system is presented in which a global deliberate approach is applied to determine the motion in the desired path line (DPL), and a local reactive approach is used for moving obstacle avoidance.

This paper first summarizes a new coupled nonlinear dynamics model for wheeled holonomic omnidirectional mobile robots, followed by development of the novel dynamic obstacle avoidance algorithm, with simulation examples and experimental validation.

2. Three-Wheeled Omnidirectional Robot Modeling Summary

This section presents a brief summary of kinematic and dynamic modeling, plus controller development. For more details, see Wu [23]. Figure 1 shows a bottom view of the Ohio University RoboCup robot. In Figure 2, is the fixed world coordinate frame, and is the moving frame, with the same origin as but rotating with the robot. The axis is set to always be perpendicular to traction force , and is defined as the angle of with respect to . is the traction force of the ground on the wheels and is the Cartesian force and moment on the robot in the moving frame. is the radial distance to the wheels from the robot center. is the radius of the wheels; and are the robot Cartesian velocity in and , and are the wheel angular velocities. The velocity kinematics equations in or are in where is the orthonormal rotation matrix which rotates vectors in to [24].

Without derivation our coupled nonlinear dynamics model is [23] where and are the rotational inertia and mass of the robot, are the motor angular velocities, and are the motor and load rotational damping coefficients, and are the motor and load rotational inertias, is the gear ratio, , where is the th motor voltage input, and are the motor back emf and torque constants, and is the inverse of the motor terminal resistance .

In simulation and hardware, we have implemented a two-level closed-loop controller (Figure 3). The outer loop is a Cartesian pose controller based on machine vision and the inner loop is a wheel velocity controller based on motor encoder feedback. For each level, we use independent linear PI controllers where the gains were obtained through trial and error in simulation; the same gains worked well for the hardware. For many straight-line, triangular, and circular motion commands, the simulation and experiment agrees well with the commanded motion indicating that our model is good and the controller is effective to compensate for the wheel coupling and nonlinearity in (2). See Figure 4 for one sample experimental motion without obstacles, comparing desired and actual position and orientation of the robot. The robot is commanded to move in a straight line between two points, dwell for 2 seconds, and return to the original point, with constant orientation. The robot follows the desired path smoothly and closely.

We have developed novel velocity and acceleration cones to characterize the practical kinematic and dynamic constraints for holonomic three-wheeled omnidirectional mobile robots. These are applied to ensure the path planner does not request more velocity than the robot is capable of kinematically nor excessive acceleration that causes actuator saturation or wheel slippage. Though we have no space to present this, our obstacle-avoidance method in this paper is subject to these practical constraints (see, [25]).

3. Dynamic Obstacle Avoidance

3.1. Problem Statement and Approach

As shown in Figure 5, a mobile robot at point must reach goal point in a fixed time , while avoiding collisions with static and moving obstacles. Line is a given desired path line (DPL). The obstacles’ motions are not preknown, but will be sensed in real-time via machine vision. We assume that the speed and acceleration capacity of all obstacles are similar to that of the mobile robot.

We present a hybrid approach wherein a global deliberate approach is applied to motion along the DPL while a local reactive approach is used to avoid collisions with obstacles. This obstacle avoidance in a nonpreknown environment is not necessarily optimal (when reviewed at a later time), because the obstacles’ motions are not preknown. Obstacle-avoidance decisions made by the robot are based only on past and current obstacle motion data from the vision system to estimate the current velocity of the obstacle. No further prediction about the future obstacle motion is made because smart obstacles may change motion according to our robot motion. All obstacle-avoidance robot motions will be restricted to a fixed-time motion problem: along the direction of the DPL, the motion of the robot is a nearly constant speed motion (ramping up from and down to zero velocity and the start and end, according to the robot acceleration capacity). Obstacle avoidance is realized by changing the robot speed in the direction perpendicular to the DPL. This means if the obstacle is on the line between the robot and target, the robot will change the speed in the direction perpendicular to the DPL while keeping the same speed in the direction along with DPL to reach the target in the fixed time period.

3.2. Moving Obstacle Avoidance

In Figure 5, is the fixed world coordinate system. The local, or DPL, coordinate system has the same origin as , and is parallel to the DPL. In our obstacle-avoidance algorithm, the starting and destination points and other robot motion conditions are transformed to DPL coordinates and then transformed back to for the robot path. The motion along the direction is predetermined (due to the fixed-time requirement), while the motion in the direction will be determined in DPL coordinates for obstacle avoidance, subject to kinematics and dynamics constraints. is the angle of with respect to , where and are the vector position of points and in , and is the quadrant-specific inverse tangent function. The Cartesian position and translational velocity (of the robot or obstacles) in DPL coordinates are found in (4), where is the Cartesian velocity in and is the inverse (transpose) of the orthonormal rotational matrix

3.2.1. Motion in Direction

In DPL coordinates, we assign the robot motion along the DPL () as shown in Figure 6

Equations (5) are for the intermediate time points where is the distance between points and , and and are the velocity and acceleration of the robot in the direction From kinematics, we can find the motion in time periods , , and

The robot starts from point , constantly accelerates by to velocity , then moves with constant velocity in , then constantly decelerates by , and stops at point . During time period , the speed of the robot in the direction is the constant . The total time to move from points to is from (5), assuming that is reset to zero for each motion. can be assigned as the maximum achievable robot acceleration in the direction. If the motion time and are given, is determined from of (5). The robot velocity and acceleration must remain within their practical kinematic and dynamic constraints [25].

3.2.2. Basic Strategy of Obstacle Avoidance

We can simplify by expanding the obstacle radius to (Figure 7), where is the robot radius, and is the obstacle radius. The robot then becomes a point which must avoid the expanded obstacle.

Figure 8 shows the vectors used in the moving obstacle-avoidance algorithm. In DPL coordinates, vector shows the relative position between the point robot and an expanded obstacle (from the robot to the obstacle). From vector loop closure , where and are position vectors of the obstacle and the robot. The distance between the robot and obstacle is . If the robot and obstacle velocities are and , the relative velocity of the robot to the obstacle is . Angle is between the tangent line from the expanded obstacle circle to the point robot and relative the position vector is the angle between the relative position vector and the relative velocity vector . If while the robot passes an obstacle, there will be no collision (Figure 8 pictures the opposite case, i.e., , where there will be a collision). The strategy for moving obstacle avoidance is to check angles and in each time step and command the motion of the robot in the direction (while the planned motion continues) to keep the relative velocity vector away from the possible collision range determined by angle .

Whether to increase or to decrease the velocity of the robot in the direction depends on which is the easier way to turn the relative velocity away from the collision range. In the case of single obstacle avoidance, if we start checking the relationship between and early enough ( at the start), we can simply choose to increase or decrease of the robot by comparing vectors of and . Two unit vectors and are compared to determine the direction of (Figure 9). If , we choose increasing of the robot and choose decreasing (increasing in the negative direction) in the reverse case. In the case shown in Figure 9, is more negative than . thus we increase in the negative direction until . The original is changed to .

Forwarding to the DPL is also considered in our algorithm as choosing the easier way to turn away the obstacle results moving less in the direction perpendicular to the DPL, consequently robot can move back to DPL faster and easier. The “easier way” is judged not only by the relative velocity but also the relative position between the robot and the moving obstacle, both in DPL coordinates. In Figure 8, for example, if the robot turns left to avoid moving obstacle instead of turning right, the robot has to either start moving right earlier or faster to avoid the collision with the moving obstacle.

It will be more complicated in cases where there is not enough distance between the robot and obstacle when a robot starts to turn off the DPL, or a robot already has a velocity in the direction. This is the multiple obstacle-avoidance case (Section 3.2.6).

3.2.3. Range of Checking Collision

An important issue is how to determine when the robot should start to leave the DPL. It will be easier to avoid collisions if the robot starts to turn off the DPL earlier and thus get more time to turn the relative velocity out of the collision range. On the other hand, velocities of obstacles are not constant; it might not be necessary to turn off the DPL if obstacles change their velocity in later time steps. Therefore, we should keep the robot moving along the DPL as long as possible, especially for multiple moving obstacles.

Assume that the maximum velocity of an obstacle is the same as the maximum speed of the robot . We consider the special worst case when the obstacle moves towards the robot along the DPL, both at their maximum speed as shown in Figure 10.

is the relative speed between the robot and obstacle in this case. If the maximum velocity and acceleration of the robot in the direction is and , the time needed to move the robot a distance in the direction to avoid the collision is The distance between the robot and obstacle at which the robot should start checking collision is then Disov from (9). The relative distance in this worst-case scenario is greater than the distance for all other cases, in which the relative speed along the relative distance will be smaller

Since an obstacle can change velocity it is reasonable to use the relative distance Disov to set a range that the robot starts to check possible collisions. When the relative distance with an obstacle is longer than Disov, the possibility of collision with an obstacle is not checked, and the robot will keep moving on the DPL until its relative distance with the obstacle is less than or equal to Disov.

3.2.4. Position for Returning to DPL

After passing by the obstacle, the robot must return to the DPL. Figure 11 shows the robot passing by an obstacle. Points , , and , represent three typical situations. At point , the robot has not yet passed by the obstacle, and it has to keep its velocity in the direction, or possibly increase speed if the obstacle increases its velocity. Point is the critical point, wherein the relative velocity vector is perpendicular to the relative position vector , and the robot is just passing the obstacle. The robot cannot start to turn back to the DPL at point because decreasing speed here may result in a collision with the obstacle in the next time step. Point is the intersection of two tangent lines of the obstacle circle, one parallel to the relative velocity , and the other parallel to the axis. Point is safe since changing the speed of the robot in the direction at point does not cause a collision with the obstacle. The angle between and at point is

It is possible for the robot to start returning to the DPL at any point between and . The robot can still collide with the obstacle if changes too fast, or if the obstacle changes velocity. The relative velocity vector from the point robot should not intersect the obstacle circle when the robot returns to the DPL. The robot has to keep moving with the same velocity in the direction until .

3.2.5. Motion in Direction

The robot motion in the direction is classified into three categories:(1)increase (or decrease) to achieve , (2)keep when , (3)decrease (or increase) to return to the DPL after it passes the obstacle.

When the relative distance with an obstacle is within Disov, the robot starts to check collisions. It starts to increase (or decrease) the speed in the direction if . The velocity in the direction is conditionally calculated as

If but , the robot will maintain its speed in the direction until it reaches the position of returning to the DPL (). The robot will not decrease its speed before that because the obstacle might change its velocity in the next step; this avoids zigzag motions in the direction.

After reaching the position of returning to the DPL (), the robot starts to decrease (or increase) its velocity in the direction to return to the DPL. is accelerated in the direction of returning to DPL. The direction of acceleration will be reversed when a robot is near the DPL so that can end at zero when the robot reaches the DPL (). The velocity in the direction after the robot reaches the position of returning to the DPL is conditionally calculated as follows:

From Figure 11, we can see that angle is changed from less than to greater than when the robot passes by an obstacle. The value of the dot product of and will change from positive to negative when the robot passes by the obstacle.

3.2.6. Multiple Obstacle Avoidance

Multiple obstacle avoidance can be categorized into avoiding collisions with obstacles one-by-one and avoiding collisions at the same time. Group cases can be handled sequentially with the above method. For Group , when the robot is avoiding an obstacle, other obstacles move within Disov. The strategy used in multiple obstacle avoidance is to determine the robot motion by checking all obstacles that are within Disov. The position of leaving the DPL and robot motion in the direction is determined by the obstacle that first appears within Disov with . When the second obstacle also has , the robot will modify its motion, trying to avoid collisions with both obstacles. The position of returning to the DPL is also affected by all obstacles within Disov of the robot.

As an example, obstacle 1 is assumed to enter within Disov first. The robot starts to increase the velocity in the direction to force the relative velocity with obstacle 1 out of collision range determined by . Then, obstacle 2 enters within Disov. At the moment shown in Figure 12, though is already out of the collision range, as is still in the collision range determined by , the robot will keep increasing its velocity in the direction until is out of the collision range.

The multiple obstacle-avoidance algorithm is summarized as follows. (1)The motion along the DPL is the same as that from single obstacle avoidance.(2)Checking collision range: for all moving obstacles with , if the relative robot/obstacle distance is less than Disov, the robot starts checking collisions. (3)Leaving DPL position: the robot leaves the DPL if any of the obstacles within the checking collision range meets the condition . The robot will increase when relative to that obstacle and decrease in the opposite case.(4)If any of the obstacles within the checking collision range satisfies the condition , the robot will keep increasing (or decreasing) until .(5)The robot will keep its velocity in the direction if for all the obstacles within the check collision range.(6)Returning to DPL: when (for all the obstacles within the check collision range) and , the robot will decrease (or increase) to return to the DPL according to (12).

4. Obstacle-Avoidance Simulations and Experiments

4.1. Simulation and Experimental Setup

We developed a simulink model for dynamic obstacle-avoidance simulation. The methods of this paper were used in conjunction with the developed controller (Figure 3) and coupled nonlinear dynamics model (2). Some details are missing in this paper due to lack of space: all motions are subject to practical kinematic and dynamic constraints via novel velocity and acceleration cones [25]; these were implemented in simulink to avoid velocities beyond the robot kinematic capabilities and to avoid accelerations leading to actuator saturation or wheel slippage.

The same simulink model was then used to control the experimental mobile robot, using a PC with a Quanser MultiQ-3 board and Wincon 3.1 software, with cables for communication. The coupled nonlinear dynamics model (2) is replaced by the real robot hardware, but the same controller is used. A machine vision system senses in real time the position of the robot and obstacles (from which the translational velocities are derived from previous steps). Our three-wheeled omnidirectional robot moves on a carpeted field as shown in Figure 13. A colored ball serves as the obstacle, moved by hand (via a long darkened handle, not shown) in the robot field. The hardware control diagram is Figure 14.

The velocity of an obstacle is required as an input for the moving obstacle-avoidance algorithm. One way to obtain the velocity signal is to use a numerical differentiation formula or the Simulink differentiation block, but this leads to a noisy signal. Instead, we applied a low-pass filter velocity estimation algorithm. As seen in Figure 15, this estimation method yields much smoother velocity for feedback than the differentiation block; this is an experimental result where the obstacle was moved by hand in a sinusoidal pattern.

Next, we present simulation and experimental validation examples for static and moving obstacle avoidance; we also present a simulation of multiple moving obstacle avoidance. For more examples and simulation/experimental validation, see Wu [23].

4.2. Example : Static Obstacle Avoidance

In the simulation, the circular robot and obstacles are approximated by octagons to decrease the calculation requirement. Static obstacle avoidance is a special case of moving obstacle avoidance with zero obstacle velocity. Table 1 shows the static obstacle avoidance simulation data (in SI units).

Figure 16(a) shows the static obstacle avoidance simulation results with the conditions of Table 1. The obstacle is placed at constant position , . The robot is commanded to move from starting point (, ) to destination point (, ) along a straight line with a motion pattern in which the robot accelerates to  m/s with  m/s2, maintains that speed for 2.5 seconds (by (5)), and decelerates to stop at the destination point.

A hardware static obstacle-avoidance experiment was performed with the same conditions as the simulated case. The results are shown in Figure 16(b). The actual path is compared with the commanded path (generated by the algorithm in real-time, not preplanned), and the vision signal of the obstacle is displayed. We see that the simulated and experimental mobile robot paths are similar and both successfully avoided the static obstacle. In Figure 16(b), we also see that the actual path follows the commanded path well, indicating that our hardware controller development is effective to compensate for the wheel coupling and nonlinear dynamics effects. Also, the static obstacle position signal is steady from the machine vision system.

4.3. Example : Moving Obstacle Avoidance

Table 2 shows the data (in SI units) for moving obstacle-avoidance simulation.

Figure 17(a) shows the moving obstacle-avoidance simulation results with the conditions of Table 2. The robot is commanded to move from starting point (, ) to destination point (, ) along a straight line with the motion pattern in which the robot accelerates to  m/s with  (m/s2), maintains that speed for 2.5 seconds (by (5)), and decelerates to stop at the destination point. The obstacle starts at (, ) at , with speed 0.2 (m/s) and direction  rad with respect to the axis. The robot effectively avoids the moving obstacle by increasing the speed in the direction. After the robot passes by the obstacle, it returns to the DPL and continues motion along it until the destination point. Sequential robot and obstacle positions in Figure 17(a) represent different snapshots in time, so we see there were no collisions in simulation (robot and obstacle motion is right to left in Figure 17(a)).

A hardware moving obstacle-avoidance experiment was performed with the same conditions as the simulated case; the results are shown in Figure 17(b). The actual experimental path on the right (generated by the algorithm in real-time, not preplanned) compares well with the simulated path on the left. Since the experimental obstacle is moved by hand, it is difficult to exactly match the simulated obstacle motion; the vision signal of obstacle motion is displayed on the right. We see that the simulated and experimental mobile robot paths both successfully avoided the moving obstacle.

4.4. Example : Multiple Moving Obstacles Avoidance

As a final example, we present a simulation of the mobile robot avoiding multiple obstacles. No experimental results are given in this case, since our experimental obstacles are guided by hand. Three obstacles are arranged to get close to the DPL when the robot travels to a destination point on the field. We focus on a Group case, wherein more than one obstacle is in the check collision range at once.

Figure 18 is an example of multiple obstacle-avoidance simulation, in which the robot effectively avoids collisions with multiple obstacles. The data for simulation are in Table 3 (SI units).

Obstacles 1 and 3 are moving, while obstacle 2 is static. As shown in Figure 18, the motion of the robot in the direction is first determined by obstacle 1 (snapshots 5 and 6). Instead of returning to the DPL, the robot maintains its velocity after it passes obstacle 1 as obstacle 2 has already entered the checking collision range with (snapshots 7, 8, and 9). The robot returns to the DPL after passing the static obstacle (snapshots 10 and 11). Instead of slowing down to return to the DPL, the robot passes through the DPL, as obstacle 3 enters the checking collision range with . The robot maintains the speed (snapshots 12 and 13) until it passes obstacle 3 (snapshots 14 and 15). Snapshot numbering is left-to-right and top-to-bottom.

This example is among those that the robot avoids collisions with multiple moving and static obstacles. However, successful obstacle avoidance is not always possible. Under some conditions, the robot is not able to realize multiple obstacle avoidance by the developed algorithm; this is discussed in the next section on limitations of our methods.

5. Limitations of the Dynamic Obstacle-Avoidance Method

Assuming that the obstacle is not so large as to violate the practical robot kinematic and dynamic constraints (or placed too close to the destination point) and that the experimental system is functioning properly, the static obstacle-avoidance algorithm should work in all cases. In this section, we discuss the limitations of our moving obstacle-avoidance algorithm. The algorithm is real time, the obstacles’ motions are not preknown (we assume the obstacle motion limits are similar to the robot’s), and obstacles can change velocities during motion.

5.1. Velocity and Acceleration Limits of the Obstacle

With the developed algorithm, it is possible that robot cannot avoid collisions if the velocity and the acceleration of the obstacle in the direction are higher than those of the robot.

As shown in Figure 19, and are two tangent lines of the obstacle circle parallel to the axis in DPL coordinates. Point is the intersection of the DPL and , and is a point on the DPL between and . Suppose that the velocity of the obstacle in the direction is zero when the robot is at point . The robot moves along the DPL as at point . When the robot is at point , if the obstacle starts to increase its velocity in the direction with an acceleration higher than the maximum acceleration of the robot, and maximum velocity in the direction higher than that of the robot, the robot is not able to avoid a collision with the obstacle.

Failure of avoiding collisions with the obstacle is because the obstacle motion ability is higher than that of the robot, and the motion of the obstacle is not preknown. If the motion of the obstacle is preknown, it is still possible to plan a path to let the robot reach the destination point within a fixed time while avoiding the collisions with the obstacle.

From the above discussion, we conclude that for single obstacle avoidance, the maximum velocity and maximum acceleration of the obstacle in the direction should be lower than (or equal to) that of the robot, and . Since the robot moves with constant velocity for most of the time along the DPL (except near starting or destination points), the acceleration condition is rewritten as , where is the maximum robot acceleration.

The first condition is rewritten as , where is the maximum robot velocity and the planned robot velocity in the direction is . If the obstacle moves perpendicular to the DPL, we have and , which can be considered as the limitation of the acceleration and velocity of the obstacle for algorithm success. In our simulation and experimental study (Section 4), we used . In real applications, if it is necessary to avoid collisions with obstacles having higher velocities than the robot, we must decrease the velocity of the robot in the direction (thus extending the motion time period).

5.2. Failure Cases in Multiple Obstacle Avoidance

If the velocity and acceleration of the obstacle are limited as in Section 5.1, the developed algorithm can effectively avoid collisions with single obstacles. However, for multiple obstacles, there are still some cases in which the robot cannot avoid collisions with the obstacle. One case is that the robot increases its velocity in the direction to avoid collisions with one obstacle. When the robot is at its maximum velocity in the direction, a second obstacle appears in the checking collision range. In order to avoid collisions with the second obstacle, the robot has to increase its velocity in the direction, but the robot has already reached its maximum velocity. Another case is that when the robot has to increase its velocity in the direction for avoiding the first obstacle, the second obstacle appears in the checking obstacle range, which requires the robot to decrease its velocity in the direction. This also results in the failure of collision avoidance with the second obstacle. These failures are due to the fact that obstacles’ motions are not preknown and the robot motion along is fixed due to the fixed time requirement. A path to the destination point in fixed time is not guaranteed when there are more than one obstacle within the checking collision range near the DPL. In such collision avoidance failures, the robot must halt, waiting until it can try for point again, with a new starting point .

5.3. Failure Cases Observed in the Experiment

Four failure modes were observed in the experiment. First, sometimes the robot cannot react to the motion of the moving obstacle; later, we found (by monitoring the vision signal) this is because the vision system did not give the correct signal of the moving obstacle, as the hand and arm moving the obstacle is sometimes visible. This was largely eliminated after we paid attention to the vision range. Secondly, if we move the obstacle too fast, the robot will try to avoid the collision with the obstacle behind the motion of the obstacle. This is a correct reaction in the developed algorithm. However, the tethered wires of the robot interrupt the vision signal or sometimes interfere with a static obstacle, which results in failure cases. This is not an issue for untethered mobile robots. Thirdly, if we move the obstacle too fast (exceeding the velocity limitations discussed in Section 5.1), the robot could not completely avoid collisions. However, we still can see that the robot correctly reacts to the motion of the moving obstacle as best it can. Fourthly, if we move the obstacle differentially to hinder the robot for a relatively long time, the robot could possibly get no chance to reach the destination position, as the field is relatively small.

Because the experimental study for moving obstacle avoidance was only performed for a single moving obstacle (the method handles any number of moving obstacles; up to eight have been simulated (not shown in this paper)), few failure cases were observed. Certainly, additional failure cases would arise in experimental multiple moving obstacle avoidance, which is planned for the near future.

6. Conclusion

A novel hybrid real-time approach has been developed for mobile robot motion planning focusing on moving obstacle avoidance. A global deliberate approach has been applied to the motion along the desired path line (DPL), while a local reactive approach is used to avoid the collisions with obstacles. The motions were subject to kinematic and dynamic constraints expressed by novel velocity and acceleration cones to avoid velocities and accelerations the robot cannot achieve due to kinematics, actuator saturation, and wheel slippage (these were not presented, see [25]). A coupled nonlinear dynamics model and controller were summarized for holonomic three-wheeled omnidirectional mobile robots.

The reactive approach applied to local motion planning used relative velocity between the robot and obstacles to detect and avoid collisions. In addition, instead of using all the global information in the field, the collision detection only uses local information within a range surrounding the robot. Furthermore, with the developed approach, there is no trapping of the robot by local minima and no undesired influence by the obstacle when the robot passes by (these drawbacks are characteristic of the widely applied potential field method of obstacle avoidance).

A fixed time problem has been implemented; that is, the robot strives to reach its goal in a given time, while avoiding obstacles. The method generally handles any obstacle motions (as long as the motion characteristics of the obstacles are similar to the robot), which are not preknown, and obstacle motion can change during the process. A machine vision system senses the obstacles’ motions for use in the algorithm. We have identified limitations of our method, both algorithmic and experimental. Simulation with experimental validation have shown the effectiveness of the developed approach for moving obstacle avoidance by a mobile robot in an unknown changing environment.