scispace - formally typeset
Search or ask a question
Journal ArticleDOI

The Open Motion Planning Library

10 Dec 2012-IEEE Robotics & Automation Magazine (IEEE)-Vol. 19, Iss: 4, pp 72-82
TL;DR: The open motion planning library is a new library for sampling-based motion planning, which contains implementations of many state-of-the-art planning algorithms, and it can be conveniently interfaced with other software components.
Abstract: The open motion planning library (OMPL) is a new library for sampling-based motion planning, which contains implementations of many state-of-the-art planning algorithms. The library is designed in a way that it allows the user to easily solve a variety of complex motion planning problems with minimal input. OMPL facilitates the addition of new motion planning algorithms, and it can be conveniently interfaced with other software components. A simple graphical user interface (GUI) built on top of the library, a number of tutorials, demos, and programming assignments are designed to teach students about sampling-based motion planning. The library is also available for use through Robot Operating System (ROS).

Content maybe subject to copyright    Report

1
The Open Motion Planning Library
Ioan A. S¸ucan, Member, IEEE, Mark Moll, Member, IEEE, and Lydia E. Kavraki, Senior Member, IEEE
Abstract—We describe the Open Motion Planning Library
(OMPL), a new library for sampling-based motion planning,
which contains implementations of many state-of-the-art plan-
ning algorithms. The library is designed in a way that allows
the user to easily solve a variety of complex motion planning
problems with minimal input. OMPL facilitates the addition
of new motion planning algorithms and it can be conveniently
interfaced with other software components. A simple graphical
user interface (GUI) built on top of the library, a number
of tutorials, demos and programming assignments have been
designed to teach students about sampling-based motion plan-
ning. Finally, the library is also available for use through the
Robot Operating System (ROS).
Index Terms—motion planning, sampling-based planning,
robotics software, OMPL, ROS, open source robotics, teaching
robotics
I. INTRODUCTION
R
OBOTIC devices are steadily becoming a significant
part of our daily lives. Search and rescue robots, service
robots, surgical robots and autonomous cars are examples of
robots most of us are familiar with. Being able to find paths
(motion plans) efficiently for such robots is critical for a
number of real-world applications (Figure 1). For example,
in urban search-and-rescue settings a small robot may need
to find paths through rubble and semi-collapsed buildings
to locate survivors. In domestic settings it would be useful
if a robot could, e.g., put away kids’ toys, fold the laundry,
and load the dishwasher. Motion planning also plays an
increasingly important role in robot-assisted surgery. For
example, before a flexible needle is inserted or an incision is
made, a path can be computed that minimizes the chance of
hurting vital organs. More generally, motion planning is the
problem of finding a continuous path that connects a given
start state of a robotic system to a given goal region for that
system, such that the path satisfies a set of constraints (e.g.,
collision avoidance, bounded forces, bounded acceleration).
This paper describes an open source software library for
motion planning, designed for research, educational and
industrial applications.
Although most of the work done towards the development
of algorithms that solve the motion planning problem comes
from robotics and artificial intelligence [1]–[3], the problem
can be viewed more abstractly as search in continuous spaces.
As such, the applications of motion planning extend beyond
robotics to fields such as computational biology [4]–[7] and
computer-aided verification [8], among others.
I.
S¸
ucan is with Willow Garage, Menlo Park, CA 94025. M. Moll and
L. Kavraki are with the Department of Computer Science at Rice University,
Houston, TX 77005, USA. Email:
{
isucan,mmoll,kavraki
}
@rice.edu. This
work was performed when I.
S¸
ucan was with the Department of Computer
Science, Rice University.
Manuscript received xxxxxx; revised xxxxxx.
Early results have shown the motion planning problem to
be PSPACE-complete [9], and existing complete algorithms
are difficult to implement and computationally intractable.
For this reason, more recent efforts focus on approaches with
weaker completeness guarantees. One of these approaches
is that of sampling-based motion planning, which has been
used successfully to solve difficult planning problems for
robots of practical interest. Many sampling-based algorithms
are probabilistically complete: a solution will eventually be
found with probability 1 if one exists, but the non-existence
of a solution cannot be reported (see, e.g., [10]–[13]).
Many of the core concepts in sampling-based motion
planning are relatively easy to explain, but implementing
sampling-based motion planning algorithms in a generic
way is non-trivial. This paper describes the Open Motion
Planning Library (OMPL, http://ompl.kavrakilab.org), an
open source C++ implementation of many sampling-based
algorithms (such as the Probabilistic Roadmap Method
(PRM) [14], Rapidly-expanding Random Trees (RRT) [15],
Kinodynamic Planning by Interior-Exterior Cell Exploration
(KPIECE) [16] and many more) and the core low-level data
structures that are commonly used. OMPL includes Python
bindings that expose almost all functionality to Python users.
This library is aimed at three different audiences:
motion planning researchers,
robotics educators, and
end users in the robotics industry.
Below, we will characterize the needs of these different
audiences.
Within the robotics community, it is often challenging
to demonstrate that a new motion planning algorithm is
an improvement over existing methods according to some
metric. First, it is a substantial amount of work for a
researcher to implement not only the new algorithm, but also
one or more state-of-the-art motion planning algorithms to
compare against. Ideally, implementations of low-level data
structures and subroutines used by these algorithms (e.g.,
proximity data structures) are shared, so that only differences
of the high-level algorithm are measured. Second, for an
accurate comparison, one needs a known set of benchmark
problems. Finally, collecting various performance metrics for
several planners with different parameter settings, running
on several benchmark problems and storing them in a way
that facilitates easy analysis afterwards is a non-trivial task.
We as developers of planning algorithms have run into the
issues above many times. We designed OMPL to help with
all these issues, and make it easier to try out new ideas.
Moreover, the library is designed in a way that facilitates
contributions from other motion planning researchers and
provides benchmarking capabilities to easily compare new
To appear in: IEEE Robotics & Automation Magazine, December 2012.

2
(a) (b) (c)
Fig. 1. Real world applications of motion planning. (a) An urban search-and-rescue robot from Carnegie Mellon University’s Biorobotics Lab. (b)
The HERB robot from Carnegie Mellon University’s Personal Robotics Lab picking up a bottle. (c) A PR2 robot folding laundry in UC Berkeley’s
Robotics Learning Lab. Images used with permission from Prof. Choset, Prof. Srinivasa, and Prof. Abbeel, respectively.
planners against all other planners implemented in OMPL
(see Box 1). We have developed a streamlined process
that gives contributing researchers appropriate credit and
minimizes the burden of writing code that satisfies our
library’s application programmers interface (API). At the
same time, our aim is to make such contributions easily
available to users of OMPL. This is achieved by releasing
the code under the Berkeley Software Distribution (BSD)
license (one of the least restrictive Open Source licenses),
releasing frequent updates, and making the code available
through a public repository. To foster a community of OMPL
users and developers we have set up a mailing list, blog,
and a Facebook page.
For robotics educators, we have designed a series of
exercises/projects around OMPL aimed at undergraduate
students. These exercises help students realize what the
complexity of motion planning means in practice, develop
an understanding of how sampling-based motion planning
algorithms work, and learn to evaluate the performance of
planners. We have also designed open-ended projects for
undergraduate and graduate students. OMPL is structured to
have a clear mapping between the motion planning concepts
used in the literature and the classes that are defined in
the implementation. The separation between abstract base
classes that only specify the interface and derived classes
that implement the specified functionality also helps students
understand general concepts in motion planning before
focusing on details.
From the beginning, OMPL was intended to be useful in
practical applications. This requires that planning algorithms
can solve motion planning problems for systems with many
degrees of freedom at interactive speeds. An additional
requirement is the ability to cleanly integrate OMPL with
other software components on a robot, such as perception,
kinematics, control, etc. Through a collaboration with Willow
Garage, OMPL is integrated within ROS [17] and serves as
the motion planning back-end for the arm planning software
stack. The availability of OMPL in ROS makes it easy for
end users in the robotics industry to stay up-to-date with
advances in sampling-based motion planning.
The rest of the paper is organized as follows. Section II
gives some background on sampling-based motion plan-
ning and existing software packages for motion planning.
Sections III and IV include an overview and lower level
details about OMPL. Integration with other software systems
is described in Section V, and finally, a discussion is in
Section VI.
II. BACKGROUND
There has been much work done towards both algorithm
development and software development for motion planning.
This paper only discusses aspects pertaining to sampling-
based motion planning.
A. Sampling-based Motion Planning: Definitions
Sampling-based motion planning algorithms relaxed com-
pleteness guarantees and demonstrated that many interesting
problems can be solved efficiently in practice, despite the
the theoretically high complexity of the problem [2], [3].
The fundamental idea of sampling-based motion planning
is to approximate the connectivity of the search space with
a graph structure. The search space is sampled in a variety
of ways, and selected samples end up as the vertices of
the approximating graph. Edges in the approximating graph
denote valid path segments.
There are two key considerations in the construction of
the graph approximation: the probability distribution used
for sampling states and the strategy for generating edges. An
enormous amount of research has been performed towards
the development of efficient algorithms that account for these
issues [18].
We will not go into the details of various sampling-
based motion planning algorithms, as such details can be
found elsewhere [2], [3]. Instead, we describe the common
components sampling-based algorithms typically depend on,
as these relate to the implementations of such algorithms:
State space
Points in the state space (or configuration
space) fully describe the state of the system being
planned for. For a free-flying rigid body, the state space
consists of all translations and rotations, while for a

3
Box 1: Benchmarking with OMPL
A seemingly simple but often ignored part of motion planning
software is benchmarking planning code. OMPL includes
benchmarking capabilities (through a class called Bench-
mark) that can be simply dropped in and applied to existing
planning contexts. In very simple terms, a Benchmark
object runs a number of planners multiple times on a
user specified planning context. Although simple, this code
automatically keeps track of all the used settings and takes
all the possible measurements during planning (currently,
tens of parameters are recorded for every single motion
plan). The recorded information is logged and can be post-
processed using a Python script included with OMPL. The
script can produce MySQL databases with all experiment
data so that the user can write their own queries later
on, but it can also automatically generate plots for all
of the performance metrics. For real- and integer-valued
measurements it generates box plots: plots that include
information about the median, confidence intervals and
outliers. An example is shown in the figure on the right.
For binary-valued measurements it generates bar plots.
A more elaborate example of what can be done with the
Benchmark class can be found at http://plannerarena.org,
a web site currently being developed to establish standard
benchmark problems and report performance metrics for
various planners on those problems.
(sec.)
Figure S1.
A sample box plot generated by OMPLs bench-
mark script.
manipulator with
n
rotational joints the state space can
be modeled by an n-dimensional torus.
Control space
A control space represents a
parametrization of the space of controls. This is only
required for systems with dynamics. For most systems
of practical interest, one can think of the control space
for a system with
m
controls simply as a subset of
R
m
.
For geometric planning no controls are used.
Sampler
A sampler is needed to generate different
states from the state space. For control-based systems,
a separate sampler is needed for sampling different
controls. Some planning algorithms (e.g., [12], [16])
only require a control sampler and do not need a state
sampler.
State validity checker
A state validity checker is a
routine that distinguishes the valid part of the state space
from the invalid part of the state space. For example,
a state validity checker can check for collisions and
whether velocities and accelerations are within certain
bounds.
Local planner
When planning with controls, the local
planner is a means of computing the evolution of the
robotic system forward (and sometimes backward) in
time. When planning solely under geometric constraints,
the local planner often performs interpolation between
states in the state space.
B. Software Packages for Motion Planning
Several other packages for motion planning are available.
Some, such as the Motion Strategies Library (MSL, http:
//msl.cs.uiuc.edu), the Motion Planning Kit (MPK, http://
robotics.stanford.edu/
mitul/mpk), and VIZMO++ [19] are
no longer maintained. KineoWorks (http://www.kineocam.
com) provides commercial motion planning software for
academic research and industrial applications. In 2007, our
group released the Object-Oriented Programming System
for Motion Planning (OOPSMP) [20], which is no longer
maintained.
Another software package that is complementary to
OMPL is OpenRAVE [21]. OpenRAVE is open source,
actively developed, and it is widely used. It is important
to understand the difference in design philosophy behind
OMPL and OpenRAVE. OpenRAVE is designed to be a
complete package for robotics. It includes, among other
things: geometry representation, collision checking, grasp
planning, forward and inverse kinematics for several robots,
controllers, motion planning algorithms, simulated sensors,
visualization tools, etc. OMPL, on the other hand, was
designed to focus completely on sampling-based motion
planning with a clear mapping between theoretical concepts
in the literature and abstract classes in the implementation.
This high level of abstraction makes it easy to integrate
OMPL with a variety of front-ends and other libraries. Some
integration examples are described in Section V. To some
extent, the integration with ROS [17] gives a user many of
OpenRAVE’s features that are purposefully not included in
OMPL. It may also be possible to use OMPL as a motion
planning plugin in OpenRAVE. As a result of the narrower
focus in OMPL, we have been able to spend more resources
on implementing a much broader variety of sampling-based
algorithms than what is currently available in OpenRAVE,
as well as benchmarking capabilities to facilitate a thorough
comparison of existing and future sampling-based motion
planners.

4
ControlSampler
StateSpace
Represents the state space in
which planning is performed;
implements topology-specific
functions: distance, interpola-
tion, state (de)allocation.
StateSampler
Implements uniform and
Gaussian sampling of states
for a specific StateSpace
ProjectionEvaluator
Computes projections from
states of a specific State-
Space to a low-dimensional
Euclidean space.
SpaceInformation
Provides routines typically used
by motion planners; combines
the functionality of classes it
depends on.
StateValidityChecker
Decides whether a given state
from a specific StateSpace
is valid.
MotionValidator
Provides the ability to check
the validity of path segments
using the interpolation
provided by the StateSpace.
ValidStateSampler
Provides the ability to sample
valid states.
Planner
Solves a motion
planning problem.
Goal
Representation
of a goal.
ProblemDefinition
Specifies the instance of the
planning problem; requires
definition of start states and a
goal.
SimpleSetup
Provides a simple way
of setting up all needed
classes without limiting
functionality.
Path
Representation of a path;
used to represent a solution
to a planning problem.
User code
only when planning with differential constraints
User must instantiate this class.
User must instantiate this class unless SimpleSetup is used.
User can instantiate this class, but defaults are provided.
A is owned by B.
A B
ControlSpace
StatePropagator
Represents the control
space the planner uses to
represent inputs to the
system being planned for.
Implements sampling of controls
for a specific ControlSpace.
Returns the state obtained
by applying a control to
some arbitrary initial state.
DirectedControlSampler
Sample controls that take the
system towards a desired state.
Fig. 2. Overview of OMPL structure. Class names correspond to well understood concepts in sampling-based motion planning. More detailed
documentation is available at http://ompl.kavrakilab.org.
C. Relationship to Other Robotics Software
There have also been many efforts to create robot
simulators such as Player/Stage [22], Player/Gazebo [23],
Webots [24], and MORSE [25]. Microsoft Robotics Devel-
oper Studio [26] also contains a robot simulator. Typically,
such simulators do not include motion planning algorithms,
but they can provide a controlled simulated environment to
test motion planners in various environments, on various
robots with different sensing and communication capabilities.
They often simulate the dynamics of the world (including
the robots themselves) using physics engines such as Bullet
(http://bulletphysics.org) and the Open Dynamics Engine
(http://ode.org), among others.
Hardware platforms typically require complex software
configurations and use various forms of middleware to
accommodate this requirement (e.g., ROS [17], Orocos
(http://www.orocos.org), OpenRTM-aist [27], OPRoS [28],
Yarp [29]). Such software systems typically include their
own visualization system, collision checking, etc. OMPL fits
naturally and easily into such systems as it only provides
sampling-based motion planning and its abstract interface
should be able to accommodate a variety of low-level
implementations.
III. CONCEPTUAL OVERVIEW OF OMPL
OMPL is intended for use in research and education, as
well as in industry. For this reason, the main design criteria
for OMPL were:
a) Clarity of concepts: OMPL was designed to consist
of a set of components as indicated in Figure 2, such that
each component corresponds to known concepts in sampling-
based motion planning.
b) Efficiency: OMPL has been implemented entirely
in C++ and is thread-safe.
c) Simple integration with other software packages:
To facilitate the integration with other software libraries,
OMPL offers abstract interfaces that can be implemented by
the “host” software package. Furthermore, the dependencies
of OMPL are minimal: only the Boost C++ libraries are
required. Optionally, OMPL can be compiled with Python
bindings, which facilitates integration with Python modules.
d) Straightforward integration of external contributions:
We strive for minimalist API constraints for planning
algorithms, so that new contributions can be easily integrated.
As opposed to all other existing motion planning soft-
ware libraries, OMPL does not include a representation
of workspaces or of robots; as a result, it also does not
include a collision checker or any means of visualization.

5
OMPL is reduced to only motion planning algorithms. The
advantage of this minimalist approach is that it allows us
to design a library that can be used for generic search
in high-dimensional continuous spaces subject to complex
constraints. Instead of defining valid states as collision-free,
which would require a specific geometric representation
of the environment and robot as well as support for a
specific collision checker, OMPL leaves the definition of
state validity completely up to the user (or the software
package in which OMPL is integrated; see Section
II-C
).
This gives the user enormous design freedom: the user can
defer collision checking to a physics engine, write a state
sampler that constructs only valid states, or define state
validity in completely arbitrary ways that may or may not
depend on geometry.
To make OMPL as easy to use as possible, various param-
eters needed for tuning sampling-based motion planners are
automatically computed. The user has the option to override
defaults, but that is not a requirement.
IV. IMPLEMENTATION OF CORE CONCEPTS
Below we will give an overview of the implementation
of the core motion planning concepts in OMPL. Figure 2
gives a high-level overview of the main classes and their
relationships. We will use the following notation. Classes
are written in a sans-serif font (e.g., StateSpace), while
methods and functions are written in a monospaced font
(e.g.,
isSatisfied()
). For conciseness, the arguments to
methods and functions are omitted.
A. States, Controls, and Spaces
To maximize the range of application for the included
planning algorithms, OMPL represents the search spaces, i.e.,
the state spaces (StateSpace), in a generic way. State spaces
include operations on states such as distance evaluation, test
for equality, interpolation, as well as memory management
for states: (de)allocation and copying. Additionally, each state
space has its own storage format for states, which is not
exposed outside the implementation of the state space itself.
To operate on states, the planning algorithms implemented in
OMPL rely only on the generic functionality offered by state
spaces. This approach enables planning algorithms in OMPL
to be applicable to any state spaces that may be defined, as
long as the expected generic functionality is provided.
Furthermore, OMPL includes a means of combining state
spaces using the class CompoundStateSpace. A combined
state space implements the functionality of a regular state
space on top of the corresponding functionality from the
maintained set of state spaces. This allows trivial construction
of more complex state spaces from simpler ones. For example
SE3StateSpace (the space of rigid body transformations
in 3D) is just a combination of SO3StateSpace (the
space of rotations) and RealVectorStateSpace (the space
of translations). Instances of CompoundStateSpace can be
constructed at run time, which is necessary for constructing
a state space from an input file specification, as is done,
for example, in ROS. For a mobile manipulator one could
construct a CompoundStateSpace with the two arms and
the mobile base as sub-state spaces. An arm typically has a
number of rotational joints and can be modeled by either
a RealVectorStateSpace (if the joints have limits) or a
CompoundStateSpace with copies of SO(2). The state space
for the base can simply be SE(2) (the space rigid body
transformations in the plane).
State spaces optionally include specifications of pro-
jections to Euclidean spaces (ProjectionEvaluator). Low-
dimensional Euclidean projections are used by several
sampling-based planning algorithms (e.g., KPIECE [16],
SBL [30], EST [12]) to guide their search for a feasible
path, as it is much easier to keep track of coverage (i.e.,
which areas have been sufficiently explored and which areas
should be explored further) in such low-dimensional spaces.
In addition to states and state spaces, some algorithms
in OMPL require a means to represent controls. Control
spaces (ControlSpace) mirror the structure of state spaces
and provide functionality specific to controls, so that planning
algorithms can be implemented in a generic way. The only
available implementations of control spaces are the Euclidean
space and a space for discrete modes, because so far there
has not been a need for control spaces with more complex
topologies. However, the API allows one to define such
control spaces.
B. State Validation and Propagation
Whether a state is valid or not depends on the planning
context. In many cases state validity simply means that a
robot is not in collision with any obstacles, but in general
any condition on a state can be used. In OMPL.app (see
section
V-A
) we have predefined a state validity checker for
rigid body motion planning. We have also implemented
a state validity checker that uses the Open Dynamics
Engine (see Box 2). If these built-in state validity checkers
cannot be used for the system of interest, a user needs to
implement their own. Based on a given state validity checker,
a default MotionValidator is constructed that checks whether
the interpolation between two states at a certain resolution
produces states that are all valid. However, it possible to plug
in a different MotionValidator. For example, one might want
to add support for continuous collision checking, which can
adaptively check for collisions and provide exact guarantees
for state validity [31].
For planning with controls a user needs to specify how
the system evolves when certain controls are applied for
some period of time starting from a given state. This is
called state propagation in OMPL. In the simplest case, a
state propagator is essentially a lightweight wrapper around
a numerical integrator for systems of the form
˙q = f (q, u)
,
where
q
is a state vector and
u
a vector of controls. To
facilitate planning for such systems, we have implemented
generic support for ODE solvers and we have integrated
Boost.Odeint [32], a new library for solving ODEs. Given a
user-provided function that implements
f (q, u)
for the system
of interest, OMPL can plan for such systems. Alternatively,
one can use variational integrators [33], or a physics engine
to perform state propagation.

Citations
More filters
Journal ArticleDOI
TL;DR: A sequential convex optimization procedure, which penalizes collisions with a hinge loss and increases the penalty coefficients in an outer loop as necessary, and an efficient formulation of the no-collisions constraint that directly considers continuous-time safety are presented.
Abstract: We present a new optimization-based approach for robotic motion planning among obstacles. Like CHOMP (Covariant Hamiltonian Optimization for Motion Planning), our algorithm can be used to find collision-free trajectories from naA¯ve, straight-line initializations that might be in collision. At the core of our approach are (a) a sequential convex optimization procedure, which penalizes collisions with a hinge loss and increases the penalty coefficients in an outer loop as necessary, and (b) an efficient formulation of the no-collisions constraint that directly considers continuous-time safety Our algorithm is implemented in a software package called TrajOpt. We report results from a series of experiments comparing TrajOpt with CHOMP and randomized planners from OMPL, with regard to planning time and path quality. We consider motion planning for 7 DOF robot arms, 18 DOF full-body robots, statically stable walking motion for the 34 DOF Atlas humanoid robot, and physical experiments with the 18 DOF PR2. We also apply TrajOpt to plan curvature-constrained steerable needle trajectories in the SE(3) configuration space and multiple non-intersecting curved channels within 3D-printed implants for intracavitary brachytherapy. Details, videos, and source code are freely available at: http://rll.berkeley.edu/trajopt/ijrr.

655 citations


Cites methods from "The Open Motion Planning Library"

  • ...We performed a quantitative comparison between TrajOpt and several implementations of motion planning algorithms, including sampling based planners from OMPL [47], as well as a recent implementation of CHOMP [61]....

    [...]

  • ...We compared TrajOpt to open-source implementations of bi-directional RRT [23] and a variant of KPIECE [46] from OMPL/MoveIt!...

    [...]

  • ...We report results from a series of experiments comparing TrajOpt with CHOMP and randomized planners from OMPL, with regard to planning time and path quality....

    [...]

  • ...We benchmarked TrajOpt against sampling-based planners from OMPL and CHOMP....

    [...]

Proceedings ArticleDOI
27 Jul 2015
TL;DR: The Yale-CMU-Berkeley (YCB) Object and Model set is intended to be used for benchmarking in robotic grasping and manipulation research, and provides high-resolution RGBD scans, physical properties and geometric models of the objects for easy incorporation into manipulation and planning software platforms.
Abstract: In this paper we present the Yale-CMU-Berkeley (YCB) Object and Model set, intended to be used for benchmarking in robotic grasping and manipulation research. The objects in the set are designed to cover various aspects of the manipulation problem; it includes objects of daily life with different shapes, sizes, textures, weight and rigidity, as well as some widely used manipulation tests. The associated database provides high-resolution RGBD scans, physical properties and geometric models of the objects for easy incorporation into manipulation and planning software platforms. A comprehensive literature survey on existing benchmarks and object datasets is also presented and their scope and limitations are discussed. The set will be freely distributed to research groups worldwide at a series of tutorials at robotics conferences, and will be otherwise available at a reasonable purchase cost.

619 citations


Cites methods from "The Open Motion Planning Library"

  • ...Inside OpenRAVE, the HERB robot uses CBiRRT, the OMPL [34] library and CHOMP to plan and optimize motion trajectories....

    [...]

Journal ArticleDOI
TL;DR: The state of the art in motion planning is surveyed and selected planners that tackle current issues in robotics are addressed, for instance, real-life kinodynamic planning, optimal planning, replanning in dynamic environments, and planning under uncertainty are discussed.
Abstract: Motion planning is a fundamental research area in robotics. Sampling-based methods offer an efficient solution for what is otherwise a rather challenging dilemma of path planning. Consequently, these methods have been extended further away from basic robot planning into further difficult scenarios and diverse applications. A comprehensive survey of the growing body of work in sampling-based planning is given here. Simulations are executed to evaluate some of the proposed planners and highlight some of the implementation details that are often left unspecified. An emphasis is placed on contemporary research directions in this field. We address planners that tackle current issues in robotics. For instance, real-life kinodynamic planning, optimal planning, replanning in dynamic environments, and planning under uncertainty are discussed. The aim of this paper is to survey the state of the art in motion planning and to assess selected planners, examine implementation details and above all shed a light on the current challenges in motion planning and the promising approaches that will potentially overcome those problems.

602 citations


Cites methods from "The Open Motion Planning Library"

  • ...An open-source library has been developed as a common benchmarking tool that limits the effect of implementation parameters [82]....

    [...]

  • ...Recommendation for planners implementation are proposed [81] and a benchmarking software is presented [82] but they do not survey recent research in the area and present only a handful of planners....

    [...]

Proceedings ArticleDOI
23 Jun 2013
TL;DR: A novel approach for incorporating collision avoidance into trajectory optimization as a method of solving robotic motion planning problems, solving a suite of 7-degree-of-freedom arm-planning problems and 18-DOF full-body planning problems and benchmarked the algorithm against several other motion planning algorithms.
Abstract: We present a novel approach for incorporating collision avoidance into trajectory optimization as a method of solving robotic motion planning problems. At the core of our approach are (i) A sequential convex optimization procedure, which penalizes collisions with a hinge loss and increases the penalty coefficients in an outer loop as necessary. (ii) An efficient formulation of the no-collisions constraint that directly considers continuous-time safety and enables the algorithm to reliably solve motion planning problems, including problems involving thin and complex obstacles. We benchmarked our algorithm against several other motion planning algorithms, solving a suite of 7-degree-of-freedom (DOF) arm-planning problems and 18-DOF full-body planning problems. We compared against sampling-based planners from OMPL, and we also compared to CHOMP, a leading approach for trajectory optimization. Our algorithm was faster than the alternatives, solved more problems, and yielded higher quality paths. Experimental evaluation on the following additional problem types also confirmed the speed and effectiveness of our approach: (i) Planning foot placements with 34 degrees of freedom (28 joints + 6 DOF pose) of the Atlas humanoid robot as it maintains static stability and has to negotiate environmental constraints. (ii) Industrial box picking. (iii) Real-world motion planning for the PR2 that requires considering all degrees of freedom at the same time.

471 citations


Cites methods from "The Open Motion Planning Library"

  • ...We performed a quantitative comparison between our algorithm and several open-source implementations of motion planning algorithms, including sampling based planners from OMPL [26], as well as a recent implementation of CHOMP....

    [...]

Journal ArticleDOI
TL;DR: The Yale-Carnegie Mellon University-Berkeley object and model set is presented, intended to be used to facilitate benchmarking in robotic manipulation research and to enable the community of manipulation researchers to more easily compare approaches and continually evolve standardized benchmarking tests and metrics as the field matures.
Abstract: In this article, we present the Yale-Carnegie Mellon University (CMU)-Berkeley (YCB) object and model set, intended to be used to facilitate benchmarking in robotic manipulation research. The objects in the set are designed to cover a wide range of aspects of the manipulation problem. The set includes objects of daily life with different shapes, sizes, textures, weights, and rigidities as well as some widely used manipulation tests. The associated database provides high-resolution red, green, blue, plus depth (RGB-D) scans, physical properties, and geometric models of the objects for easy incorporation into manipulation and planning software platforms. In addition to describing the objects and models in the set along with how they were chosen and derived, we provide a framework and a number of example task protocols, laying out how the set can be used to quantitatively evaluate a range of manipulation approaches, including planning, learning, mechanical design, control, and many others. A comprehensive literature survey on the existing benchmarks and object data sets is also presented, and their scope and limitations are discussed. The YCB set will be freely distributed to research groups worldwide at a series of tutorials at robotics conferences. Subsequent sets will be, otherwise, available to purchase at a reasonable cost. It is our hope that the ready availability of this set along with the ground laid in terms of protocol templates will enable the community of manipulation researchers to more easily compare approaches as well as continually evolve standardized benchmarking tests and metrics as the field matures.

462 citations

References
More filters
Proceedings Article
01 Jan 2009
TL;DR: This paper discusses how ROS relates to existing robot software frameworks, and briefly overview some of the available application software which uses ROS.
Abstract: This paper gives an overview of ROS, an opensource robot operating system. ROS is not an operating system in the traditional sense of process management and scheduling; rather, it provides a structured communications layer above the host operating systems of a heterogenous compute cluster. In this paper, we discuss how ROS relates to existing robot software frameworks, and briefly overview some of the available application software which uses ROS.

8,387 citations


"The Open Motion Planning Library" refers background in this paper

  • ...Section II gives some background on sampling-based motion planning and existing software packages for motion planning....

    [...]

MonographDOI
01 Jan 2006
TL;DR: This coherent and comprehensive book unifies material from several sources, including robotics, control theory, artificial intelligence, and algorithms, into planning under differential constraints that arise when automating the motions of virtually any mechanical system.
Abstract: Planning algorithms are impacting technical disciplines and industries around the world, including robotics, computer-aided design, manufacturing, computer graphics, aerospace applications, drug design, and protein folding. This coherent and comprehensive book unifies material from several sources, including robotics, control theory, artificial intelligence, and algorithms. The treatment is centered on robot motion planning but integrates material on planning in discrete spaces. A major part of the book is devoted to planning under uncertainty, including decision theory, Markov decision processes, and information spaces, which are the “configuration spaces” of all sensor-based planning problems. The last part of the book delves into planning under differential constraints that arise when automating the motions of virtually any mechanical system. Developed from courses taught by the author, the book is intended for students, engineers, and researchers in robotics, artificial intelligence, and control theory as well as computer graphics, algorithms, and computational biology.

6,340 citations


"The Open Motion Planning Library" refers background or methods in this paper

  • ...Integration with other software systems is described in Section V, and finally, a discussion is in Section VI....

    [...]

  • ...Although most of the work done towards the development of algorithms that solve the motion planning problem comes from robotics and artificial intelligence [1]–[3], the problem can be viewed more abstractly as search in continuous spaces....

    [...]

Book
01 Jan 1990
TL;DR: This chapter discusses the configuration space of a Rigid Object, the challenges of dealing with uncertainty, and potential field methods for solving these problems.
Abstract: 1 Introduction and Overview.- 2 Configuration Space of a Rigid Object.- 3 Obstacles in Configuration Space.- 4 Roadmap Methods.- 5 Exact Cell Decomposition.- 6 Approximate Cell Decomposition.- 7 Potential Field Methods.- 8 Multiple Moving Objects.- 9 Kinematic Constraints.- 10 Dealing with Uncertainty.- 11 Movable Objects.- Prospects.- Appendix A Basic Mathematics.- Appendix B Computational Complexity.- Appendix C Graph Searching.- Appendix D Sweep-Line Algorithm.- References.

6,186 citations

Journal ArticleDOI
01 Aug 1996
TL;DR: Experimental results show that path planning can be done in a fraction of a second on a contemporary workstation (/spl ap/150 MIPS), after learning for relatively short periods of time (a few dozen seconds).
Abstract: A new motion planning method for robots in static workspaces is presented. This method proceeds in two phases: a learning phase and a query phase. In the learning phase, a probabilistic roadmap is constructed and stored as a graph whose nodes correspond to collision-free configurations and whose edges correspond to feasible paths between these configurations. These paths are computed using a simple and fast local planner. In the query phase, any given start and goal configurations of the robot are connected to two nodes of the roadmap; the roadmap is then searched for a path joining these two nodes. The method is general and easy to implement. It can be applied to virtually any type of holonomic robot. It requires selecting certain parameters (e.g., the duration of the learning phase) whose values depend on the scene, that is the robot and its workspace. But these values turn out to be relatively easy to choose, Increased efficiency can also be achieved by tailoring some components of the method (e.g., the local planner) to the considered robots. In this paper the method is applied to planar articulated robots with many degrees of freedom. Experimental results show that path planning can be done in a fraction of a second on a contemporary workstation (/spl ap/150 MIPS), after learning for relatively short periods of time (a few dozen seconds).

4,977 citations

Book
01 Jan 2006

4,417 citations