Content uploaded by Gunther Reissig
Author content
All content in this area was uploaded by Gunther Reissig on Jan 06, 2014
Content may be subject to copyright.
Authors’ Version of a paper presented at the 50th IEEE Conference on Decision and Control,
Orlando, FL, U.S.A., 12-15 Dec 2011. See http://www.reiszig.de/gunther/pubs/i11MILP3D.html
for a BibTeX entry. Definitive Publication: http://dx.doi.org/10.1109/CDC.2011.6161276
Increasing Efficiency of Optimization-based Path Planning
for Robotic Manipulators
Hao Ding†∗ , Gunther Reißig⋆, and Olaf Stursberg†
Abstract—Path planning for robotic manipulators interact-
ing with obstacles is considered, where an end-effector is to
be driven to a goal region in minimum time, collisions are to
be avoided, and kinematic and dynamic constraints are to be
obeyed. The obstacles can be time-varying in their positions, but
the positions should be known or estimated over the prediction
horizon for planning the path. This non-convex optimization
problem can be approximated by Mixed Integer Programs
(MIPs), which usually leads to a large number of binary
variables, and hence, to inacceptable computational time for
the planning. In this paper, we present a geometric result whose
application drastically reduces the number of binary decision
variables in the aforementioned MIPs for 3D motion planning
problems. This leads to a reduction in computational time,
which is demonstrated for different scenarios.
I. INTRODUCTION
Path planning of robotic manipulators has been investi-
gated taking into account safety, efficiency, and optimality.
In general, the task can be summarized as follows: Given an
initial configuration, the best way (with respect to a given
performance criterion) of driving the end effector of a robotic
manipulator into a specified goal region has to be deter-
mined. Kinematic and dynamic constraints, including those
that guarantee the avoidance of collisions with obstacles,
must be obeyed. The obstacles can be time-varying in their
positions, but the positions should be known or estimated
over the prediction horizon for planning the path.
Since this non-convex optimization problem is hard to be
solved efficiently, several motion planning algorithms have
been proposed which are based on solving approximations
to the original problem. A real-time motion planning method
using potential fields by combining repulsive potentials for
obstacles with an attractive potential of the goal was pro-
posed in [1]. Such a method can be applied online, but opti-
mality of motion is not considered and the inclusion of robot
kinematics and dynamics is difficult. Methods operating in
the configuration space, such as cell decomposition [2] and
mixed-integer programming [3], take advantage of the fact
that the configuration of the robot reduces to a single point.
However, to find proper and efficient obstacle representation
is a big challenge for robots with many degrees of freedom
†Institute of Control and System Theory, Dept. of Electrical Engineering
and Computer Science, University of Kassel, Germany, {hao.ding,
stursberg}@uni-kassel.de.
⋆Chair of Control Eng. (LRT-15), Dept. Aerospace Eng., University of
the Federal Armed Forces Munich, D-85577 Neubiberg (Munich), Germany,
http://www.reiszig.de/gunther/
∗Group of Robotics and Manufacturing, ABB Corporate Research,
Ladenburg, Germany
This work is partially supported by the project EsIMiP funded by the
Bavarian Research Foundation (AZ-852-08).
[4]. To account for the drawbacks of these two classes of
methods, sampling-based approaches like rapidly-exploring
random trees (RRTs, [5]) and probabilistic roadmaps (PRMs,
[6]) have been proposed. The idea is to plan the path
in the configuration space, but checking collisions in the
workspace using forward kinematics. As variants, kinody-
namic planning [7], RRT∗[8], elastic roadmaps [9], and
model-based optimization embedded into RRTs [10] have
been investigated. However, all sampling-based approaches
rely on a quantization of the configuration space, of which
only a finite number of samples is considered during motion
planning.
In addition to the previously mentioned techniques, it has
been proposed to solve mixed-integer linear program (MILP)
approximations of path planning problems directly in the
workspace, where selected points on the links (particles)
are used to represent the robot geometry as well as ob-
stacle avoidance constraints [11]. The technique has been
extended in [12] to incorporate state-dependent and time-
varying constraints. Depending on the number of particles
used, this approach often leads to a large number of binary
variables, and hence, to inacceptable computational time for
the planning. For 2D scenarios, we have recently presented
a geometric result whose application to the aforementioned
MILPs drastically reduces the number of binary variables
as well as the computational effort for solving path planning
problems. In this paper, we extend that result to 3D scenarios.
For the sake of simplicity, only time-optimal control will be
considered, i.e., the time for steering the end effector from
a prescribed initial position to a goal is to be minimized,
but the approach we propose also applies to more general
cost functions. We represent the dynamics of the robot by
bounds on the joint velocities. This is justified because the
joint positions of industrial robots are usually controlled by
built-in lower-level controllers. Depending on the capability
of the latter, bounds on velocities can be chosen to guarantee
that the robot can successfully track the optimized trajec-
tories. This simple dynamic model is also useful, e.g. for
human robot interaction and collaboration, where additional
constraints on the joint velocities are imposed depending on
the obstacle movement.
The remainder of this paper is organized as follows:
In Section II, the problem of optimal motion planning
for robotic manipulators in the workspace is defined and
approximated by an MILP. In Section III, we present our
main result, a theorem related to the three dimensional
geometric aspects of collision avoidance, whose application
yields equivalent MILPs with a drastically reduced number
Authors’ Version of a paper presented at the 50th IEEE Conference on Decision and Control,
Orlando, FL, U.S.A., 12-15 Dec 2011. See http://www.reiszig.de/gunther/pubs/i11MILP3D.html
for a BibTeX entry. Definitive Publication: http://dx.doi.org/10.1109/CDC.2011.6161276
of binary decision variables. This leads to savings in the
computational effort for solving motion planning problems,
which is demonstrated in Section IV for a 2-link robotic
manipulator interacting with obstacles in three dimensions.
II. MOTION PLANNING PROBLEM IN THE WORKSPACE
The following notation is used throughout the paper:
•Workspace: the Euclidean space Z=R3with points
(z1, z2, z 3)T∈Z.
•Configuration space:C=Rn; points
(q1, q2,...,qn)T∈Crepresent joint angles of
the robotic manipulator with ndegrees of freedom.
•zj∈Zdenotes the position of joint jincluding the
position of the end effector in the workspace with j∈
{1,...,n+ 1}.
The idea of motion planning considered in the paper is
to determine optimized trajectories of joint positions in the
workspace in order to drive the end effector to the goal set.
The paths of all robot links has to be free of collisions with
the obstacles. Accordingly, the motion planning problem in
the workspace can be formulated as:
min
g
X
τ=0
J(z(τ), τ )(1a)
s.t. (zj(t+ 1) −zj(t)) ∈
[V−
j(z(t), F (t)), V +
j(z(t), F (t))] ·∆t, (1b)
∀t∈ {0,1,...,g−1},∀j∈ {1,...,n+ 1}(1c)
zj(0) = (z1,0
j(0), z2,0
j(0), z3,0
j(0))T, zn+1(g)∈G,
(1d)
H(z(t)) ∩F(t) = ∅,∀t∈ {0,1,...,g},(1e)
where z= (z1,...,zn+1)and:
•the joint velocities in the workspace are bounded to
[V−
j(z(t), F (t)), V +
j(z(t), F (t))];
•∆tdenotes the sampling time;
•the initial joint positions in the workspace zj(0) and the
goal set Gfor the end effector zn+1(g)are specified;
•H(z(t)) represents the geometry of the robotic ma-
nipulator (including the kinematics), which must not
intersect with the forbidden region F(t).
The above optimization problem is non-convex. We here
follow the approach initially proposed in [11], where selected
points of the robot geometry (particles) are used to formulate
obstacle avoidance constraints, and the overall non-convex
optimization problem is approximated by a mixed-integer
linear program (MILP).
A. Collision Avoidance
1) For a Single Point: The condition that a point lies
outside a polyhedral obstacle can be formulated as a mixed-
integer linear constraint, as is explained below.
Let the obstacle P ⊆ Z=R3be a polyhedron, i.e., a
finite intersection of half-spaces,
P={ξ|A·ξ < b},(2)
where A∈RN×3is a matrix with rows Ak,k∈ {1,...,N},
and b= (b1,...,bN)T. The condition that the point ξ
lies outside the obstacle P,ξ /∈ P, is equivalent to the
requirement that at least one among the Nscalar inequalities
in A·ξ≥bis satisfied. This, in turn, is equivalent to the set
of constraints
A·ξ≥b+ (v−1)·M, (3)
N
X
k=1
vk= 1,(4)
where v= (v1,...,vN)Tis a vector of binary variables
vk∈ {0,1}and 1= 1N×1is a vector of ones. Mis a
sufficiently large constant1, hence the name ‘big-M method’
[13]. The constraint (3) says that the kth scalar inequality in
A·ξ≥bis enforced if and only if vk= 1, and the constraint
(4) ensures that the latter equality holds for exactly one k.
If (3) and (4) are constraints in an optimization problem,
points ξ(e.g. joint positions) in the obstacle Pare infeasible,
and hence, collision is avoided. In the presence of multiple
obstacles, an analogous set of constraints, with separate
matrices Aand band separate binary variables vfor each
obstacle, can be used.
2) For Robotic Manipulators: The constraints in (1e) have
been introduced to avoid collisions with obstacles. Assuming
that the links form straight lines between adjacent joints, a
finite number of particles are chosen along the link in order
to represent the geometry of the robot, namely H(z(t)) in
(1e). The particles are chosen by:
psj =λs·zj+ (1 −λs)·zj+1,(5)
where psj denotes the sth particle on link j. By selecting
λs∈[0,1] with s∈ {1,...,S}, where Sis the number of
particles per link, the position psj of the particle is defined.
In order to guarantee that none of the introduced particles is
contained in P, we substitute psj for ξin (3) to arrive at the
constraint
Ak·psj (t)≥bk+ (vj,s,k(t)−1) ·M(6)
for each face kof the obstacle P, each link j, each particle
sassociated with link j, and each time t∈ {0,...,g}. In
addition, the constraint
N
X
k=1
vj,s,k(t) = 1 (7)
is required for each j,sand t. Here, vj,s,k(t)is a binary
variable to be introduced in the MILP as a decision variable,
whereas psj (t)is just an abbreviation for the term (5)
containing the decision variables zj(t).
The number of particles has to be chosen such that the
geometry of any link is represented with sufficient accuracy.
For compensating the error made by approximating collision
avoidance constraints with the help of particles, the obstacle
Pis to be enlarged by a suitable safety margin, which will
be discussed in Sec. IV.
1The way of choosing the value of Mcan be found in [13, p. 205].
Authors’ Version of a paper presented at the 50th IEEE Conference on Decision and Control,
Orlando, FL, U.S.A., 12-15 Dec 2011. See http://www.reiszig.de/gunther/pubs/i11MILP3D.html
for a BibTeX entry. Definitive Publication: http://dx.doi.org/10.1109/CDC.2011.6161276
B. Kinematic and Dynamic Constraints
Since the joints of the robot are connected by straight
links, the kinematic constraints imply that the distance be-
tween the joints qjand qj+1 is equal to the length rj,j+1 of
the corresponding link. This requirement can be represented
by the constraints
(zj+1(t)−zj(t))T·(zj+1 (t)−zj(t)) = r2
j,j+1 (8)
with j∈ {1,...,n}and t∈ {0,1, . . . , g}. See [11].
The quadratic constraints in (8) may be approximated by
a circumscribing polyhedron and an inscribing polyhedron
[14], [12]. If zj+1 (t)−zj(t)lies in the region between
the polyhedra, the kinematic constraints are satisfied ap-
proximately. The fact that zj+1(t)−zj(t)lies inside the
circumscribing polyhedron is expressed by:
Acs ·(zj+1(t)−zj(t)) ≤Bcs ,(9)
where Acs and Bcs specify the circumscribing polyhedron.
Likewise, zj+1(t)−zj(t)must lie outside the inscribing
polyhedron which is formulated by:
Ais ·(zj+1(t)−zj(t)) ≥Bis + (u(t)−1)·M, (10)
where u(t) = (u1(t),...,uNis (t))Tis a vector of binary
variables uk∈ {0,1},Nis the number of faces of the
inscribing polyhedron, 1= 1N×1a vector of ones, and Ma
large constant. In complete analogy to Section II-A.1, the kth
scalar inequality in Ais ·(zj+1(t)−zj(t)) ≥Bis is enforced
if and only if uk(t) = 1. To guarantee that zj+1 (t)−zj(t)
lies outside the polyhedron specified by (10), at least one
among the Nis inequalities must be satisfied, which can be
ensured by the following condition:
Nis
X
k=1
uk(t) = 1.(11)
The conjunction of (9), (10), and (11) approximates the
quadratic equality constraint (8) using linear inequalities and
binary decision variables.
As mentioned before, the dynamic constraints considered
here are the velocity limits of the joints in the workspace.
Varying velocity limits in different regions to account for
the safety of operation or for time and energy efficiency
can also be formulated using binary variables [12]. In the
paper, for simplification, velocity limits (compare to (1b))
are considered as constants for each joint in the workspace:
V−
j·∆t≤(zj(t+ 1) −zj(t)) ≤V+
j·∆t. (12)
The velocity limits may be different for different joints in Z.
C. Objective Function
Different criteria like average kinetic energy or transition
time may be used [11], [12]. Here, only the minimization of
the transition time is considered, which can be realized by
the following cost function [15], [12]:
J=−
g
X
t=0
a(t)(13)
with
a(0) ≤a(1) ≤ · · · ≤ a(g),(14)
where the binary variable a(t)satisfies the constraint
zn+1(t)/∈G⇒a(t) = 0.(15)
III. MAIN RESULT
Using constraints of the form (3) to avoid collisions, as
explained in Sections II-A.1 and II-B, may introduce a huge
number of binary variables. This, in turn, often leads to intol-
erable computational effort for solving the resulting MILPs.
In this section we extend the two-dimensional geometric
result in [15] to the three-dimensional case, which will allow
us to drastically reduce the number of binary variables. To
this end, we first introduce some basic concepts from the
theory of linear programming [16]:
Let the polyhedron Pbe given by P={ξ∈Rm|A·
ξ≤b}, where A∈RN×mand b∈RN. The system
A·ξ≤bis redundant if one of its scalar inequalities is
implied by the others, and non-redundant, otherwise. The
polyhedron Pitself as well as any intersection of Pwith
one of its supporting hyperplanes is called a face of P. A
face containing a single point is called a vertex, and each
compact one-dimensional face is called an edge. A face of
maximal dimension among the faces of Pthat are different
from Pis called a facet, and a face that does not contain
any other face of Pis said to be minimal. Finally, Pis full-
dimensional if its interior is non-empty, and Pis simple if
each of its vertices is contained in exactly mfacets of P.
III.1 Theorem. Let P={ξ∈R3|A·ξ≤b}be a full-
dimensional, simple polyhedron, A∈RN×3,b∈RN,N >
2, and assume that the system A·ξ≤bof linear inequalities
is non-redundant. Let x, y ∈R3,x6=y. Then exactly one of
the following two statements holds.
(i) The line segment Jx, yKjoining xand yintersects the
interior of P.
(ii) There exists a one-dimensional face Eof Pwith the
following property: If f1, f2∈ {1,...,N}are (the
uniquely determined) indices that satisfy
E={ξ∈ P | Af1·ξ=bf1, Af2·ξ=bf2},(16)
then for each point p∈Jx, yKit holds that
Af1p≥bf1or Af2p≥bf2.(17)
Obviously, the two statements are mutually exclusive.
What we need to show is that (ii) holds whenever (i) does
not hold. We sketch a proof which works by reduction to the
two-dimensional case.
Assume that the line segment Jx, yK=
J(x1, x2, x3),(y1, y2, y3)K⊆R3does not intersect the
interior of P. By means of a linear change of coordinates,
one may obtain from P ⊆ R3a full-dimensional polyhedron
e
P ⊆ R2with non-redundant representation
e
P=nξ∈R2
e
Aξ1
ξ2≤˜
bo,(18)
Authors’ Version of a paper presented at the 50th IEEE Conference on Decision and Control,
Orlando, FL, U.S.A., 12-15 Dec 2011. See http://www.reiszig.de/gunther/pubs/i11MILP3D.html
for a BibTeX entry. Definitive Publication: http://dx.doi.org/10.1109/CDC.2011.6161276
such that the line segment J(x1, x2),(y1, y2)K⊆R2does
not intersect the interior of e
P. It can be shown that our
claim follows from the two-dimensional result given below
provided that (18) involves more than two inequalities, which
is the most difficult case.
III.2 Theorem ([15]). Let (18) be a full-dimensional poly-
hedron, e
A∈RN×2,e
b∈RN,N > 2, and assume that
the system e
A·ξ≤˜
bof linear inequalities is non-redundant
and that the rows of e
Aare ordered counterclockwise. Let
˜x, ˜y∈R2,˜x6= ˜y. Then exactly one of the following two
statements holds.
(i) The line segment J˜x, ˜yKjoining ˜xand ˜yintersects the
interior of e
P.
(ii) There is some i∈ {1,...,N}such that for each point
p∈J˜x, ˜yKit holds that e
Aip≥˜
bior e
Ai+1p≥˜
bi+1.
Here, e
Aidenotes the ith row of e
A, and e
Ai+1 stands for
e
A1if i=N.
A direct application of Theorem III.1 shows that in order
to avoid collisions it suffices to introduce two constraints
Af1(E)psj (t)≥bf1(E)+ (vj,E(t) + wj,s (t)−2)M, (19a)
Af2(E)psj (t)≥bf2(E)+ (vj,E(t)−wj,s (t)−1)M(19b)
for each one-dimensional face Eof the obstacle P, each
link j, each particle sassociated with link j, and each time
t∈ {0,...,g}. In addition, a constraint
X
E
vj,E (t) = 1 (20)
is required for each jand t, where the sum is over all
one-dimensional faces Eof P. Here, vj,E(t), wj,s (t)∈
{0,1}are binary variables to be introduced in the MILP as
decision variables, and for each one-dimensional face Eof
P,f1(E)and f2(E)denote the uniquely determined indices
that satisfy (16).
In the above formulation (19)-(20), the binary variable
vj,E (t)can be seen as selecting a pair of adjacent facets
of the obstacle Pthat share a common edge, rather than a
facet of Pas with the formulation in Sections II-A.1 and II-
A.2, and the binary variable wj,s (t)selects one of the facets
of the already selected pair. Indeed, (19a) is only enforced
if vj,E (t) = wj,s(t) = 1, and (19b) is only enforced if
vj,E (t) = 1 and wj,s (t) = 0.
The crucial point here is that vdoes not anymore depend
on the particle index s, which greatly reduces the number
of binary decision variables. In fact, the number of binary
variables introduced for the purpose of formulating collision
avoidance constraints is
n·(g+ 1) ·(S+Ne)
in contrast to
n·(g+ 1) ·S·N
for the method of Sections II-A.1 and II-A.2, where Ne
denotes the number of one-dimensional faces of P.
IV. COMPUTATIONAL RESULTS
The proposed method is applied to a 2-link robotic ma-
nipulator in R3interacting with two and three obstacles,
respectively. Its performance is compared to that of the
method from [12].
For the 2-link scenario of Fig. 1, the robotic manipulator
interacts with two obstacles. One of them is the 8-face
polyhedron Pshown in Fig. 1, and the other is a table-
like obstacle represented by the constraint zj≥ −0.2for
j∈ {1,2}.
Our computational results are based on the following
parameters. The sampling time is ∆t= 0.2, the link length
is 0.3, and the bounds on the velocities in the workspace
of the middle joint and the end-effector are 0.2and 0.3,
respectively. The end effector is to be driven to the goal
region G= [0.19,0.21] ×[0.49,0.51] ×[−0.01,0.01] from
the initial position determined by z1= (0,0,0)T(base joint),
z2= (0.3,0,0)T(middle joint), and z3= (0.6,0,0)T(end-
effector). Particles are equally distributed on each link, which
include the end-effector of the corresponding link.
Base Joint Start
G
P
z3
z2
z1
0.100.10.20.30.40.5
−0.1
0
0.1
0.2
0.3
0.4
0.5
−0.2
0
0.2
Fig. 1. A 2-link robotic manipulator interacting with a 8-face obstacle P.
The final configurations are shown in blue, and the computed motion of
the end effector which reaches the goal within 12 steps, is illustrated by a
sequence of green dashed line segment.
The method proposed in this paper is capable of planning
the motion of sampled systems only. However, the resulting
motion can be forced to satisfy the constraints between the
sampling instants if the method is applied to a robust version
of the original specification, e.g. [17]. For the scenario con-
sidered here, such a robust version is obtained by enlarging
the obstacles by a suitable safety margin, which is shown
as the larger polyhedron in Fig. 1. That margin is chosen to
additionally account for the error made by approximating the
link length constraint (8), the error made by approximating
collision avoidance constraints with the help of particles, as
well as the error made by neglecting the links’ width.
The method proposed in the present paper and the previous
method from [12] have been implemented in C++ using
Concert Technology libraries in CPLEX Studio Academic
Research 12.2 and run on a single thread of an i5-CPU with
Authors’ Version of a paper presented at the 50th IEEE Conference on Decision and Control,
Orlando, FL, U.S.A., 12-15 Dec 2011. See http://www.reiszig.de/gunther/pubs/i11MILP3D.html
for a BibTeX entry. Definitive Publication: http://dx.doi.org/10.1109/CDC.2011.6161276
Particles S
Binaries
1000
2000
3000
4000
5000
10000
0 5 10 15 20 25 30 Particles S
1
100
1000
10000
0 5
10
10 15 20 25 30
Computational Time (sec)
Fig. 2. Number of binary variables in the MILP (left) and the computational time (right), as a function of the number Sof particles per link for the
scenario of the 2-link robot interacting with the 8-face obstacle. (•corresponds to the methods proposed in the present paper, and ◦, to that from [12]).
Base Joint
P3
P2
P1
Start
G
z3
z2
z1
0.4
0.2
0
0.2
0.4
0.6−0.4
−0.2
0
0.2
0.4
−0.5
0
0.5
(a) Side view.
Base Joint
P3
P2
P1
Start
G
z1
z2
0.4
0.3
0.2
0.1
0
0.1
0.2
0.3
0.4
0.5
0.6
−0.4−0.3−0.2−0.1
00.10.20.30.40.5
(b) Top view.
Fig. 3. A 2-link robotic manipulator interacting with 3 obstacles.
2.67 GHz clock rate. In order to separate the effects of dif-
ferent MILP formulations from unknown heuristics that are
built in to CPLEX, the MIP Strategy Probe2is turned off. The
quadratic constraints of each link length are approximated
by two inscribing and circumscribing polyhedra of 14 faces
each, see Section II-B. The ‘big-M method’ of Section II-
A.1 is applied with M= 100. We use the horizon g= 14,
and the goal can be reached within 12 steps.
The results presented in Fig. 2 show that the MILP
formulation proposed in the present paper drastically reduces
the number of binary decision variables. In addition, the
computational time has been reduced in most of the cases,
especially when the number of particles is large.
A more challenging scenario of a 2-link robot with 3
obstacles of 6faces each is illustrated in Fig. 3. We choose
a prediction horizon of g= 16, and the goal is reached at
the 15-th step. Specifically, for S= 5 and g= 9 in this
2Probe determines the extent by which variables should be probed prior
to the branching phase. Depending on the particular optimization problem,
that option may have a dramatic influence on the solution time [18].
scenario, the solution was determined within 0.497 seconds
using 4threads.
Further tests which we do not report here in detail have
shown that the computational effort may vary widely even
for scenarios that look quite similar. In addition, if all the
powerful built-in heuristics are used, CPLEX often shows
an excellent performance regardless of any specific MILP
formulation, especially if the number of particles is small.
In this paper, we have combined the idea of reducing
the number of binary variables with some but not all of
the aforementioned built-in heuristics. Our results on 2D
planning problems [15] show that a combination with a
larger set of built-in heuristics leads to even more impressive
reductions in computational effort.
V. CONCLUSIONS AND FUTURE WORK
Motion planning for robotic manipulators with polyhedral
obstacles and velocity constraints for the joint positions
is considered in the paper. It has been approximated by
Mixed-Integer Linear Programs (MILPs). We have presented
Authors’ Version of a paper presented at the 50th IEEE Conference on Decision and Control,
Orlando, FL, U.S.A., 12-15 Dec 2011. See http://www.reiszig.de/gunther/pubs/i11MILP3D.html
for a BibTeX entry. Definitive Publication: http://dx.doi.org/10.1109/CDC.2011.6161276
and proved a geometric theorem in R3whose application
drastically reduces the number of binary decision variables
in the MILPs, compared to previous results from [12]. In
addition, computational time during the MILP solution is
reduced in most cases, especially with larger number of
particles, over previous methods.
The combination of the proposed theorem in R3with
suitable heuristics in CPLEX is a matter of current research.
An ambitious goal is to generate the path of the robotic
manipulator online with identification of dynamic obstacles
(like human operators [19]) from measured data, which has
been realized in a human-robot-interaction scenario in [20].
The computation will be accelerated by using the moving
horizon scheme known from model predictive control rather
than optimizing at once over the complete time span required
to reach the goal. Our results indicate that the method
proposed in this paper can be successfully applied in this
setting in order to plan a robot’s motion online.
We also work on extending the method to cover more
general dynamic constraints than just velocity bounds, by
combining our results with a recently proposed method for
computing reachable sets of nonlinear systems [21].
REFERENCES
[1] O. Khatib, “Real-time obstacle avoidance for manipulators and mobile
robots,” Int. J. of Robotics Research, vol. 5, no. 1, pp. 90–98, 1986.
[2] J. Latombe, Robot Motion Planning. Kluwer, 1991.
[3] H. Ding, M. Zhou, and O. Stursberg, “Optimal Motion Planning for
Manipulators with Dynamic Obstacles using Mixed Integer Linear
Programming,” in IEEE Mediterranean Conf. on Control and Automa.,
2009, pp. 934–939.
[4] M. W. Spong, S. Hutchinson, and M. Vidyasagar, Robot Model and
Control. John Wiley & Sons, Inc., 2006.
[5] J. Kuffner and S. LaValle, “RRT-connect: An efficient approach to
single-query path planning,” in Proc. IEEE Int. Conf. on Robot. and
Autom., 2000, pp. 995–1001.
[6] L. Kavraki, P. Svestka, J. Latombe, and M. Overmars, “Probabilistic
roadmaps for path planning in high-dimensional configuration space,”
IEEE Transactions on Robot. and Autom., vol. 12, no. 4, pp. 566–580,
1996.
[7] D. Hsu, R. Kindel, J.-C. Latombe, and S. Rock, “Randomized kin-
odynamic motion planning with moving obstacles,” Int. J. of Robot.
Research, vol. 21, no. 3, pp. 233–255, 2002.
[8] S. Karaman and E. Frazzoli, “Sampling-based algorithms for optimal
motion planning,” Int. J. of Robot. Research, vol. 30, no. 7, pp. 846–
894, 2011.
[9] Y. Yang and O. Brock, “Elastic roadmaps - motion generation for
autonomous mobile manipulation,” Autonomous Robots, vol. 28, pp.
113–130, 2010.
[10] H. Ding, G. Schnattinger, B. Passenberg, and O. Stursberg, “Improving
motion of robotic manipulators by an embedded optimizer.” in IEEE
Conf. on Autom. Sci. and Eng., 2010, pp. 204–209.
[11] L. Blackmore and B. Williams, “Optimal manipulator path planning
with obstacles using disjunctive programming,” in Proc. of the Amer-
ican Control Conference, 2006, pp. 3200–3202.
[12] H. Ding, M. Zhou, and O. Stursberg, “Optimal path planning in the
workspace for articulated robots using mixed integer programming,” in
IEEE/RSJ Int. Conf. on Intell. Robots and Syst., 2009, pp. 5770–5775.
[13] H. P. Williams, Model building in mathematical programming, 2nd ed.
WILEY, 1985.
[14] A. Richards and J. How, “Mixed-integer programming for control,” in
Proc. of the American Control Conference, 2005, pp. 2676–2683.
[15] H. Ding, G. Reißig, D. Gross, and O. Stursberg, “Mixed-integer
programming for optimal path planning of robotic manipulators,” in
IEEE Conf. on Autom. Sci. and Eng., 2011, accepted.
[16] A. Schrijver, Theory of linear and integer programming. Chichester:
John Wiley & Sons Ltd., 1986, a Wiley-Interscience Publication.
[17] G. E. Fainekos, A. Girard, H. Kress-Gazit, and G. J. Pappas, “Temporal
logic motion planning for dynamic robots,” Automatica J. IFAC,
vol. 45, no. 2, pp. 343–352, 2009.
[18] IBM, User’s Manual for CPLEX, 2010.
[19] H. Ding, G. Reißig, K. Wijaya, D. Bortot, K. Bengler, and O. Sturs-
berg, “Human arm motion modeling and long-term prediction for safe
and efficient human-robot-interaction,” in IEEE Int. Conf. Robot. and
Autom., 2011, pp. 5875–5880.
[20] H. Ding, K. Wijaya, G. Reißig, and O. Stursberg, “Optimizing motion
of robotic manipulators in interaction with human operators,” in Int.
Conf. on Intell. Robot. and Appl., ser. Lecture Notes in Computer
Science (LNCS), S. Jeschke, Ed. Springer, 2011.
[21] G. Reißig, “Computing abstractions of nonlinear systems,” IEEE
Trans. Automat. Control, vol. 56, 2011, accepted, avail. via
http://www.reiszig.de/gunther/pubs/i11abs.html.