36. Robotic Path Planning Methods

36.1 Abstract

The main goal in the control of robots is to achieve human flexibility. Unfortunately humans are very complex systems, and this is carried over to the design of robots. Thus, for any apparently simple task like motion, there are some very complex control problems. When the robot must move between two points, it must consider the control of motors, possible collisions, and physical limitations. These problems have been solved in a number of different ways, and these solutions tend to follow certain trends. In fact, without generalizations, the number of solutions is so diverse, that they tend to overwhelm the search for a simple solution. A formal survey of path planning techniques will allow a knowledgeable overview of path planning. May 18th,1989.

36.2 Introduction

There are a number of different ways to classify the robotics problems. Various features of a problem may determine which type of path planning strategy will work best. Two fundamental classifications suggested by Fu, Gonzalez, and Lee [1987, Pg.150] are Obstacle Constraint and Path Constraint. Obstacle Constraints indicate that there are some points in space which are already occupied, and are not free for the robot to pass through. Path Constraints are usually provided as points on a path which the robot must follow. From these two suggestions there is a control strategy diagram which may be drawn,

Figure 36.1 Figure 1.1 Control Strategies for Manipulators [Fu,Gonzalez & Lee,1987]

These basic strategies form the basis for most approaches to robotic path planning. Positional Control is a simple motion controller using joint interpolated motion, or point to point motion. Path Tracking is moving through a prespecified set of points on a path. All of the strategies in this diagram affect the methods used to plan paths, thus from this point it is best to discuss some requirements of the system.

36.2.1 Robot Applications

Many authors suggest, in their papers, that there are a set of tasks to which a robot may be applied. The earlier work in Artificial Intelligence suggested many approaches to solving problems, which involves splitting them into tasks. It is relatively easy to list a few ’commonly expected’ path planning tasks for a robot.

Grasping and Releasing objects.

Moving from place to place.

Following prespecified paths.

Following moving objects.

Working with other manipulators.

Exerting Forces (i.e.. pushing, pulling and holding).

Exert Torques.

Collecting Data.

Using tools.

Items on this list have been approached by various authors. A paper describing the integrated approach of all these items is yet to be seen, although some combinations have been documented. The ideal situation would be a good general method which incorporates all of these features.

36.2.2 Robotic Constraints

Robots are machines, and as machines they are subject to all of the constraints of mechanics. Thus when dealing with many joints (prismatic or revolute) the physical limits of manipulator motion become evident. For the best solution, the limits of joint and actuator positions, velocity, acceleration, and jerk must be considered. The physical nature of the device also means that there are dimensions which must be considered, thus kinematics and collision avoidance come into play. When a robot makes any move, it expends energy to accelerate, hold and brake. This also means that the energy efficiency of the manipulator should be optimized, by reducing unnecessary expenditures of energy. Most importantly, if robots are to be cost effective, then their speed is of concern. In a high production situation, a cycle time that is 10% faster could save millions of dollars. Thus, time of path traversal can most often be the most important path planning factor.

MEASURES OF PERFORMANCE:

Time for Path Traversal.
Velocity of Manipulator Links or joints.
Energy.
Actuator Forces.
Proximity to Obstacles.

CONSTRAINTS:

Joint Positions, Velocities, Accelerations and Jerks.
Actuator Forces and Dynamics.
Kinematics (this includes singularities).
Collisions with Obstacles.
Time, when moving obstacles are involved.

Considering these factors, the problem may be formulated as a classical optimization problem, as many authors have done. These approaches usually produce good results, at the expense of computation time. Other methods are being found which trade off some of the completeness of the optimization to find solutions quickly.

36.2.3 The Optimization Problem of Path Planners

To aid the description of the path planning problem, a generalized statement of the optimization criteria will be given. This will be presented for both the Measure of Performance and Constraints. The first most important Measure of Performance is time for the path. To find this, and other factors, a number of relations will be derived. First assume that the path is made up of a number of discrete segments (trajectories). These segments are linked together to form the path of motion. Motion along the path will then have a few characteristics, and these provide the basis for some equations.

where: si = the ith segment of the path (i = 0 to n), (a vector trajectory)

P = the total path of n linked segments

D = the total path distance

vi = the velocity on the ith segment.

ti = the time to travel the ith path segment.

T = the total path time.

ei = the energy for the ith path segment

E = the total path energy cost (including kinetic, potential, friction).

Local Path Time: ti =˜ si˜ /˜ vi˜

n

Global Path Time: T = S ˜ si˜ /˜ vi˜

i=1

Local Path Length = ˜ si˜

n

Global Path Length: D = S ˜ si˜

i=1

Local Energy Input = ei

n

Global Energy Input: E = Σ ei

i=1

Feasible is defined as D, P, T, E are all non-infinite.

Local Optimization involves optimizing some function of si, vi & ei.

Global Optimization involves optimizing some function of T, D and E.

Collision avoidance involves altering si so that the path segments avoid obstacles. vi is used to produce the best velocity through a path segment. ei is a factor which is determined from energy input, less energy output (including friction loses). One, or any, of si, vi, ei, or n may be altered when attempting to find an alternate path. These are the only factors describing the path, and they may be found in various ways by themselves. The other factors involving forces, torques, and obstacle proximity must be determined in a similar way that is specific to the manipulator.

An example of how to derive, and apply, optimization techniques to an actual system is in order. To find a value for these parameters for a single link manipulator we would have to define a few variables

Figure 36.2 Figure 1.2 An Example Singe Link Manipulator

This is now a measure of performance for the path described by a set of angular velocities ýi (i = 0 to n). This is a global optimization setup for minimum energy input and minimum time (their exact weightings are determined by Pt & Pe). We could also express the path by a set of joint torques using the value ei. This leads to the problem of what do we do with limits on the system.

The limits on a system are a bit more arbitrary. In this case the manipulator may have a torque limit, and it has a definite position limit. To account for these, equality and inequality constraints may be used. It is best to use Equality Constraints for the motion limits here, so that the rotation may get very close, but not touch the ground. If the motion does violate this constraint, then the function will turn on and make the overall cost very high.

P∅ = Motion Penalty Coefficient

Motion Constraint = 0 (if 0° <= ∅ <=180°)

= P∅ (if 180° <= ∅ <= 0°)

To compensate for the maximum torque here, an Inequality Constraint will be used, so that the torque avoids approaching the maximum torque value.

PΤ = Torque Penalty Coefficient

n

Torque Constraint = PΤ ∑(ei / Tmax)2

i=1

Every torque value is considered and if the torque approaches a maximum, then the torque constraint will grow considerably, and make the overall cost high.

To complete the description the optimization process will be described. The path could be split into 2 segments (n = 2), the first segment goes from 0° to 90°, the second segment goes from 90° to 180°. The process is simple, we choose start values for ∅¢1 and ∅¢2 (these will both be of the same magnitude, but opposite sign in this example). The next step is to calculate the value for cost,

COST = Measurement of Performance + Motion Constraint + Torque Constraint

We would continue choosing new values for ∅¢1 and ∅¢2 until COST has obtained a minimum value. This would provide an optimal path plan. The next factor of importance is to be able to express the difference between various path planning methods.

36.2.4 Evaluation of Path Planners

It is valuable to have a number of criteria to determine the value of a path planning method. These values should reflect the information required, the time (and complexity) of the method, the type of results, and the level of abstraction from the manipulator.

GENERAL REQUIREMENTS EVALUATION CRITERIA:

Dimensions of Space (2D, 2.5D, 3D)
Collision Avoidance (None, Contact Detection, Proximity Calculation)
Multilink Manipulators
Rotations of Payload
Moving Workspace Obstacles
Multi Robot Coordination
Degree of Automation

INFORMATION SETUP EVALUATION CRITERIA:

Information Source (Knowledge Based, Sensor Based)
World Modeling

METHOD EVALUATION CRITERIA:

Path Planning Strategies, for information passing (eg. Hierarchical)
Path Planning Methods (algorithms used for path planning)
Internal Representations
Minimization (Which Costs are minimized?)
Limits (Which limits are considered?)
Solution type (Robot, Joint Space, Cartesian Space, Straight Line, Via Points with Rotations, Splines, etc.)

IMPLEMENTATION EVALUATION CRITERIA:

Execution (Time, Machine, Language)
Testing (What are the experimental results?)

Most of these categories are quite basic, but some are not so clearly defined. All of these areas will be discussed in the subsequent sections.

36.3 General Requirements

The general requirements of a path planner are discussed in this section. Some of the factors involved in the application, and for evaluating their performance, are described. These factors do not include all the essential parts of a path planner, nor all of the possible requirements, but they provide a good idea of what the current requirements are.

36.3.1 Problem Dimensionality

A problem may be represented in one of a number of different dimensions. The fewer the dimensions in the problem, the simpler the solution. A 2D problem is relatively simple, and good solutions already exist for finding paths in this representation. When height is added to the 2D obstacles, it becomes a 2.5D problem. This 2.5D problem is also within the grasp of current problem solving routines. When we try a 3D problem the problem starts to push the current limits of researched techniques and computational ability.

Figure 36.3 Figure 2.1 Dimensionality of Obstacles

36.3.2 2D Mobility Problem

When a simple mobile robot has to navigate across a factory floor, it must solve the classic ’piano movers’ problem. This representation is easily done with convex polygons, and it runs quickly. This problem is referred to as the piano movers problem, because it involves having to move a very large object (like a piano) through a cluttered environment, without picking it up. The perspective is that, the obstacles can be seen from directly above, but they are assumed infinite in height. This method may be adapted for a robotic manipulator, if it is working in a clear workspace, and is performing pick and place operations. The use of this method will save time, in all applicable cases.

As a result of the speed benefit of the 2D path finding solutions, they may be used as analytical tools. A special property can make the 2D methods applicable to 3D problems. If a 2D view of a 3D work space shows a path, then the same path will also exist in the 3D workspace. This has been used in some path planning methods, and can provide a ‘trick’ to avoid extensive 3D calculations. Another trick which may be used, is to represent the moving object with a box or a circle. This result in a simple technique for maintaining a minimum obstacle clearance, for collision avoidance.

Figure 36.4 Figure 2.2 Simplification of 3D Problem

36.3.2.1 - 2.5D Height Problem

When height is added to 2D objects, it is no longer necessary to assume that they have an infinite height. It is equivalent to changing the view from looking straight down on the workspace to looking at it from an angle. This can allow some very simple path plans in which the manipulator is now allowed to move over and around objects. With pick and place tasks this can be the basis for a method which guarantees that the payload, and manipulator links, are above collision height. This is a very practical approximation that is similar to the manipulations which humans tend to favor (i.e. Gravity fed obstacles and objects).

This method is faster than 3D solutions, while still allowing depth in obstacles. Any object in the real world that does not have a vertical orientation will be very difficult to model. Despite this problem, this is still a very good representation for solving most pick and place problems (in an uncluttered workspace).

36.3.2.2 - 3D Space Problem

When we have a cluttered 3D space problem, it may not be possible to resort to the use of 2D and 2.5D representations, if obstacles have irregular surfaces which may not be represented in 2D or 2.5D. This is the most frustrating problem. This problem has fewer simplifying restrictions, and as a result the dimensions grow quickly for every new factor.

The most devastating setback to the 3D methods occurs when a multilink manipulator is added, without any limiting assumptions. The addition of each manipulator link will increase the problem complexity geometrically. This method may be simplified when spheres are used to represent moving obstacles.

The most successful attempts at solving this problem have been the optimization attempts. Optimization methods are typically slow, and thus the three dimensional path planning problem will have to be solved off line for now. If a good fast solution is discovered for this problem, it will eliminate the need for the 2D and 2.5D problems.

36.3.3 Collision Avoidance

Collision detection is the most important factor of Path Planning. Without automatic collision avoidance, the robotic workcell must be engineered to be collision free, or sub-optimal paths must be chosen by a human programmer. Local Collision Detection is important when moving through an unknown, or uncertain environment. These allow for feedback to the planner, for halting paths which contain collisions. Global Collision Avoidance may be done for planning paths which should avoid objects by a certain margin of safety. The actual detail of the method may vary, but moving close to obstacles is avoided by these methods.

Figure 36.5 Figure 2.3 Collision Avoidance

36.3.4 Multilink

One problem that tends to paralyze most methods is the expansion to multilink systems. The first implementation of most techniques is made with a simple mobile robot. When the method is increased by adding oddly sized links, and then a payload, the complexity grows at a more than exponential rate.

The number of degrees of freedom also play in the applications of the robot. If a manipulator has 6 degrees of freedom, then it can obtain any position or orientation in space. Some specific cases of problems require only 3 or 4 degrees of freedom. This can be a great time saver. When an environment becomes cluttered then it may be desirable to have a higher number of degrees of freedom than six, so that the redundancy of the robot can move through the environment. The complexity of most routines increases exponentially with the number of degrees of freedom, thus it is best to match the manipulator degrees of freedom to the complexity of the task to be done.

One assumption that helps reduce the problem complexity is the approximation of motion in a single plane. The net result of this effort is that the robot is reduced to 2 or 3 degrees of freedom. The payload may also be neglected, or fixed, and thus the degrees of freedom are reduced. A second approach is to approximate the volume of the links swept out over a small volume in space. This volume is then checked against obstacles for collisions. A payload on a manipulator may sometimes be approximated as part of the robot if, it is small, or it is symmetrical. This means that the number of degrees of freedom for a manipulator may be reduced, and thus the problem simplified in some cases.

Figure 36.6 Figure 2.4 Multi-Link Approaches

Multilink manipulators also come in a variety of configurations. These configurations lend themselves to different simplifications, which may sometime provide good fast solutions in path planning.

Cartesian (i.e. X, Y, Z motions)

Cylindrical

Spherical (Stanford Manipulator)

Revolute (Like Human arm)

Scara

The various robot configurations are fundamentally different. Many approaches have tried to create general solutions for all configurations, or alternate solutions for different specific manipulators. The fastest solutions are the ones which have been made manipulator specific. With a manipulator it is also possible to describe motions in both Joint Space (Manipulator Space), and Cartesian Space (Task Space). There are approaches which use one, or both of these.

36.3.5 Rotations

Rotations are another problem for some path planners. It can be difficult to rotate during motion, thus some will not rotate, some will rotate only at certain ’safe’ points, and some will rotate along a complete path. The best scenario is when rotations may be performed to avoid collisions, and not just to meet the orientation of the goal state.

Figure 36.7 Figure 2.5 Payload Rotation

36.3.6 Obstacle Motion Problem

Motion of obstacles can cause significant path planning problems. Motion occurs in the form of rotation, and translation. In most path planners the only motions considered are for the payload and manipulator. In most cases an obstacle in the environment will experience both rotation and translation. This has devastating effects on all of the path planning methods, because some tough new requirements are added. The path planning systems must now incorporate a time scale factor, and keep an object description which includes a position, a velocity vector, and rotation vector. The method must also do the calculations to detect collisions and status at every instant of time as the system changes. With simplifications the problem may be reduced to a more manageable level. Obstacles may be categorized into motion categories; Static (un-moving), Deterministic (has predictable occurrence and positions), and Random (Freely moving, with no regular occurrence). All of these are of interest because most parts fixed in a workcell are Static, workpieces from feeders and conveyors are Deterministic, and human intruders are Random. Random obstacle motion usually occurs so quickly that path planning may only be able to escape the path of the obstacle, not compensate it. These motion strategies are often considered in the static and cyclic states, but the Random solutions are not implemented widely, except as safety measures.

Figure 36.8 Figure 2.6 Obstacle Motion Types

36.3.7 Robot Coordination

If only a single robot may be used in a workcell, then bottlenecks will soon arise. When two robots are placed in close proximity, they can produce more bottlenecks, thus they must be given some scheme for avoiding each other. If these robots are to cooperate then a complete and integrated cooperation strategy is required. These strategies require some sort of status link between both manipulators. To make sense of the status of the other robot, it is also necessary to have algorithms for path planning in the Deterministic environment. This algorithm relies upon a proper moving obstacle path planning scheme being developed first. It is possible to use assumptions, or an engineered environment to allow robot coordinations, without the extensiveness of a complete coordination algorithm.

Figure 36.9 Figure 2.7 Multi-Robot Work Spaces

36.3.8 Interactive Programming

One factor that is now available for all commercial robots is the ability for the human user to plan the path. This may be done with a special graphical program, or by moving the robot and setting points, or by entering sets of points. These methods are proven, and do work, but they are very inefficient, inflexible, and prone to errors. Thus the thrust of this paper will be to ignore the interactive approach, because automated path planning is much more desirable. The interactive approach will almost guarantee that an operator will not find an optimal approach. Finding a good path is not possible without having to stop the robot and lose production time.

36.4 Setup Evaluation Criteria

The type of environment information required by a path planner is critical to its operation. Some simple path planners may work in a simple collision detection mode. Some path planners require pre-processed information about the environment, and they are much more difficult to deal with.

36.4.1 Information Source

The sources of information, which a path planner uses, will have a fundamental effect upon how a path is planned. This is a problem, in how the information is collected. Data may be collected before or during the execution of a path. This means data may be presented in the form of an known obstacle (and position), or by a simple indication of contact. These tend to draw distinctions between methods which have Collision Detection (Local or Trajectory Path Planners) and those which have obstacle information (Global Path Planners).

36.4.1.1 - Knowledge Based Planning (A Priori)

It is much easier to solve a problem if all the information is available at the beginning of the solution. In robotics we may plan paths before their execution, if we have some knowledge of the environment. This is strictly a ‘blindly generate’ type of strategy that trusts the knowledge of the environment provided. Planning paths before execution allows efforts to get a shorter path time, more efficient dynamics, and absolute collision avoidance. When working in this mode a priori knowledge (i.e. Known before) is used. Techniques are available to solve a variety of problems, when given the a priori information. Some of the knowledge which we use for a priori path planning may come from vision systems, engineering specifications, or CAD programs.

A Priori Knowledge may be applicable to moving objects, if they have a predictable frequency or motion. A Priori knowledge may not be used for unpredictable or random motion, there is no detection method allowed by its definition.

A Priori Knowledge may be derived from modeling packages or High Level Sensors. These sensors are slow and typically drive a World modeler in an Off-line programmer. The best example of this type of sensor is the vision systems. This system is the most desired information collector for robotics in the future. This system would provide a complete means of world modeling for the path planner. Another common detection system currently in use is the Range Imaging System, which use stripes of LASER light to determine geometry of objects. One example of this is the use of the system to recognize objects and use the geometrical information to determine how to grasp the object [K.Rao, G.Medioni, H.Liu, G.A.Bekey, 1989]. Some of these sensors require knowledge from the world modeler for object recognition purposes. In general these sensors are slower because of their need to interpret low level data, before providing high level descriptions.

Figure 36.10 Figure 3.1 A Priori Path Planning

36.4.1.2 - Sensor Based Planning (A Postieri)

Sometimes information is not available when we begin to solve a problem, thus we must solve the problem in stages as the A Postieri information becomes available. Sensor based planning is an indispensable function when environments change with time, are unknown, or there are inaccuracies in the robotic equipment. A Postieri Knowledge may be used to find the next trajectory in a path (by collecting information about the outcome of the previous trajectory) or even be used strictly to guide the robot in a random sense when exploring an environment. These techniques correspond to an execute and evaluate strategy.

This information feedback is acquired through a set of different sensors. The sensors used may range from vision systems to contact switches. These low level sensors are not very sophisticated, but their low cost makes them very popular. These sensors will typically detect various, expected, conditions. Good examples of these sensors are Position Encoders and Contact Switches. The Sensors can return a signal when contact is made with obstacles, or measure a force being applied. When used in a feedback loop, they may provide actual joint position for a position control algorithm. High level sensors also have the ability to provide low level data, and may be used to detect events. Such Low Level information from this system could also be used to check for collisions while in motion, and detect moving objects. Quite naturally the extent to which this information is collected, determines how the path planner will work.

The ultimate robot would use these sensors to gather information about the environment, and then plan paths and verify information during execution. But this raises the point that a mixture of both of the a priori and a postieri methods must be mixed to make a more dynamic planner. This especially critical when dealing with motion, either to coordinate with regular motion, or to detect and deal with un-predicted motion. Some good papers have already been written on path planning in the A Postieri mode.

Figure 36.11 Figure 3.2 A Postieri Path Planning

36.4.2 World Modeling

How the world is modeled can make a big difference to the path planning strategy. Some of the assumptions about the world are that all obstacles are solid and rigid. Solid is assumed so that collisions will occur on contact. Rigid is assumed so that deformations do not occur on contact. The objects must be represented with some sort of method. Some of the various methods are Polygons, Polyhedra (constructed with 3D polygons), Ellipsoids, sets of points, analytic surfaces, Arrays, Oct-trees, Quad-trees, Constructive Solid Geometry (CSG), and Balanced Trees. The method chosen can limit the use of complex shapes. Some methods are very receptive to data acquired through sensors and CAD systems.

The most common method of representing objects (in all dimensions) is with convex polygons. These are ideal when working with flat surfaces in the real world. Curved surfaces use flat polygons to approximate their surfaces. One factor that makes the polygons an excellent representation is that if a point is found to lie outside one wall of a polygon, then it may be declared to be outside the entire polygon. Most methods do not allow for concave polygons, because they are much more difficult to deal with, in computation. The way to over come this is to use overlapping convex polygons, to represent a concave polygon. These types of representations can typically be derived from most CAD systems. This form allows easy use of existing facilities.

Arrays are good when fast recall of information from a map is required. The set up time for an array is long, the memory required is large, and algorithms are slow. This is a more intuitive approach, but it is also not very practical with present equipment. Quad-trees (for 2D) and Oct-trees (for 3D) are excellent representations for the work space. These allow the workspace resolution to vary, so that empty space in the work cell does not waste space in the representation. The disadvantage to these techniques is their complexity can slow down access times. An enhancement to the Quad-tree and Oct-Tree structures which represent space with blocks and cubes, is a balanced tree which will use non-square rectangles to represent space. This could potentially save even more memory than the other methods, but the routines would again make the access time even slower.

The most powerful method of representation available is CSG (Constructive Solid Geometry). This allows objects to be created by performing boolean operations with geometrical primitives. The original design is done quickly, the object is very space efficient, represents complex surfaces easily, but it is very quite complicated to use. One method discussed is the use of bounding boxes for the different levels of an object’s design tree. A discussion was given by A.P.Ambler [1985] about using Solids modeling with robotics. The thrust of this paper was the different operations, communications, and information which a solids modeler would have to handle to drive a robotic system. This paper proposes a good setup for an Off-Line Programming Package.

It should be noted that sometimes information is given to the world modeler in an awkward form. This information may be represented in another way, or interpreted to make sense of the information. Spatial Planes can be used to establish spatial orientation. Bounding Boxes and Bounding Polyhedra may be used to approximate complex surfaces so that they may be stored in a smaller space, and be easy to use by most algorithms.

Figure 36.12 Figure 3.3 World modeling Techniques

Figure 36.13 Figure 3.4 Modeling Approximation Techniques

36.5 Method Evaluation Criteria

The major variation between the path planning methods arises in the approach to the solution. The methods range from simple mathematical techniques, to very sophisticated multi-component systems with heuristic rules.

As a result of the numerous approaches to the path planning problem that have arisen, a basic knowledge is critical to an overview of the field. The best way to start this section is with a brief definition of strategies, and then a brief explanation of the popular approaches (some specific methods are detailed in the appendices). Even though the system design strategies are not a direct part of path planning, they have a profound impact on the operation of the path planner.

36.5.1 Path Planning Strategies

A path may be planned and executed in a number of different ways. The most obvious is the direct method of planning a path and then executing it. This section will attempt to introduce some of the abstracts behind the strategies of path planners.

36.5.1.1 - Basic Path Planners (A Priori)

Path planners typically use environmental information, and initial and goal conditions. Through algorithmic approaches, the path planners suggest a number of intermediate steps required to move from the initial to the goal state. The path may be described by discrete points, splines, path segments, etc.. Each of the path segments describe a location (or configuration) and rotation of the manipulator and payload. These can be furnished in a number of ways, as joint angles, cartesian locations of joints, location of payload, as a series of relative motions.

36.5.1.2 - Hybrid Path Planners (A Priori)

A newer development is the possibility of hybrid path planning. In this mode a combination of path planning methods would be used to first find a general path (or set of paths) and then a second method to optimize the path. This method is more complex, but has the potential for higher speed, and better results than a single step method.

This strategy may use methods based on alternate representations (like those in figure 3.4). Some common methods in use are Separation Planes, Bounding Boxes, Bounding Polyhedra, 2D views of 3D workspaces, tight corner heuristics, backup heuristics, etc. These are some of the techniques that may be used to refine and produce better paths.

Figure 36.14 Figure 4.1 Basic Operation of a Hybrid Path Planner

36.5.1.3 - Trajectory Path Planning (A Postieri)

The amount of knowledge which a path planner has may be very limited. If the robot has no previous knowledge of the environment, then information must be gathered while the robot is in motion. Trajectory planners rely on feedback for finding new trajectories and detecting poor results. Contact or distance sensors are used to detect an obstacle and the manipulator trajectory is altered to avoid collision. This method will typically guarantee a solution (if it exists or if it does not encounter a blind alley), but at a much higher time cost, and a longer path. The collection of current data becomes critical when dealing with moving obstacles, that do not have a periodic cycle. This method may also be tested by simulation as suggested by K.Sun and V.Lumelsky [1987], who developed a simulator for a sensor based robots.

For the purpose of clarifying this subject a special distinction will be drawn between a path and a trajectory. When discussing a path, it will refer to the complete route traced from the start to the goal node. The path is made up of a number of segments and each of these path segments is continuous (no stop points, or sharp corners). Another name for a path segment could be a trajectory. This distinction is presented as being significant, by the author, when considering a trajectory planner, which basically chooses the locally optimum direction, as opposed to a complete path. Only some path planners use trajectory based planning, which is easier and faster to compute, but generally produces sub-optimal paths.

36.5.1.4 - Hierarchical Planners (A Priori and A Postieri)

If the best of both controllers are desired in a single system, it is possible to use a high level A Priori planner to produce rough paths, and then use a low level A Postieri planner when executing the path. This would make the planner able to deal with complex situations , and the ability to deal with the unexpected. This also has the ability to do rough path planning in the A Priori level, and let the A Postieri level smooth the corners.

Figure 36.15 Figure 4.2 A Hierarchical Planner (and an Example)

36.5.1.5 - DYNAMIC PLANNERS (A PRIORI & A POSTIERI)

Dynamic Planners are a special mixture of an A Priori Path Planner and A Postieri Motion controller for a manipulator. The A Priori Path Planner could plan a path with limited or inaccurate information. If during the execution of this path, a sensor detects a collision, the the A Priori Path Planner is informed, and it updates its World Model, then finds a new path. To be more formal, the dynamic Planner is characterized by separate path planning and execution modules, in which the execution module may give feedback to the planning module. This is definitely a preferred path planner for truly intelligent robotic systems. Some dynamic planners have been suggested which would allow motion on a path, while the path is still being planned, to overcome the path planning bottle neck of computation time.

Figure 36.16 Figure 4.3 Dynamic Path Planning

36.5.1.6 - Off-Line Programming

One strategy that has become popular is the Off-Line Programming approach. When using Off-Line Programming we will take an environmental model, which allows human interaction and graphical simulation to model the robot. Via the tools, the human may produce optimal paths in a combination of human intelligence and algorithmic tools. This is best compared to a CAD package that allows modeling of the robot and the work cell. Once the modeling has been completed, a various assortment of tools are available to plan manipulator motions inside the workcell. This allows rearrangements of obstacles in the workcell, and optimization of robot motions and layout. This sort of software package may be used in a number of modes. The Off-Line Program may interactively calculate, and download, a path which directly drives the robot. The Off-Line Program may also create a path for the manipulator, which includes programming like directions (J.C.Latombe, C.Laugier, J.M.Lefebvre, E.Mazer [1985]). In the Off-line programming mode the results are usually slower, in the order of minutes for near optimal path generation. This time is acceptable when doing batch work, and setups for large production runs. If the Off-line program cannot find an optimal path before the previous tasks have completed, the workcell will have to halt. The most important aspects of the Off-line programmer is the World modeler and Graphical Interface.

An Off-line programmer was discussed by A.Liegeois, P.Borrel, E.Dombre [1985]. The authors approach was to use a CAD based approach with graphical representation and collision detection, then convert the results to actual cartesian or joint coordinates.

At present Off-Line programmers are possible, and there are many good graphical and path planning methods available in construction of these packages.

36.5.1.7 - On-Line Programming

The previous Off-line Programming method allowed a mix of human interaction and A Priori path planning in a modeled environment. The same concept is possible, with human interaction and the A Postieri path planning. This is On-Line programming, because there are no graphical simulations in this strategy, the actual robot is used. On line programming allows the user to directly enter robot motions and directly verify their safety and use tools to optimize the path. This is not desirable for path planning because it is time consuming and inflexible, this is similar to the original method of robot programming with set via points.

36.5.2 Path Planning Methods

This section will attempt to provide a simple point of view, to classify the path planning techniques available. It should be noted that all of the methods are trying to optimize some feature of the path, but they do not all use classical Optimization Techniques.

The most complete approach to path planning is Optimization. Optimization techniques may be done on a local and global basis. Through the calculation of costs, constraints, and application of optimization techniques, an optimal solution may be determined. Some of the mathematical methods used for the optimization technique are Calculus of Variations, Trajectory optimization (hit or miss shoot for the goal state) and dynamic programming. The most noticeable difference between Local and Global optimization is that Local optimization is concerned with avoiding collisions (it will come very close), and global optimization will avoid objects (make a wide path around, when possible).

The most intuitive approach is the Spatial Relationships between Robot and Obstacles. This approach uses direct examination of the actual orientations to find distances and free paths which may be traversed. It was suggested by Lozano-Perez (1983) that spatial planning "involves placing an object among other objects or moving it without colliding with nearby objects". There are quite a few methods already in existence.

The Transformed Space solutions are often based on Spatial Planning problems, they are actually attempts to reduce the complexity of the spatial planning problems by fixing the orientations of objects. These problems diverge quickly from spatial planning when they use transformed maps of space. When space is transformed, it is usually mapped so as to negate the geometry of a manipulator. The best known approach is the Cartesian Configuration Space Approach as discussed by Lozano-Perez [1983]. These techniques have different approaches to representing the environment, but in effect are only interested in avoiding objects, by generating a mapped representation of ’free space’ and then determining free paths with a FindPath algorithm.

An alternative to the previous methods are the Field methods. These methods impose some distributed values over space. The Potential Field method is a technique similar to Spatial Planning representations. This involves representing the environment as potential sources and sinks and then following the potential gradient. This technique is slow and tends to get caught in Cul-de-sacs. The Gradient method is very similar to the Potential field method. It uses distance functions to represent the proximity of the next best point. This method is faster than the Potential field method, and it gets caught in Cul-de-sacs.

An approach which is beginning to gain popularity is the use of Controls Theory for path planning. This was done, very successfully, by E.Freund and H.Hoyer [1988]. This approach allows the non-linear control of a robot, which includes the collision avoidance for many moving objects, mobile robots, manipulator arms, and objects that may have a variable size. This approach seems to have great potential for use in low level control, in the A Postieri sense.

To be complete, there are some techniques that are uncommon (like path planning with simulated annealing S.Kirkpatrick, C.D.Gelatt, M.P.Vecchi [1983]), or are still in their infancy (like the controls approaches). To cover these there will have to be a New and Advanced Topics classification. This does not indicate a shortcoming in the representations, but a lack of definition in the areas included.

36.5.3 Optimization Techniques

These topics include

SPATIAL PLANNING

TRANSFORMED SPACE

FIELD METHODS

NEW AND ADVANCED TOPICS

36.5.4 Internal Representations

Most problem solving techniques need some internal method of dealing with the problem. These methods all have their various advantages. Most of these internal representations depend upon the method of world modeling used in the setup. These may be converted inside the program. There are factors to consider when choosing between various internal representations. For example if arrays are used they are very large and, the updating procedure is very slow, but the lookup is very swift. This technique is of best use when, the obstacles do not move, and the arrays are set up off-line to be used on line. With the current advances in computer hardware (i.e.. Vector Processing and Memory) special hardware may become available that will make the arrays based methods very fast, thus they should not be discarded, but shelved.

The next technique of interest is lists. These are mainly an efficient way to store linked data. This may vary from an oct-tree representation of some object to a simple list of boxes in space. These are efficient with space, but there is storage overhead, and lookups are slower than the array.

Functions are very space efficient, but they are subject to inflexibility. Functions may represent a variety of execution speeds from quite fast for a simple problem to very slow for a complex problem. It should be noted that functions may grow exponentially with increased environment complexity. This function should be used with discretion.

36.5.5 Minimization of Path Costs

Each path has some features which affect the cost. As was described earlier the costs are time, velocity, dynamics, energy, and proximity to obstacles. A basic statement of the goal is given, and this should be used when formulating a complete Measure of Performance function or algorithm.

“The manipulator should traverse the path in the least amount of time, with reasonable forces on the manipulator, using a reasonable amount of energy, and not approaching obstacles too closely.”

36.5.6 Limitations in Path Planning

The constraints in Path Planning were also described earlier. These also evoke a single statement in description,

"The Kinematic, Dynamic and Actuator constraints of the manipulator should not be exceeded, and obstacles should not be touched."

This is worded arbitrarily, because of the variations in different manipulators. If this statement is followed in essence, then the limits will be observed. Consideration of this statement will aid when creating a Constraint function or algorithm for a robot path planner.

36.5.7 Results From Path Planners

The results from path planners tend to come in one of a number of simple forms. The actual numbers may represent joint or cartesian locations. These may be used in various ways to describe a path; Splines, Functions, Locations, Trajectories, and Forces. This area is not of great importance because the problems have been researched, and it is easy to convert between the path planner results. The only relevance of this area is that results are usually expressed in a form preferred by the path planning method.

36.6 Implementation Evaluation Criteria

This section is the most difficult to handle. In some cases the methods are excellent, but the implementations are so poor that they fail to display the merits of a path planning method. Up to now researchers have occasionally included run-times and machines, for their discussions, although some have not tested their methods. This variation is noticeable, thus some standardization is needed. In this section some simple means for comparison are suggested. A quick list of general implementation evaluation criteria is also in order,

minimum time for solution search

minimum path time

maximum forces

minimum distance

maximum torques

2D mobile robots or 3D linked manipulators

feasible trajectories

36.6.1 Computational Time

One thing that needs definition is the Typical Execution Time. The problem with this criterion is computers, languages and programs run at different speeds, and various problems will vary between implementations. Thus the author proposes a set of two scenarios in 2D and 3D workspaces, and suggests that Typical Execution time be expressed in machine cycles (A good High Level Robotics programming Language could save a lot of trouble at this point).

Figure 36.17 Figure 5.1 Path Planning Test Scenarios

These look like nicely packaged problems, but they call for a few exceptions. The classic "Piano Movers Problem" is a good example. The piano movers problem is perfectly suited to a mobile robot. If the routine is used for mobile robots, then both the scenarios above should be used on the object to be moved (without the arm). In both of these problems the consideration of manipulator links is important. In a 3D problem the path planner must consider all links of the robot as linked objects which are to be moved, without collision. The ideal minimum, to properly evaluate the methods on a comparative basis, would need planning time, setup time, travel time, and a performance index (covering stress and strain in the robotic manipulator).

These tests have one bias, both are oriented towards representation with polygons. This was considered acceptable because most objects in the real world are constructed of flat surfaces, or can be approximated with them (like Cylinders, Spheres, Toroids).

The ultimate path planning test could be a needle through a hole problem. In this scenario, a box with a hole in it could be held at an odd angle in space. The peg could be picked up off the ground, and inserted into the hole. The manipulator could then force the peg through the hole as far as possible, and then remove the peg from the other side and return it to its original position. This could also be approached as a single path, or as many as twelve separate paths.

1. Move arm near cylinder

2. Move to and grasp cylinder

3. Move to near hole

4. Insert peg in hole and release.

5. Move arm away from peg.

6. Move arm to near other side of peg.

7. Grasp peg.

8. Remove peg from hole.

9. move peg to near original position.

10. place peg on ground and release.

11. move away from peg.

12. Move arm to start position.

This evokes a number of different approaches. The most obvious is the use of both gross and fine motions. The second most obvious is a single path in which all of the tasks are located at via points on the path. Another approach is to combine steps into more efficient tasks. This problem allows flexibility for all path planners.

Figure 36.18 Figure 5.2 Peg Through Hole Problem

36.6.2 Testing a Path Planner

Testing a new method is very subjective problem. The points to consider are the type of method used, and its implementation. A few points by which to describe these methods are given below, but these facts are not always given in the path planning papers.

Guarantee to find solution.

Optimality of Solution.

Ability for method to get trapped.

Ability to find alternate paths.

Degree of Automation in the Planning process.

36.7 Other Areas of Interest

Some areas do not fit into the standard criteria for evaluation. These are just as important, but have not been needed, or heavily researched yet. This section is intended as a catch-all for the intangible, or so far in-formal, factors in Path Planning.

36.7.1 Errors

Errors are inherent in every sort of system. Robotics is no exception, but in robotics errors can be very costly and dangerous. Thus there is a definite need to deal with error trapping, error reduction, error recovery, error simulation, and error prediction. All of these errors can arise in any part of the system, and in the domain of path planning they can have a drastic effect. An error in world modeling can result in a faulty path that may be less than optimal, or at worst cause a collision. In a feedback system, the errors could indicate fictitious collisions, or empty space when it is actually occupied. Thus all aspects of robotic path planning should eventually encorporate the ability to deal with unexpected events, and eliminate errors.

36.7.2 Resolution of Environment Representation

For some planning methods this is not applicable, but for other methods this becomes a critical factor. The real resolution of the environment is governed by accuracy and repeatability. The accuracy is the variance between the commanded and actual manipulator position. Repeatability is the variation in position that occurs when a position in space is re-found by the manipulator. Both of these factors are subject to possible errors which arise from sensor data. These errors can add a compounded error into the robot system, and thus they should be introduced into the path planning routines. Neither of these methods is considered by many of the authors of papers.

The resolution will have the most profound impact when the environment is represented in an array, oct-tree, Quad-tree, integers, or via sensors. Thus good research into resolution for a robotic system will allow auto scaling of Path Planning methods to be used, to match the environment, and provide realistic accuracies. One benefit of this approach would be running methods quickly at a poor resolution, for fast solutions, and at a high resolution for accurate solutions, in tight corners.

It was suggested by J.H.Graham [1984] that probabilistic methods for path planning help by allowing looser tolerances of parts involved, and allowing motions not normally considered.

To help overcome the resolution problem there are a couple of tricks. When modeling in three dimensions the surfaces may be multifaceted, and hard to calculate quickly. This aspect of calculation may be sped up by using simple approximating surfaces not near the start or stop point, where low resolution is acceptable. It is also possible to use gross motion approximations when traveling through this space. Finally, if the path planner uses collision avoidance, errors in accuracy will be insignificant, because the avoidance of objects may be greater than the resolution..

36.8 Comparisons

Now that the various methods and techniques have been introduced it is possible to discuss them in a general sense. A chart format has been chosen to present some of the known information. The information may be spotty in some cases where researches have not provided complete data. Also, because a chart is a rigid structure to present information of this sort, a small section is included with comments. This table should only be used as an overview, it is not complete, and it is very general.

Figure 36.19 Figure 7.1a A Comparative Chart of Path Planning Methods

Figure 36.20 Figure 7.1b A Comparative Chart of Path Planning Methods

36.9 Conclusions

This is the most interesting section, but unfortunately, very vague. In the next few years Powerful computer hardware advances will allow low cost, but extremely powerful operations. This will make many memory intensive path planning methods feasible, the very complex operations will now be reasonable for calculation. If computers become powerful enough, then an expert path planning system would be a definite asset, making the robots flexible over a number of different frontiers, without any programming. The advance of customized computer hardware which now does graphics indicates that it is very feasible to convert complex robotic path planning from a software to a hardware domain. The potential of parallel processing also opens doors to solving very complex and involved problems.

A good direction for robotics research is to allow a path planning system which will combine the various problems and solutions. This will allow the robot to switch modes with an expert system and thus chose the solution to fit the problem, and not try to make the problem fit the solution, as is commonly done now. This would involve the use of rules and heuristics (based on the elements discussed in this paper) to build up a very complex and complete path planner from very simple methods (which are currently being researched). The multi-level path planning strategies are seen to also hold promise for robotic development (the author prefers the Dynamics Path Planning approach). These approaches allow the best of all planning methods.

36.10 Appendix A - Optimization Techniques

Optimization involves modeling a system as a function of some variables, then deriving some cost, or measurement of performance from it. The variables are then adjusted to get the best measure of performance out. These methods give the best results, but they can be tricky to set up, and they can be very slow.

36.10.1 Optimization - Velocity

By optimizing the manipulator velocity the path time can be reduced, and the robot used to its full ability. One approach was made by S.Dubowsky, M.A. Norris and Z.Shiller [1986]. The thrust of their research was production of a Path Planning CAD System called OPTARM II. Their program will produce a path which is made up of smooth splines. The optimization is done to keep either the maximum or minimum torque on the robot actuators. Their success was in producing path within 5% of optimal value based on collision avoidance and motion limits on the joints. For a six degree of freedom manipulator the program produces smooth motion on the microVAX in a few minutes of CPU time, which will give optimal paths up to twice as fast as the constant velocity method for path motion.

A different approach to the velocity optimization problem was taken by B.Faverjon and P.Tournassoud [1987]. A fast method was found for finding distances of separation between objects in space. The world was modeled as geometrical primitives, and the primitives could be used to represent the world to various depths of complexity.

Figure 36.21 Figure A.1 Various Levels of Geometrical Representation

Using the distance of separation in a function for a velocity damper, the collisions were incorporated as a constraint. When the cost function was optimized for velocity the tendency was to avoid obstacles where velocity was damped. This method was also made to work with moving objects.

This method was intended for use with a 10 link nuclear manipulator, and it has been implemented on a SUN 3 computer. The actual run time was not given, but the routine ran at a tenth of the speed possible with the manipulator. The manipulator was said to have approached objects to within 1 cm.

36.10.2 Optimization: Geometrical

A different approach based on the calculus of variations has been developed by R.O.Buchal and D.B.Cherchas [1989]. The techniques use convex polygons to represent objects, and an iterative technique to find the best path which avoids these polygons. The path is subdivided into a number of smaller intervals, linking a set of pre specified via points. Convex hulls are used to represent the volume swept out by the motion of the moving object. The penetration depth, and penetration vector, are used to correct the path for each of the individual path segments.

Figure 36.22 Figure A.2 Path Segment Interference

The penalty function is formulated as to consider the limits on the joints and actuators. The optimization routine is used to correct the path segments, and this procedure takes about 1 minute on a VAX 11/750 for a 2D model, with manipulator considered, without manipulator collisions. The main objective of this routine is to minimize time. This method needs a set of path points specified for good solutions, and this is a potential area of research.

36.10.3 Optimization - Path Refinement

Some methods provide very rough paths containing jerky motions. To smooth the jerks in paths (as a post processor), a method was suggested by S.Singh and M.C.Leu [1987]. Using the technique of Dynamic Programming, time and energy for a given path are minimized. This method does not account for collisions, but is intended to just be run Off-line. A control strategy is suggested for the manipulator to use on the resulting path. Even though the performance of this method is not given, it looks like a good addition to any a priori programming strategy.

36.10.4 Optimization - Moving Obstacles

Every environment has something moving. To consider this problem B.H.Lee and Y.P.Chien [1987] suggest a method for off-line optimization of this problem. Unfortunately this method was not implemented, thus the success of the technique is unknown. The first constraint is a maximum time for motion, this is to force movement before iminent collision and also to force speed in the path. A constraint is assigned to the priority of the obstacle, which usually has first priority on the path. The constraints of start and stop points are also used. Collision constraints are also used, with every object represented as a sphere. The Cost function considers smoothness of the path, and the torque of the actuators, to ensure that the robot is not overstretched.

36.10.5 Optimization - Sensor Based

An interesting approach to path planning was suggested by B.Espiau and R.Boulic [1986]. In the attempt to find a path planning method for a 10 degree of freedom manipulator, they came up with an unusual approach to optimization. With proximity or contact sensors mounted on every link of the manipulator, the path was navigated. To do this the sensor data would be used alter the penalty functions to represent detected obstacles encountered by the manipulator. The cost function was based on velocity and dynamic functions. This gave a dynamic approach to finding paths in which the path was found by the local optimization of trajectories. For this particular method a large number of sensors are required, and unfortunately the authors did not provide statistics about the performance of the method.

36.10.6 Optimization - Energy

In a method suggested by M.Vukobratovic and M.Kircanski [1982] the energy of the system was proposed as an excellent method for path planning. Using the techniques of optimization for energy the best path is found. This is done by calculating the dynamics at certain points in space, and then using the dynamic programming technique (of operations research) to find the best path. This technique runs a few minutes on a PDP11/70. The end effector is ignored in this method as negligible. This method is only intended to smooth paths, so that the stresses on the load and manipulator are decreased. The information provided on this method was not very complete.

36.11 Appendix B - Spatial Planning

Spatial Planning is best described as making maps of space, then using the direct relationships between those objects in space to find paths. These methods cover a variety of techniques, but essentially their primary function is to determine the spatial relations between the object and the obstacle and avoid collisions. These techniques in general have not produced the best paths, but they produce paths quickly. These methods are also best used with 2D problems.

36.11.1 Spatial Planning - Swept Volume

Lozano-Perez and Wesley (1979) discuss a generate and test strategy used for path planning. The technique will begin with a straight line from start to goal, regardless of collisions. Then a repetitive cycle of analyzing a path (by detecting collisions on the path with Swept Volumes) and then using the information to generate an improved path.

This method may be more formally described with a set of steps. The first step is to check the validity of the proposed path. The path validity is found by considering volume swept out as the object moves along the path. If a collision is not detected the method will be halted. In the case of collision, the information about the collision will be used for correction of path. This information used may include details about the collision, like shape of intersections of volumes, the object causing collision, depth of penetration, and the nearest free point.

The difficulties of this solution become obvious when some of the intricacies of the problem are considered. Models of complex surfaces can contain a very large number of simple surfaces. Calculating the intersections of these numerous simple surfaces can be a very difficult task. A second problem is how we may determine a global optimum when only local information about obstacles at collisions is made available. With the local information about collisions being used in path correction, radical different options are ignored. These two problems could result in an expensive search of the space of possible paths with a very large upper bound on the worst case path length.

Figure 36.23 Figure B.1 Swept Volume Path Planning

36.11.2 Spatial Planning - Optimization

Lozano-Perez and Wesley [1979] describe their work (see Cartesian Configuration Space) as being an improvement over the Optimization Technique of Spatial Planning. The basic concept they describe, is to explicitly compute the collision constraints on the position of a moving object relative to other obstacles. The trajectory picked is the shortest path which will satisfy all of the path constraints.

With objects modeled as convex polyhedra, vertices of the moving object may move between the obstacle surface planes and collide. This condition is easy to detect, because if a vertices is outside any plane of an obstacle, there is no collision. One possible simplification is to use a circle to represent the objects geometry, and just maintain a radial clearance from all objects. It should also be noted that the circular geometry is not sensitive to rotation. This was the path planning technique used in a mobile vehicular robot called SHAKEY by N.J.Nilsson [1969].

Figure 36.24 Figure B.2 Spatial Planning : Optimization

36.11.3 Spatial Planning - Generalized Cones

Generalized cones [R.A.Brooks, 1983] are a faster approach than the Cartesian Configuration Space method . These cones are achieved through a special representation of the environment. The surfaces of convex polygons are used to determine conically bounded pathways, for the path of the object being moved. The method of determining free pathways (or Freeways) is based on the use of cone shaped spaces. The cones fit snugly between objects and have spines that run along the center of the cones. These spines are the paths that the object may travel along. This makes the method inherently 2D and thus has not been implemented in 3D as of yet, but it has spawned a method which is successful in 3D by Brooks[1983]. To determine which spines to follow, the author uses the A* search technique to explore the various paths along the spines. This leads to problems in cluttered spaces where certain possible paths may be overlooked by the generalized cones. This method chooses a path with considerable clearance of objects.

Figure 36.25 Figure B.3 Problem Represented with Generalized Cones

Figure 36.26 Figure B.4 Problem Represented with Generalized Cones

As can be seen the rotation with this technique is very restricted, and the object is typically oriented with the spine.

36.11.4 Spatial Planning - Freeways

A follow up to R.A.Brooks [1983] research into the use of Generalized cones for the representation of Free Space, R.A. Brooks [1983] developed a method of path planning for manipulators with 5 or 6 d.o.f. motion. This method is able to solve the pick and place problem in under a minute on an MIT Lisp machine, by approximating the robot as a 4 d.o.f. manipulator. His method is based on the assumption that the world is represented as supported, and suspended, prisms. This method is suggested as a possible precursor for the use of video information about the workcell, from a high level vision system. This has two points of interest; the objects which are suspended from the side will be grossly misrepresented, but this form of encription suits video cameras well. The assumption that the manipulator may be treated as a set of 4 d.o.f. is based on the limitation of the problem to only pick and place operations and insertion (or fitting) operations. This unfortunately means that the objects may only be rotated about the vertical axis when in motion.

The use of Freeways between obstacles allows a choice between alternate paths.

Figure 36.27 Figure B.5 Freeway Between Blocks

The freeways are basis for maps of joint configurations which are acceptable for motion through these freeways. The methods then find the path using link constraints. This method is described in algorithm form, and the algorithms are quite substantial.

36.11.5 Spatial Planning - Oct-Tree

In a paper by T.Soetadji [1986] a method for 3D path planning by a mobile robot is suggested. The method is based upon use of an Oct-tree representation of 3D space. In the paper, the development of the Oct-Tree routines is discussed, and a robotic system for implementation is suggested. Once the Oct-tree is set up, an A* or a Breadth First search is used to find the best path for the mobile robot. This method finds the minimum distance (with collision avoidance) on a VAX 750. The search time for the path is on the order of 1 second. The tree structure also proves very efficient, because it had only occupied 1.7 MBytes of memory for a very complicated environment.

36.11.6 Spatial Planning - Voronoi Diagrams

A newer approach to representing space has been done with Voronoi Diagrams. O.Takahashi and R.J.Schilling [1989] have suggested such a method. Using an environment of polygons, the pathways may be represented with Voronoi diagrams, then represented in a graph.

Figure 36.28 Figure B.6 Voronoi Diagram of Simple Work Space

After the Voronoi diagram has been set up in graph form, a path may be found. This is simplified by the use of some heuristic rules for wide paths, tight bends, narrow gaps, and reversing, which identify a number of orientations. This procedure produces short smooth paths (which avoid obstacles) for 2D objects on an IBM compatible computer with no co-processor in 10 seconds to 1 minute. This method has potential for use with vision systems. Algorithms suggested by A.C.Meng [1988] allow for fast udate of Voronoi diagrams, in a changing environment. This makes the operation much faster, by avoiding the complete reconstruction of the diagram, and makes real time trajectory correction feasible.

36.11.7 Spatial Planning - General Interest

E.G.Gilbert and D.W.Johnson [1985] created an optimization approach to path planning (with the piano movers problem), with rotations and collision avoidance. This method runs 10 to 20 minutes on a Harris-800 computer. This method was based on work which was later published by E.G.Gilbert, D.W.Johnson, and S.S.Keerthi [1987] which provides algorithms for calculating distances between convex (and concave) hulls in a very short time (order of milliseconds).

36.11.8 Spatial Planning - Vgraphs

A method proposed by K.Kant and S.Zucker [1988] involves collision avoidance of rectangles based upon the search of a VGRAPH. This method also suggests the use of a Low Level controller Collision Avoidance Module. This controller would use low level information about the environment to behave as if experiencing forces from workspace obstacles. The manipulator would be experiencing a pull to the goal state. This method produces a Kinematic and Dynamic, Time Optimal path. None of the implementation details were given in the paper.

Figure 36.29 Figure B.7 : Visibility of Corners of Rectangles (VGRAPH)

36.12 Appendix C - Transformed Space

Some methods find it beneficial to transform the representation of space, so that it simplifies the search for the path. These methods may often be based on Spatial Planning, or any other technique, but they all remap space. These methods are usually very inflexible after mapping, and all environmental changes requires a remapping.

36.12.1 Transformed Space - Cartesian Configuration Space

The Configuration Space method was popularized by Lozano-Perez and Wesley (1979), and was clarified later by Lozano-Perez (1983). The technique of Lozano-Perez and Wesley has become a very popular topic in path planning and is worth an exhaustive discussion. The method provides a simplified technique which will allow movement of one object through a scattered set of obstacles. This is done by simplifying the problem to moving a point through a set of obstacles. The major assumption of this technique is that the objects do not rotate and obstacles are all fixed convex polygons. The obstacles must be fixed to limit the complexity of the solution.

Figure 36.30 Figure C.1 Configuration Space (Find Space & Find Path)

The basic concept involves shrinking the moving object to a single reference point. This is done by growing the obstacles so that their new area covers all of the space in which the object would collide with the obstacles. After the determination of configuration space the problem is then reduced to moving a point through an array of obstacles (i.e.. through the free space).

Unfortunately, a set of obstacles which have been grown are good only for an object which has no rotation throughout its path. This problem is not insurmountable, and may be over come by creating a special representation of the moving object which identifies free space for the object to rotate in. This object will be a convex hull shaped to cover the area swept out when the block rotates about the reference vertex. The convex hull is used to grow the obstacles in configuration space, to find a possible rotation point. Then the path is planned by, finding a path to the rotation point in the first orientation, and a path from the rotation to the goal in the second orientation. The path may also be broken up into more than one rotation, as need demands. Each of these configuration space maps at different orientations are called slices. As seen in the Figure A.4, this has the potential of eliminating some potential paths, or complicating the problem.

Figure 36.31 Figure C.2 Object Rotation in Config Space

The algorithmic technique which Lozano-Perez suggests is a two step solution to the ’Spatial Planning Problem’. His solution covers two main algorithms, Findspace and Findpath. He compares the Findspace algorithm to finding a space in a car trunk for a suitcase. This is the part in which the obstacles are grown to two or three dimensions, rotations are accounted for, and degrees of freedom are considered. At this point is should be considered that the tendency is to work in cartesian coordinates, but use of other representations could simplifiy the object expansion, and the conversion to a VGRAPH. The Findpath problem is comparable to determining how to get the suitcase into that empty space. The Findpath algorithm determines the best path by finding a set of connecting free points in the Configuration Space. To do this a simple three step process has been used. The objects are first grown, and then a set of vertices for each is determined. Next the vertices are check for visibility (ie. can they be seen from the current point?) and a VGRAPH is constructed, and finally a search of the VGRAPH yields a solution. This is a good example of the problem solving techniques of artificial intelligence.

It is very obvious that the technique is not very advanced by itself. There has been some expansion on advanced topics, and these will be discussed below. Another consideration is the addition of a three dimensional setting. This becomes a much more complex problem because of the need to deal with deriving the hulls, locating intersections, finding enveloped points in space. When we expand to three dimensional space the algorithm is still attempting to navigate by corner vertices. In three dimensional trajectories the best paths are usually around edges of objects. A trick must be used to make the search graphs recognize the edges. The trick used is each edge is subdivided from a line with two vertices into a number of smaller lines (with a maximum length limit) and a greater number of vertices. This obviously does not ease the calculation time problem in three dimensions. Another trick is to use care points, located either inside or outside the objects, and then use these as points which require precise calculation nearby, and allow crude calculation when distant.

We must also consider the complexity introduced when a multi link manipulator is to be moved. Our object now becomes a non-convex hull, or a set of convex hulls, possibly represented as the previous slices represented rotations.

An alternate development of the configuration space method was done by R.H.Davis and M.Camacho [1984], which implements the Lozano-Perez methods in Prolog under UNIX. They basically have formulated the problem using the A* search, with a deeper development of the Path Finding Heuristics. Another variation on the Configuration Space Method was that of R.A.Brooks and Lozano-Perez [1985]. Configuration space was sliced and then broken into cells which could be full, half full or empty. From this representation a connectivity graph would be produced, and the A* search would be used to find a path, This technique required alterations to both the FindPath and FindSpace routines. This technique does allow rotations ( but the run time is in the order of tens of minutes on an MIT LISP machine).

An approach for using Cartesian Configuration Space on a Stanford Manipulator (1 Prismatic Joint) was proposed by J.Y.S.Luh and C.E.Campbell [1984]. This method had to consider both the front and the rear travelway for the sliding prismatic link. To do this the manipulator was shrunk to a point, and the rear obstacles translated to the ’front workspace’. The method also makes use of an algorithm for converting non-polygonal shapes to good approximation convex polygons. There were no statistics given with this method.

Configuration Space was used by J.Laumond [1986] to do planning for a two wheeled mobile robot. This method was successful in using configuration space to find paths from some very difficult problems. The best example given of the success of this technique is the Parking Spot problem. In this case the wheeled robot is very similar to an automobile which is stuck between two other parked cars. To get out the robot had to move in both forward and reverse directions to maneuver out of the ’tight spot’.

As for evaluating the overall success of this technique, the computational limits are the major concern. Lozano-Perez, claims success in a laboratory setting with his configuration space path planning routines on a seven degree of freedom manipulator. But he does not note his execution speed, nor does he describe his results quantitatively. This technique was implemented previously by Udupa (1977) for computer control of manipulators. His experiment used a robot with three approximated degree of freedom, in three dimensions. Because of the three degree of freedom limit, the robot was limited in cluttered environments, and had to depend upon some heuristics. His technique also made use of a variable description of space, using recursive addition of straight paths. The recursive determination of paths has some of the same drawbacks that the swept volume method has, and this is what Lozano-Perez and Wesley overcame with their graph search method. This technique is very useful for planning 2 dimensional paths, based on the easy and speed of calculation. There is also no doubt that this technique could be made to work with a more complex robot path planning problem, but the computational speed would be a major factor. Lozano-Perez and Wesley (1979) implemented their algorithms on an IBM370/168 in PL/1. This technique does not handle rotations well, and the result may be a non-optimal solution, or possibly even no solution. The algorithm will provide the shortest distance path, with collision avoidance, but it may not produce continuous paths. Lozano-Perez (1983) also discusses his algorithms in depth which means that his methodology is easy to incorporate in other projects.

36.12.1.1 - Transformed Space - A Cartesian Configuration Space Application

A use of the Configuration Space method was made by C.Tseng, C.Crane and J.Duffy [1988] for a good solution to the pick and place problem. The objects as 2.5D in the environment by represention as upward extruded polygons. First the objects are grown to compensate for the cross-section of the manipulator. The manipulator arm is then ’lifted up’ to ensure clearance of all the objects in its path. This method may fail in the presence of very tall objects. The method was implemented on a VAX 750 and could find paths in cluttered workcells in under 2 seconds.

36.12.2 Transformed Space - Joint Configuration Space

The Cartesian Configuration Space Method uses a check for which particular points in space are free, and then chooses a free path through. This is not very useful when expanding to a multilink manipulator. Thus an approach has been formulated to determine which points in joint space are collision free. This method was formulated by W.E. Red and Hung-Viet Truong-Cao [1985]. This method was applied to manipulators with two revolute joints, and to a robot with one revolute and one prismatic joint. This method works best with two joints, and expansion to three joints requires more computation time. Thus this solution is ideal when the robot is operating in a 2D planar configuration. The effect is a setup time of 2 to 5 minutes, and then 15 seconds for any solution after the initial setup.

Figure 36.32 Figure C.3 Joint Configuration Space for two Revolute Joints

This technique has some definite advantages in the speed of solution. Resolution errors occur due to the resolution of the configuration space map. This table can only be used for the motion of two joints, the third increases the complexity exponentially, but it is still ideal for some batch processing applications.

36.12.3 Transformed Space - Oct-Trees

An interesting method created by B.Faverjon [1986] is to constructively model solid objects (via a custom CAD program) and then generate an Oct-tree representation of joint space from these. The A* search is used to find trajectories in the Oct-tree. This method works in cluttered environments for pick and place operations. The method was solved on a Perkin-Elmer mini-computer in under a minute.

36.12.4 Transformed Space - Constraint Space

K.L.Muck [1988] tried a different sort of mapping technique. Space is represented in an Oct-tree, with the Oct-tree representing robotic motion constraints in the environment. A connectivity graph is then generated from the Oct-tree and the A* search is used. The main thrust of this routine is to reduce the problem to solving the specific motion constraints which apply to the current condition. This technique was implemented for a single link manipulator in a convex hull environment.

36.12.5 Transformed Space - Vision Based

Some of the potential of Spatial Planning is exposed in some of the current research. To allow the development of vision for use in the field of path planning, E.K. Wong and K.S. Fu [1986] have done some research. This research allows a path planning method to be run with three views of a work cell, and from these three views deduce the maximum filled volume. Once the information from the vision system has been interpreted to provide the basic world model, then the objects may be grown into configuration space for an arbitrary moving object. The three views of the object then may be examined from each of the three views, to determine the free path. This premise is based on the idea that if a clear path is visible in one view, then it is a clear path in three dimensional space. This technique uses oct-trees for the representation of space, thus the technique may be very efficient (depending upon the resolution of the oct-tree). This method was implemented on a VAX 11/780 to find a path for an obstacle in three space in 1 to twenty seconds (depending upon the oct-tree search depth). This had not been mated to a vision system in the cited paper.

36.12.6 Transformed Space - General Interest

E.Palma-Villalon and P.Dauchez [1988] came up with a method to do fast path planning for a mobile robot. Rectangles are used to represent obstacles, and the moving robot is represented with a circle. The obstacles are grown by the radius of the circle (into configuration space). A map is created with a course resolution is made to indicate which objects are present in a grid box.

Figure 36.33 Figure C.4 Grid Representation of Space

This map only indicates an objects presence, the remainder of the information is kept in a concurrent list. By finding and using a series of holes and walls within the grid an A* search is applied to find the best path. The cost function of the search is based on the path length and the number of turns made. The performance of this method is not stated, and thus no basis for comparison is available. This method provides straight line path segments. The mapping to configuration space could be convenient for the first pass of a path planner for general path finding.

36.13 Appendix D - Field Methods

In an attempt to model ’natural flow’, there have been attempts to use gradients and potentials to choose natural path choices. These methods use the equivalent of field representations to provide a direction of travel that is ’down hill’. These methods have long setup times, and they can get caught. These techniques will benefit the most as more powerful computer hardware becomes available.

36.13.1 Spatial Planning - Steepest Descent

In an attempt to find a fast path planning method, the steepest descent method was proposed by P.W.Verbeek, L.Dorst, B.J.H. Verwer, and F.C.A. Groen [1987]. Their method is an array based method which will take the workspace represented polygons. This array is a two dimension representation of space in which the goal position is represented with a zero value, and the objects are represented with a value of infinity. Each element of the array is considered in a series of iterations over the array. The result of these iterations is a map of a ’height’ with respect to the goal state. The method then just follows the steepest gradient, down to the goal state.

Figure 36.34 Figure D.1 Steepest Descent Representation and Path

This method has been implemented for a 2D multilink manipulator, but it uses 4 Mbytes of memory for a workspace resolution of 32 by 32 by 32. On a 12 MHz, 68000 VME computer system the whole process takes about 12 seconds. This is broken up into a 6 seconds for detection and labeling of forbidden states, a 6 second generation of distance landscape, and less than a second for finding the shortest path by steepest descent.

36.13.2 Spatial Planning - Potential Field Method

When considering that the basic thrust of the path planning methods is to avoid obstacles, it is easy to compare this avoidance to repulsion. The basic concept of repulsion is based on potential fields, as thus the potential field method of W.T.Park [1984]. In particular, the method was directed towards a workcell with multiple manipulators. In this setting there is a problem with potential manipulator collisions, which must be considered when path planning. To do this a planar view of the work cell is created, and the arms are given a potential. The potential repulsion of the manipulators is mapped for a number of various joint and slider positions. In the work of Park, a manipulator with two revolute joints, and a Stanford manipulator is used. Both of the manipulators have two degrees of freedom, thus a number of two dimensional arrays are necessary to fully describe the work space. This memory requirement is very large, and thus is one of the drawbacks of this technique. The Even with the use of compression techniques, the arrays still consume over 100 KBytes each. In the experimental implementation, the computer used was a VAX 750. The problem was constrained to 4 d.o.f., which used 2 MBytes of memory, and took 8 hours of computation time, to calculate about a million combinations. This method may also get caught in cul-de-sacs. The bottom line on this method is it highly oriented to batch and workcell operations, but too staggering to consider for use in a practical system.

In a more complex vein, Y.K.Hwang and N.Ahuja [1988] have developed a method using polygons and polyhedra to represent objects, from which a potential field is generated. First general topological paths are found from valleys of potential minimums. The best of these paths is selected, and three FindPath algorithms are used to refine it, until it is acceptable. The first algorithm moves along the path and reduces potential numerically. Second, a tight fit algorithm is used for small pathways. Lastly, an algorithm which will move off the given path if necessary is used, as a last resort. This method has been implemented to run on a SUN 260 for a ’Piano Movers Problem’. The total runtime is in the tens of minutes, and it does fail in certain cases.

To avoid becoming trapped when using this method, another approach was developed to mapping the potential field by P.Khosla and R.Volpe [1988]. They have developed an alternate approach which avoids the local minima found in traditional potential field methods. To do this they have used superquadratic approximation of the potential fields to drop off from obstacles swiftly. The superquadratic is used to have a gradual slope to the goal, thus to make sure that its effect is more wide spread than the obstacles. The results which they have obtained are not described, but they have written a program which will work with a two link manipulator, ignoring link collisions.

36.14 Appendix E - New and Advanced Topics

There are some methods of path planning which cannot be easily classified into the four preceding divisions. These are listed here, and they are devided into advanced topics, which are ahead of their time, and new topics which are still awaiting implementation.

36.14.1 Advanced Topics - Dual Manipulator Cooperation

Dual manipulator cooperation is an interesting concept that allows maximum use of the manipulators. When a payload is encountered that is too heavy, or bulky, for a single manipulator, a second manipulator may be used in unison with the first. I.H.Suh and K.G.Shin [1989] have developed some of the theoretical requirements for two manipulators to carry a single large object. This is done through assigning one manipulator as the leader, and the second as the follower. To overcome the problem caused by the limited degrees of freedom, their method allows one manipulator to ’slide’ with respect to the other during the carrying process. If two 6 degree of freedom manipulators were to try and carry a piece together they would find limits. By allowing one manipulator to slide, it is equivalent to adding 1 degree of freedom to the system.

A paper on optimal arm configurations is given by S.Lee [1989]. A method is discussed for identifying optimal dual arm control based on manipulability ellipsoids. This is a lengthy paper outlining all of the details of the method.

36.14.2 Advanced Topics - A Postieri Path Planner

A Sensor Based path planning strategy was devised by (E.Fruend and H.Hoyer [1988]) which allows real time trajectory planning and collision avoidance. This strategy is achieved in a hierarchical system, which is also presented in this paper. This strategy is based on non-linear control theory, and it considers four cases,

1. Moving Arms, Stationary Robots, Stationary Obstacles, and Constant Obstacle Size.

2. Stationary Arms, Mobile Robots, Moving Obstacles, and Constant Obstacle Size.

3. Moving Arms, Mobile Robots, Moving Obstacles, and Variable Obstacle Size.

4. Moving Arms, Mobile Robots, Moving Obstacles, and Constant Obstacle Size.

the calculations of the trajectories in this technique are done on the order of milliseconds, and this shows great potential as the low end of a Dynamic Planner, which is completely autonomous. This method considers the Dynamics of manipulators as well, and attempts to generate a minimum time trajectory, which is collision free.

36.14.3 New Topics - Slack Variables

The use of slack variables has been suggested vaguely in a paper by S.C.Zaharakis and A.Guez [1988]. This uses a 2D environment filled with boxes, in which an A* algorithm is used to find paths. This method finds paths considering bang-bang (full on or full off) control theory, and the manipulator dynamics, to find minimum time paths. The implementation was done on a MAC II, and found results in under a minute.

36.15 References

36.1 A.P.Ambler, "Robotics and Solid modeling: A Discussion of the Requirements Robotic Applications Put on Solid modeling Systems", 2nd International Symposium Robotics Research 1985, pp 361-367.

36.2 R.A.Brooks, T.Lozano-Perez, "A Subdivision Algorithm in Configuration Space for Findpath with Rotation" IEEE Transactions on Systems, Man, and Cybernetics, Vol.SMC-15, No.2, Mar/Apr 1985, pp 224-233.

36.3 R.A.Brooks, "Planning Collision-free Motions for Pick-and-Place Operations", The International Journal of Robotics Research, Vol. 2, No. 4, Winter 1983, pp 19-44.

36.4 R.A.Brooks, "Solving the Find-Path Problem by Good Representation of Free Space" IEEE Transactions on Systems, Man, and Cybernetics (Mar/Apr 1983) Vol.smc-13, No.3, pp 190-197.

36.5 R.O.Buchal, D.B.Cherchas, "An Iterative Method for Generating Kinematically Feasible Interference-free Robot Trajectories", Future Publication in Robotica.

36.6 R.H.Davis, M.Camacho, "The Application of Logic Programming to the Generation of Paths for Robots" Robotica (1984) vol.2, pp 93-103.

36.7 S.Dubowsky, M.A. Norris, Z. Shiller, "Time Optimal Trajectory Planning for Robotic Manipulators with Obstacle Avoidance: A CAD Approach", Proceedings 1986 IEEE International Conference on Robotics and Automation, pp.1906-1912, San Francisco, California, April 1986.

36.8 B.Espiau, R.Boulic, "Collision Avoidance for Redundant Robots with Proximity Sensors", The Third International Symposium of Robotics Research, 1986, pp243-251.

36.9 E.Freund, H.Hoyer, "Real-Time Pathfinding in Multirobot Systems Including Obstacle Avoidance", The International Journal of Robotics Research, Vol. 7, No. 1, February 1988, pp 42-70.

36.10 B. Faverjon, "Object Level Programming of Industrial Robots", Proceedings 1986 IEEE International Conference on Robotics and Automation, San Francisco, April 1986, pp 1406-1412.

36.11 B.Faverjon, P.Tournassoud, "A Local Based Approach for Path Planning of Manipulators With a High Number of Degrees of Freedom", 1987 IEEE International Conference on Robotics and Automation, Raleigh, North Carolina, March-April 1987, pp 1152-1159.

36.12 K.S.Fu, R.C.Gonzalez, C.S.G.Lee, "Robotics; Control, Sensing, Vision, and Intelligence", New York: McGraw Hill, 1987.

36.13 E.G.Gilbert, D.W. Johnson, "Distance Functions and Their Application to Robot Path Planning in the Presence of Obstacles", IEEE Journal of Robotics and Automation, Vol. RA-1, No. 1, March 1985.

36.14 E.G.Gilbert, D.W.Johnson, S.S.Keerthi, "A Fast Procedure for Computing the Distance Between Complex Objects in Three Space", 1987 IEEE International Conference on Robotics and Automation", pp. 1883-1889, Raleigh, North Carolina, March-April 1987.

36.15 J.H.Graham, "Comment on "Automatic Planning of Manipulator Transfer Movements"", IEEE Transactions on Systems, Man, and Cybernetics, Vol. SMC-14, No.3, May/June 1984, pp 499-500.

36.16 Y.K.Hwang, N.Ahuja, "Path Planning Using a Potential Field Representation", Proceedings 1988 IEEE International Conference on Robotics and Automation, Philadelphia, April 1988, pp 648-649.

36.17 Y.Kanayama, "Least Cost Paths with Algebraic Cost Functions", 1988 IEEE International Conference on Robotics and Automation, Philadelphia, Pennsylvania, April 1988, pp 75-80.

36.18 K.Kant, S.Zucker, "Planning Collision-Free Trajectories in Time-Varying Environments: A Two-Level Hierarchy", Proceedings 1988 IEEE International Conference on Robotics and Automation, Philadelphia, April 1988, pp 1644-1649.

36.19 P.Khosla, R.Volpe, "Superquadratic Artificial Potentials for Obstacle Avoidance and Approach", Proceedings 1988 IEEE International Conference on Robotics and Automation, Philadelphia, April 1988, pp 1778-1784.

36.20 S.Kirkpatrick, C.D.Gelatt, M.P.Vecchi, "Optimization by Simulated Annealing", Science, 13 May 1983, Vol.220, No.4598, pp 671-680.

36.21 J.C.Latombe, C.Laugier, J.M.Lefebvre, E.Mazer, "The LM Robot Programming System", 2nd International Symposium of Robotics Research, 1985, pp377-391.

36.22 J. Laumond, "Feasible Trajectories for Mobile Robots with Kinematic and Environment Constraints", Intelligent Autonomous Systems, An International Conference held in Amsterdam, The Netherlands, December 1986, pp 346-354.

36.23 B.H.Lee, Y.P.Chien, "Time Varying Obstacle Avoidance for Robotic Manipulators: Approaches and Difficulties", 1987 IEEE International Conference on Robotics and Automation, Raleigh, North Carolina, March-April 1987, pp 1610-1615.

36.24 S.Lee, "Dual Redundant Arm Configuration Optimization with Task-Oriented Dual Arm Manipulability", Vol. 5, No. 1, February 1989, pp.78-97.

36.25 A.Liegeois, P.Borrel, E.Dombre, "Programming, Simulating and Evaluating Robot Actions", The Second International Symposium of Robotics Research, 1985, pp 411-418.

36.26 T.Lozano-Perez, M.A.Wesley, "An Algorithm for Planning Collision Free Paths Among Polyhedral Obstacles" Communications of the ACM (October 1979) vol.22, no.10, pp 560-570.

36.27 T. Lozano-Perez, "Spatial Planning: A Configuration Space Approach" IEEE Transactions on Computers, Vol.c-32, No.2, February 1983.

36.28 J.Y.S.Luh, C.E.Campbell, "Minimum Distance Collision-Free Path Planning for Industrial Robots with a Prismatic Joint", IEEE Transactions on Automatic Control, Vol. AC-29, No. 8, August 1984.

36.29 A.C.Meng, "Dynamic Motion Replanning for Unexpected Obstacles", Proceedings 1988 IEEE International Conference on Robotics and Automation, Philadelphia, April 1988, pp 1848-1849

36.30 K.L.Muck, "Motion Planning in Constraint Space", Proceedings 1988 IEEE International Conference on Robotics and Automation, Philadelphia, April 1988, pp 633-635.

36.31 N.J. Nilsson, "A Mobile Automaton: An Application of Artificial Intelligence Techniques" Proceedings International Joint Conference Artificial Intelligence, 1969, pp 509-520.

36.32 E.Palma-Villalon, P.Dauchez, "World Representation and Path Planning for a Mobile Robot", Robotica (1988), Volume 6, pp 35-40.

36.33 W.T.Park, "State-Space Representation for Coordination of Multiple Manipulators", 14th ISIR, Gothenburg, Sweden, 1984, pp 397-405.

36.34 K.Rao, G.Medioni, H.Liu, G.A.Bekey, "Shape Description and Grasping for Robot Hand-Eye Coordination", IEEE Control Systems Magazine, Vol.9, No.2, February 1989, pp.22-29.

36.35 W.E.Red, H.V.Truong-Cao, "Configuration Maps for Robot Path Planning in Two Dimensions" Journal of Dynamic Systems, Measurement, and Control (December 1985) Vol.107, pp 292-298.

36.36 S.Singh, M.C.Leu, "Optimal Trajectory Generation for Robotic Manipulators Using Dynamic Programming", Journal of Dynamic Systems, Measurement, and Control, June 1987, Vol. 109, pp 88-96.

36.37 T.Soetadji, "Cube Based Representation of Free Space", Intelligent Autonomous Systems, An International Conference held in Amsterdam, The Netherlands, December 1986, pp 546-560.

36.38 I.H.Suh, K.G. Shin, "Coordination of Dual Robot Arms Using Kinematic Redundancy", IEEE Transactions on Robotics and Automation, Vol.5, No.2, April 1989, pp. 236-242.

36.39 K.Sun, V.Lumelsky, "Computer Simulation of Sensor-based Robot Collision Avoidance in an unknown Environment", Robotica (1987), volume 5, pp 291-302.

36.40 O.Takahashi, R.J.Schilling, "Motion Planning in a Plane Using Generalized Voronoi Diagrams", IEEE Transactions on Robotics and Automation, Vol.5, No. 2, April 1989, pp 143-150.

36.41 C.Tseng, C.Crane, J.Duffy, "Generating Collision-FreePaths for Robot Manipulators", Computers in Mechanical Engineering, September/October 1988, pp 58-64.

36.42 S. Udupa, "Collision Detection and Avoidance in Computer Controlled Manipulators" Ph.D. Thesis, California Institute of Technology, Pasadena, California, 1977.

36.43 P.W.Verbeek, L.Dorst, B.J.H. Verwer, F.C.A.Groen, "Collision Avoidance and Path Finding Through Constrained Distance Transformation in Robot State Space", Intelligent Autonomous Systems, An International Conference held in Amsterdam, The Netherlands, December 1986, pp 627-634.

36.44 M.Vukobratovic, M.Kircanski, "A Method for Optimal Synthesis of Manipulation Robot Trajectories", Journal of Dynamic Systems, Measurement and Control, June 1982, Vol. 104, pp 188-193

36.45 E.K. Wong, K.S.Fu, "A Hierarchical Orthagonal Space Approach to Three-Dimensional Path Planning", IEEE Journal of Robotics and Automation, Vol. RA-2, No. 1, March 1986, pp 42-53.

36.46 S.C.Zaharakis, A.Guez, "Time Optimal Navigation Via Slack Time Sets", Proceedings 1988 IEEE International Conference on Robotics and Automation, Philadelphia, April 1988, pp 650-651.