OpenRAVE bindings for the
OMPL suite of motion planning algorithms. This
package provides an OMPL plugin that implements the OpenRAVE::PlannerBase
interface and delegates planning requests to an OMPL planner. It also includes
the "OMPLSimplifier" plugin that exposes OMPL's PathSimplifier
to OpenRAVE
through the same interface. See this demo video
for a brief overview of or_ompl's features.
This is implemented by initializing OMPL with a state space that matches the
joint limits and resolutions of the robot's active DOFs. Collision checking
is implemented by providing OMPL with a custom "state validity checker"
that uses OpenRAVE's CheckCollision
and CheckSelfCollision
calls to check
for collision with the environment.
or_ompl wraps each OMPL geometric planner as an OpenRAVE planner that
implements the PlannerBase
interface. E.g. OMPL's RRTConnect algorithm is
exposed through a OMPL_RRTConnect
planner in OpenRAVE. The planning time
limit and any planner parameters that are exposed through OMPL's ParamSet
class can be set by name in the PlannerParameters
struct in OpenRAVE.
The wrapper classes necessary to call a planner are automatically generated
from the planners.yaml
configuration file by the Python script
scripts/wrap_planners.py
. If you find that a planner is missing, please open
an issue or send a
send us a pull request
with an updated 'planners.yaml' file. The presence or absence of each planner
is determined by testing whether the corresponding header file exists in the
OMPL include directory.
See the package.xml
file for a full list of dependencies. These are the major
dependencies:
- OpenRAVE 0.8 or above (primarily developed in 0.9)
- OMPL 0.10 or above (primarily developed in 0.10 and 0.13)
- ROS optional, see below
The CMakeLists.txt
file in the root of this repository supports Catkin and
standalone CMake builds. See the appropriate section below for installation
instructions specific to your environment.
This preferred way of building or_ompl. In this case, you should have OpenRAVE and OMPL installed as system dependencies. We use a helper package called openrave_catkin to manage the build process.
Once the dependencies are satisfied, you can simply clone this repository into
your Catkin workspace and run catkin_make
:
$ . /my/workspace/devel/setup.bash
$ cd /my/workspace/src
$ git clone https://github.com/personalrobotics/openrave_catkin.git
$ git clone https://github.com/personalrobotics/or_ompl.git
$ cd ..
$ catkin_make
This will build the OpenRAVE plugins into the share/openrave-0.9/plugins
directory in your devel space. If you run catkin_make install
the plugin will
be installed to the same directory in your install space. In both cases, the
corresponding directory will be automatically added to your OPENRAVE_PLUGINS
path using a Catkin environment
hook.
See the documentation for
openrave_catkin
for more information.
You can build or_ompl entirely ROS-agnostic by setting the NO_ROS
variable:
$ git clone https://github.com/personalrobotics/or_ompl.git
$ mkdir build
$ cd build
$ cmake -DNO_ROS:bool=1 ..
$ make
Just as in the rosbuild case, this will build the plugin in the lib/
directory. You will need to add this directory to your OPENRAVE_PLUGINS
path
so that OpenRAVE can find it.
Wherever possible we aim to fully support the full breadth of features in both OMPL and OpenRAVE. However, you should be aware of a few limitations:
- per-joint weights are not supported (unit weights are assumed)
- per-joint resolutions are not supported (a conservative resolution is selected)
- kineodynamic planning is not supported
- planning with affine DOFs is not implemented
- simplifier does not work with the
SmoothTrajectory
helper function - no support for multi-query planning (e.g. PRM)
None of these are fundamental issues and we hope, perhaps with your help, to shrink this list over time. We would welcome pull requests for any of these features.
You can find planners provided by this plugin by looking for planners that
start with the OMPL_
prefix in the output of openrave --listplugins
.
The following Python code will plan using OMPL's implementation of RRT-Connect,
then shortcut the trajectory using OMPL's path simplifier. We assume that the
variable robot
is an OpenRAVE robot that is configured with an appropriate
set of active DOFs:
from openravepy import *
env = ... # your environment
robot = ... # your robot
planner = RaveCreatePlanner(env, 'OMPL_RRTConnect')
simplifier = RaveCreatePlanner(env, 'OMPL_Simplifier')
# Setup the planning instance.
params = Planner.PlannerParameters()
params.SetRobotActiveJoints(robot)
params.SetGoalConfig(goal)
# Set the timeout and planner-specific parameters. You can view a list of
# supported parameters by calling: planner.SendCommand('GetParameters')
params.SetExtraParameters('<range>0.02</range>')
planner.InitPlan(robot, params)
# Invoke the planner.
traj = RaveCreateTrajectory(env, '')
result = planner.PlanPath(traj)
assert result == PlannerStatus.HasSolution
# Shortcut the path.
simplifier.InitPlan(robot, Planner.PlannerParameters())
result = simplifier.PlanPath(traj)
assert result == PlannerStatus.HasSolution
# Time the trajectory.
result = planningutils.RetimeTrajectory(traj)
assert result == PlannerStatus.HasSolution
# Execute the trajectory.
robot.GetController().SetPath(traj)
A working version of this script is included in scripts/example.py
. See the
documentation on the OpenRAVE website
for more information about how to invoke an OpenRAVE planner.
Collision checking is often the bottleneck for motion planning for manipulators
with the sample-based motion planners included in OMPL. You should consider
using a fast collision checker plugin, like
or_fcl, to achieve best
performance with or_ompl
.
Additionally, you should consider setting the ActiveDOFs
option during
planning:
Allows planners to greatly reduce redundant collision checks. If set and the target object is a robot, then only the links controlled by the currently set active DOFs and their attached bodies will be checked for collisions.
The things that will not be checked for collision are: links that do not move with respect to each other as a result of moving the active dofs.
You can use a CollisionOptionsStateSaver
to set the flag and automatically
restore the collision detector to its original state after planning is done:
with CollisionOptionsStateSaver(env.GetCollisionChecker(), CollisionOptions.ActiveDOFs):
result = planner.PlanPath(traj)
The following table shows which OMPL planners are available via or_ompl
.
(1 Oct 2015) Note that if you are using the ROS package of OMPL ros-indigo-ompl
then BIT* and FMT* will not be available. To use those planners♣ you will need to install the latest OMPL from source. There is a catkinized package here OMPL_catkin_pkg
Planner Name | OMPL Library | OpenRAVE Plugin Name |
or_ompl Unit Test |
---|---|---|---|
BIT* (Batch Informed Trees) ♣ | BITstar | OMPL_BITstar | ✗ |
BKPIECE1 (Bi-directional KPIECE) | BKPIECE1 | OMPL_BKPIECE1 | ✔ |
EST (Expansive Space Trees) | EST | OMPL_EST | ✔ |
FMT* (Fast Marching Tree) ♣ | FMT | OMPL_FMT | ✗ |
KPIECE1 (Kinematic Planning by Interior-Exterior Cell Exploration) | KPIECE1 | OMPL_KPIECE1 | ✔ |
LBKPIECE1 (Lazy Bi-directional KPIECE) | LBKPIECE1 | OMPL_LBKPIECE1 | ✔ |
LazyPRM | LazyPRM | OMPL_LazyPRM | ✔ |
LazyRRT | LazyRRT | OMPL_LazyRRT | ✔ |
PDST (Path-Directed Subdivision Trees) | PDST | OMPL_PDST | ✗ |
PRM (Probabilistic Road Map) | PRM | OMPL_PRM | ✔ |
PRM* | PRMstar | OMPL_PRMstar | ✔ |
RRT (Rapidly Exploring Random Trees) | RRT | OMPL_RRT | ✔ |
RRTConnect (Bi-directional RRT) | RRTConnect | OMPL_RRTConnect | ✔ |
RRT* | RRTstar | OMPL_RRTstar | ✗ |
SBL (Single-query Bi-directional Lazy collision checking planner) | SBL | OMPL_SBL | ✔ |
SPARS (SPArse Roadmap Spanner) | SPARS | OMPL_SPARS | ✗ |
SPARS2 | SPARStwo | OMPL_SPARStwo | ✗ |
T-RRT (Transition-based RRT) | TRRT | OMPL_TRRT | ✗ |
pRRT (Parallel RRT) | pRRT | OMPL_pRRT | ✗ |
pSBL (Parallel SBL) | pSBL | OMPL_pSBL | ✗ |
Cforest (Coupled Forest of Random Engrafting Search Trees - parallelization framework) | CForest | N/A | N/A |
Thunder | Thunder | N/A | N/A |
Lightning | Lightning | N/A | N/A |
LazyPRM* | LazyPRMstar | N/A | N/A |
BiTRRT (Bidirectional T-RRT) | BiTRRT | N/A | N/A |
LazyLBTRRT | LazyLBTRRT | N/A | N/A |
LBTRRT (Lower Bound Tree RRT) | LBTRRT | N/A | N/A |
STRIDE (Search Tree with Resolution Independent Density Estimation) | STRIDE | N/A | N/A |
or_ompl is licensed under a BSD license. See LICENSE
for more information.
or_ompl was developed by the Personal Robotics Lab in the Robotics Institute at Carnegie Mellon University. This plugin was written by Michael Koval and grew out of earlier plugin written by Christopher Dellin and Matthew Klingensmith.