- Rigid body planning [Python version]. This demo is essentially the same example described in the first tutorial. It illustrates how to use the main classes.
- State sampling [Python version]. This is the demo program used in the last beginner tutorial.
- Analyze and visualize planner data in Python. This demo relies on the graph-tool package.
- Rigid body planning with controls [Python version]. This demo shows how to perform planning under differential constraints for a simple car-like vehicle.
- Rigid body planning with integration and controls. This example extends the previous example by showing how one can plan for systems of ordinary differential equations in a generic way. This example uses simple Euler integration. For higher accuracy it is recommended to use the ODESolver class described in the next demo.
- Rigid body planning with ODESolver and controls. [Python version] This example compares and contrasts the previous demo of planning with integration and planning using the ODESolver class, which wraps around Boost.Numeric.Odeint. Code showing the same model being planned with a user-implemented numerical integration technique as well as the ODESolver is presented.
Koules This is a very elaborate demo to illustrate planning for underactuated kinodynamic systems with drift. It based on an old Unix game called Koules. The physics have been made significantly harder compared to the original game. The demo can solve just one level of Koules, all levels, or run a number of planners on one level as a benchmarking run. The demo prints out a path that can be turned into a movie using KoulesPlayback.py. Example usage:
> ./demo_Koules --planall --planner kpiece --numkoules 7 --maxtime 600 --output koules7.log > /path/to/ompl/demos/KoulesPlaypack.py koules7.log
This will create a movie called koules7.mp4. See the gallery for an example of what this might look like.
This demo illustrates also many advanced OMPL concepts, such as classes for a custom state space, a control sampler, a projection, a state propagator, and a goal class. It also demonstrates how one could put a simple bang-bang controller inside the StatePropagator. In this demo the (Directed)ControlSampler simply samples a target velocity vector and inside the StatePropagator the control is chosen to drive the ship to attain this velocity.
- Planning for a simple hybrid system. This demo shows how one could plan for a car with gears. The gear is a discrete state variable, while its pose is continuous. The car needs to make a sharp turn and is forced to change gears. This is not the best way to plan for hybrid systems, since this approach ignores completely the structure that exist in the system. Nevertheless, it demonstrates that the planners in OMPL are state space agnostic and can plan in discrete or hybrid state spaces.
- Rigid body planning with an Inverse Kinematics solver generating goal states in a separate thread. This demo shows off two neat features of OMPL: a genetic algorithm-based Inverse Kinematics solver and a lazy goal state sampler. In a separate thread goal states are computed by the IK solver. While solving a motion planning problem, the planning algorithms select a random goal state from the ones computed so far.
- Rigid body planning using the Open Dynamics Engine (ODE). When ODE is installed, OMPL will compile an extension that makes is easier to use ODE for forward propagation of models of motion. In this example, a box is pushed around in the plane from a start position to a goal position.
- Random walk planner. A simple demo illustrating how to create a new planning algorithm in Python. This particular planner simply performs a random walk until it gets close to the goal.
- Planning for Dubins and Reeds-Shepp cars. This demo illustrates the use of the ompl::base::DubinsStateSpace and ompl::base::ReedsSheppStateSpace. The demo can solve two simple planning problems, print trajectories from the origin to a user-specified state, or print a discretized distance field.
- Optimal planning for a 2D point robot. [Python version]. This demo illustrates the use of
ompl::base::OptimizationObjective
to construct optimization objectives for optimal motion planning. - Hypercube benchmark. A simple benchmark where the configuration space consists of a hypercube in Rn and the free space is a narrow corridor along edges of the hypercube. The exploration progress of a planner is therefore hard to capture in a low-dimensional projection.
- Kinematic chain benchmark. A benchmark for an n-link kinematic chain to get out of a narrow passage. It requires the chain to fold up and expand again. As in the previous benchmark, the free space is hard to capture by a low-dimensional projection of the configuration space.
- 2D point planning using a PPM image as a map [Python version]
- Circle Grid benchmark. Implements a configurable 2D circle grid benchmark problem, where the user can specify state space, size of the grid and circles, so that the problem can be as hard as desired.
- LTLWithTriangulation. A demo for ompl::control::LTLPlanner, a planner that find solutions for kinodynamic motion planning problems where the goal is specified by a Linear Temporal Logic (LTL) specification.
- Constrained Planning Demos. These are a set of demos that illustrate how to use OMPL to plan for robot motion under constraints. Each of these demos supports planning for an individual planner as well as benchmarking, and complete configurability of the hyperparameters of the constrained space. See the help with the
-h
flag on each program..- ConstrainedPlanningSphere [Python version]. Plan for a point in R3 constrained to the surface of a sphere, with narrow obstacles it must traverse. The results for this program are visualizable with the Blender file
ConstrainedPlanningSphere.blend
. Use the-o
flag to enable output, and run the script linked inside the blender file. - ConstrainedPlanningTorus [Python version]. Plan for a point in R3 constrained to the surface of a torus. A "maze" image is loaded (some examples are provided in
ompl/demos/constraint/mazes
) to use as the set of obstacles to traverse. The start and goal point are red and green pixels in the images respectively. The results for this program are visualizable with the Blender fileConstrainedPlanningTorus.blend
. Use the-o
flag to enable output, and run the script linked inside the blender file. - ConstrainedPlanningImplicitChain [Python version]. Plan for a set of balls, each in R3, constrained to be a unit distance apart. This imposes spherical kinematics on the balls, implicitly defining a kinematic chain. The results for this program are visualizable with the Blender file
ConstrainedPlanningImplicitChain.blend
. Use the-o
flag to enable output, and run the script linked inside the blender file. - ConstrainedPlanningImplicitParallel. Plan for a parallel robot made of many implicit chains. The results for this program are visualizable with the Blender file
ConstrainedPlanningImplicitParallel.blend
. Use the-o
flag to enable output, and run the script linked inside the blender file. - ConstrainedPlanningKinematicChain. Similar to the kinematic chain benchmark above, but with a constraint that only allows the tip of the manipulator to move along a line.
- ConstrainedPlanningSphere [Python version]. Plan for a point in R3 constrained to the surface of a sphere, with narrow obstacles it must traverse. The results for this program are visualizable with the Blender file
- Multilevel Planning Demos. Set of demos to illustrate how to use OMPL to plan motions on different abstraction levels. For more information refer to the Multilevel Planning Guide and the Multilevel Planning Tutorial
- Multilevel Rigid Body in 2D. Two-level planning for a rigid body in \(SE(2)\) with simplified space \(\mathbb{R}^2\).
- Multilevel Rigid Body in 3D. Two-level planning for a rigid body in \(SE(3)\) with simplified space \(\mathbb{R}^3\).
- Multilevel HyperCube. N-level hypercube benchmark using a point robot moving in a cube \(\mathbb{[0,1]}^N\) (This is a modified version of the Hypercube benchmark).
- Multilevel HyperCube Benchmark. Benchmark version of Multilevel Hypercube
- Multilevel KinematicChain. Multilevel version of Kinematic Chain benchmark.