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.
from tesseract_robotics.tesseract_motion_planners_simple import (
SimpleMotionPlanner,
generateInterpolatedProgram,
)
SimpleMotionPlanner¶
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.
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¶
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¶
- Use as preprocessing for optimization-based planners
- Verify collision after planning with simple planner
- Good for short motions where collision is unlikely
Auto-generated API Reference¶
tesseract_motion_planners_simple Python bindings
SimpleMotionPlanner
¶
SimplePlannerFixedSizeMoveProfile
¶
Bases: SimplePlannerMoveProfile
SimplePlannerFixedSizeAssignMoveProfile
¶
Bases: SimplePlannerMoveProfile
SimplePlannerFixedSizeAssignNoIKMoveProfile
¶
Bases: SimplePlannerMoveProfile
SimplePlannerLVSMoveProfile
¶
Bases: SimplePlannerMoveProfile
state_longest_valid_segment_length
property
writable
¶
translation_longest_valid_segment_length
property
writable
¶
rotation_longest_valid_segment_length
property
writable
¶
__init__
¶
__init__(state_longest_valid_segment_length: float = 0.08726646259971647, translation_longest_valid_segment_length: float = 0.1, rotation_longest_valid_segment_length: float = 0.08726646259971647, min_steps: int = 1, max_steps: int = 2147483647) -> None
SimplePlannerLVSNoIKMoveProfile
¶
Bases: SimplePlannerMoveProfile
state_longest_valid_segment_length
property
writable
¶
translation_longest_valid_segment_length
property
writable
¶
rotation_longest_valid_segment_length
property
writable
¶
__init__
¶
__init__(state_longest_valid_segment_length: float = 0.08726646259971647, translation_longest_valid_segment_length: float = 0.1, rotation_longest_valid_segment_length: float = 0.08726646259971647, min_steps: int = 1, max_steps: int = 2147483647) -> None
SimplePlannerLVSAssignMoveProfile
¶
Bases: SimplePlannerMoveProfile
state_longest_valid_segment_length
property
writable
¶
translation_longest_valid_segment_length
property
writable
¶
rotation_longest_valid_segment_length
property
writable
¶
__init__
¶
__init__(state_longest_valid_segment_length: float = 0.08726646259971647, translation_longest_valid_segment_length: float = 0.1, rotation_longest_valid_segment_length: float = 0.08726646259971647, min_steps: int = 1, max_steps: int = 2147483647) -> None
SimplePlannerLVSAssignNoIKMoveProfile
¶
Bases: SimplePlannerMoveProfile
state_longest_valid_segment_length
property
writable
¶
translation_longest_valid_segment_length
property
writable
¶
rotation_longest_valid_segment_length
property
writable
¶
__init__
¶
__init__(state_longest_valid_segment_length: float = 0.08726646259971647, translation_longest_valid_segment_length: float = 0.1, rotation_longest_valid_segment_length: float = 0.08726646259971647, min_steps: int = 1, max_steps: int = 2147483647) -> None
generateInterpolatedProgram
¶
generateInterpolatedProgram(instructions: 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_robotics.tesseract_command_language._tesseract_command_language.CompositeInstruction
Generate an interpolated program from a composite instruction
ProfileDictionary_addSimplePlannerMoveProfile
¶
ProfileDictionary_addSimplePlannerMoveProfile(dict: ProfileDictionary, ns: str, profile_name: str, profile: SimplePlannerMoveProfile) -> None
Add a simple planner move profile to ProfileDictionary
ProfileDictionary_addSimplePlannerCompositeProfile
¶
ProfileDictionary_addSimplePlannerCompositeProfile(dict: ProfileDictionary, ns: str, profile_name: str, profile: SimplePlannerCompositeProfile) -> None
Add a simple planner composite profile to ProfileDictionary