Skip to content

tesseract_robotics.tesseract_motion_planners_simple

Simple joint-space interpolation planner.

Overview

The Simple planner performs linear interpolation in joint space. No collision checking - use only when path is known to be safe.

Python
from tesseract_robotics.tesseract_motion_planners_simple import (
    SimpleMotionPlanner,
    generateInterpolatedProgram,
)

SimpleMotionPlanner

Python
from tesseract_robotics.tesseract_motion_planners_simple import SimpleMotionPlanner
from tesseract_robotics.tesseract_motion_planners import PlannerRequest

planner = SimpleMotionPlanner()

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

response = planner.solve(request)

Utility Functions

generateInterpolatedProgram

Interpolate a program to add intermediate waypoints.

Python
from tesseract_robotics.tesseract_motion_planners_simple import generateInterpolatedProgram

# Add waypoints between existing ones
interpolated = generateInterpolatedProgram(
    program,
    env,
    profiles,
    max_step=0.1  # max joint step between waypoints
)

Use Cases

  • Initial seeding: Generate dense trajectory for TrajOpt
  • Safe paths: When you know the path is collision-free
  • Testing: Quick trajectory generation for debugging
  • Time parameterization input: Dense trajectory for velocity planning

Example

Python
from tesseract_robotics.tesseract_motion_planners_simple import SimpleMotionPlanner
from tesseract_robotics.tesseract_motion_planners import PlannerRequest
from tesseract_robotics.tesseract_command_language import ProfileDictionary

# Simple planner needs minimal setup
profiles = ProfileDictionary()

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

planner = SimpleMotionPlanner()
response = planner.solve(request)

if response.successful:
    # Result is linearly interpolated joint trajectory
    trajectory = response.results

Limitations

  • No collision checking: Path may collide with obstacles
  • Joint-space only: Cartesian interpolation not supported
  • No optimization: Just linear interpolation

Tips

  1. Use as preprocessing for optimization-based planners
  2. Verify collision after planning with simple planner
  3. Good for short motions where collision is unlikely

Auto-generated API Reference

SimpleMotionPlanner

__init__

Python
__init__(name: str = 'SIMPLE') -> None

getName

Python
getName() -> str

solve

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

terminate

Python
terminate() -> bool

clear

Python
clear() -> None

generateInterpolatedProgram

Python
generateInterpolatedProgram(instructions: 'tesseract_planning::CompositeInstruction', env: 'tesseract_environment::Environment', state_longest_valid_segment_length: float = 0.08726646259971647, translation_longest_valid_segment_length: float = 0.15, rotation_longest_valid_segment_length: float = 0.08726646259971647, min_steps: int = 1) -> 'tesseract_planning::CompositeInstruction'

Generate an interpolated program from a composite instruction