Skip to content

tesseract_robotics.tesseract_motion_planners_ompl

OMPL (Open Motion Planning Library) planner bindings.

Overview

OMPL provides sampling-based planners for complex environments where optimization-based planners may get stuck in local minima.

Python
from tesseract_robotics.tesseract_motion_planners_ompl import (
    OMPLMotionPlanner,
    OMPLPlanProfile, OMPLRealVectorPlanProfile,
    RRTConnectConfigurator, RRTstarConfigurator, SBLConfigurator,
    ProfileDictionary_addOMPLProfile,
)

OMPLMotionPlanner

The OMPL motion planner.

Python
from tesseract_robotics.tesseract_motion_planners_ompl import OMPLMotionPlanner
from tesseract_robotics.tesseract_motion_planners import PlannerRequest

planner = OMPLMotionPlanner()

request = PlannerRequest()
request.env = env
request.instructions = program
request.profiles = profiles

response = planner.solve(request)

Profiles

OMPLRealVectorPlanProfile

Configure OMPL planning behavior.

Python
from tesseract_robotics.tesseract_motion_planners_ompl import OMPLRealVectorPlanProfile

profile = OMPLRealVectorPlanProfile()

# Planning time
profile.planning_time = 5.0  # seconds

# Simplification
profile.simplify = True

# State validation resolution
profile.collision_check_config.longest_valid_segment_length = 0.01

# Add planner configurator
profile.planners = [RRTConnectConfigurator()]
Attribute Type Default Description
planning_time float 5.0 Max planning time (seconds)
simplify bool True Simplify path after planning
optimize bool True Run path optimization
planners list [RRTConnect] Planner configurators

Planner Configurators

RRTConnectConfigurator

Rapidly-exploring Random Tree Connect - fast, bidirectional.

Python
from tesseract_robotics.tesseract_motion_planners_ompl import RRTConnectConfigurator

config = RRTConnectConfigurator()
config.range = 0.0  # 0 = auto

profile.planners = [config]

RRTstarConfigurator

RRT* - asymptotically optimal.

Python
from tesseract_robotics.tesseract_motion_planners_ompl import RRTstarConfigurator

config = RRTstarConfigurator()
config.range = 0.0
config.goal_bias = 0.05

profile.planners = [config]

SBLConfigurator

Single-query Bidirectional Lazy PRM.

Python
from tesseract_robotics.tesseract_motion_planners_ompl import SBLConfigurator

config = SBLConfigurator()
config.range = 0.0

profile.planners = [config]

OMPLPlannerType

Available OMPL planners:

Type Description
RRTConnect Bidirectional RRT (default, fast)
RRT Basic RRT
RRTstar Asymptotically optimal RRT
PRM Probabilistic Roadmap
PRMstar Optimal PRM
SBL Single-query Bidirectional Lazy
EST Expansive Space Trees
LBTRRT Lower Bound Tree RRT
BiTRRT Bidirectional Transition RRT

Adding Profiles

Python
from tesseract_robotics.tesseract_command_language import ProfileDictionary
from tesseract_robotics.tesseract_motion_planners_ompl import (
    OMPLRealVectorPlanProfile, ProfileDictionary_addOMPLProfile,
    RRTConnectConfigurator
)

# Create profile
profile = OMPLRealVectorPlanProfile()
profile.planning_time = 10.0
profile.planners = [RRTConnectConfigurator()]

# Add to dictionary
profiles = ProfileDictionary()
ProfileDictionary_addOMPLProfile(profiles, "DEFAULT", profile)

# Use with planner request
request.profiles = profiles

Complete Example

Python
from tesseract_robotics.tesseract_motion_planners_ompl import (
    OMPLMotionPlanner, OMPLRealVectorPlanProfile,
    RRTConnectConfigurator, ProfileDictionary_addOMPLProfile
)
from tesseract_robotics.tesseract_motion_planners import PlannerRequest
from tesseract_robotics.tesseract_command_language import ProfileDictionary

# Configure OMPL profile
profile = OMPLRealVectorPlanProfile()
profile.planning_time = 5.0
profile.simplify = True
profile.planners = [RRTConnectConfigurator()]

profiles = ProfileDictionary()
ProfileDictionary_addOMPLProfile(profiles, "DEFAULT", profile)

# Create request
request = PlannerRequest()
request.env = env
request.instructions = program
request.profiles = profiles

# Solve
planner = OMPLMotionPlanner()
response = planner.solve(request)

if response.successful:
    trajectory = response.results
    print(f"Found path with {len(trajectory)} waypoints")
else:
    print(f"Planning failed: {response.message}")

Tips

  1. RRTConnect is usually the best starting point - fast and reliable
  2. Increase planning_time for complex environments
  3. Use simplify=True to reduce waypoints
  4. Lower collision resolution (longest_valid_segment_length) for narrow passages
  5. OMPL finds paths, not smooth trajectories - use TrajOpt for smoothing

Auto-generated API Reference

OMPLPlanProfile module-attribute

Python
OMPLPlanProfile: TypeAlias = OMPLMoveProfile

OMPLRealVectorPlanProfile module-attribute

Python
OMPLRealVectorPlanProfile: TypeAlias = OMPLRealVectorMoveProfile

OMPLSolverConfig

planning_time property writable

Python
planning_time: float

Max planning time allowed in seconds (default: 5.0)

max_solutions property writable

Python
max_solutions: int

Max number of solutions to find before exiting (default: 10)

simplify property writable

Python
simplify: bool

Simplify trajectory (default: false). Ignores n_output_states if true.

optimize property writable

Python
optimize: bool

Use all planning time to optimize trajectory (default: true)

__init__

Python
__init__() -> None

addPlanner

Python
addPlanner(planner: OMPLPlannerConfigurator) -> None

Add a planner configurator (each runs in parallel)

clearPlanners

Python
clearPlanners() -> None

Clear all planners

getNumPlanners

Python
getNumPlanners() -> int

Get number of planners (threads)

OMPLPlannerType

Bases: Enum

SBL class-attribute instance-attribute

Python
SBL = 0

EST class-attribute instance-attribute

Python
EST = 1

LBKPIECE1 class-attribute instance-attribute

Python
LBKPIECE1 = 2

BKPIECE1 class-attribute instance-attribute

Python
BKPIECE1 = 3

KPIECE1 class-attribute instance-attribute

Python
KPIECE1 = 4

BiTRRT class-attribute instance-attribute

Python
BiTRRT = 5

RRT class-attribute instance-attribute

Python
RRT = 6

RRTConnect class-attribute instance-attribute

Python
RRTConnect = 7

RRTstar class-attribute instance-attribute

Python
RRTstar = 8

TRRT class-attribute instance-attribute

Python
TRRT = 9

PRM class-attribute instance-attribute

Python
PRM = 10

PRMstar class-attribute instance-attribute

Python
PRMstar = 11

LazyPRMstar class-attribute instance-attribute

Python
LazyPRMstar = 12

SPARS class-attribute instance-attribute

Python
SPARS = 13

OMPLPlannerConfigurator

getType

Python
getType() -> OMPLPlannerType

RRTConnectConfigurator

Bases: OMPLPlannerConfigurator

range property writable

Python
range: float

__init__

Python
__init__() -> None

RRTstarConfigurator

Bases: OMPLPlannerConfigurator

range property writable

Python
range: float

goal_bias property writable

Python
goal_bias: float

delay_collision_checking property writable

Python
delay_collision_checking: bool

__init__

Python
__init__() -> None

SBLConfigurator

Bases: OMPLPlannerConfigurator

range property writable

Python
range: float

__init__

Python
__init__() -> None

OMPLMoveProfile

Bases: Profile

getKey

Python
getKey() -> int

getStaticKey staticmethod

Python
getStaticKey() -> int

OMPLRealVectorMoveProfile

Bases: OMPLMoveProfile

solver_config property writable

Python
solver_config: OMPLSolverConfig

The OMPL parallel planner solver config

contact_manager_config property writable

Python
contact_manager_config: ContactManagerConfig

The contact manager configuration (collision margins)

collision_check_config property writable

Python
collision_check_config: CollisionCheckConfig

The collision check configuration

__init__

Python
__init__() -> None

OMPLMotionPlanner

__init__

Python
__init__(name: str) -> None

getName

Python
getName() -> str

solve

Python
solve(request: 'tesseract_planning::PlannerRequest') -> 'tesseract_planning::PlannerResponse'

terminate

Python
terminate() -> bool

clear

Python
clear() -> None

OMPLMoveProfile_as_ProfileConstPtr

Python
OMPLMoveProfile_as_ProfileConstPtr(profile: OMPLMoveProfile) -> tesseract_robotics.tesseract_command_language._tesseract_command_language.Profile

Convert OMPLMoveProfile to Profile::ConstPtr for use with ProfileDictionary.addProfile

OMPLPlanProfile_as_ProfileConstPtr

Python
OMPLPlanProfile_as_ProfileConstPtr(profile: OMPLMoveProfile) -> tesseract_robotics.tesseract_command_language._tesseract_command_language.Profile

Convert OMPLPlanProfile to Profile::ConstPtr (legacy alias)

ProfileDictionary_addOMPLMoveProfile

Python
ProfileDictionary_addOMPLMoveProfile(dict: ProfileDictionary, ns: str, profile_name: str, profile: OMPLMoveProfile) -> None

Add OMPL move profile to ProfileDictionary

ProfileDictionary_addOMPLProfile

Python
ProfileDictionary_addOMPLProfile(dict: ProfileDictionary, ns: str, profile_name: str, profile: OMPLMoveProfile) -> None

Add OMPL plan profile to ProfileDictionary (legacy alias)