Skip to content

tesseract_robotics.planning

High-level planning API for robot motion planning.

tesseract_robotics.planning

tesseract_robotics.planning - Pythonic API for Tesseract Motion Planning

This module provides a high-level, Pythonic interface to the Tesseract motion planning libraries. It wraps the lower-level nanobind bindings with convenient factory functions, automatic type conversions, and builder patterns.

Key Features: - Automatic poly-type wrapping (no more _wrap_ functions) - Simple robot/environment loading from URDF/SRDF - Builder pattern for motion programs - Simplified task composer workflow - Transform/pose helpers

Example Usage

from tesseract_robotics.planning import ( Robot, MotionProgram, CartesianTarget, JointTarget, plan_freespace, )

Load robot from URDF/SRDF

robot = Robot.from_urdf("package://my_robot/urdf/robot.urdf", "package://my_robot/urdf/robot.srdf")

Create motion program with builder pattern

program = (MotionProgram("manipulator") .move_to(JointTarget([0, 0, 0, 0, 0, 0])) .move_to(CartesianTarget([0.5, 0.0, 0.5], [0, 0, 1, 0])) .move_to(JointTarget([0.5, 0, 0, 0, 0, 0])) )

Plan and execute

result = plan_freespace(robot, program) if result.successful: print(f"Found trajectory with {len(result.trajectory)} waypoints")

STANDARD_PROFILE_NAMES module-attribute

Python
STANDARD_PROFILE_NAMES = ['DEFAULT', 'FREESPACE', 'CARTESIAN', 'RASTER', 'UPRIGHT']

Transform module-attribute

Python
Transform = Pose

__all__ module-attribute

Python
__all__ = ['Robot', 'RobotState', 'MotionProgram', 'CartesianTarget', 'JointTarget', 'StateTarget', 'MoveType', 'Pose', 'Transform', 'translation', 'rotation_x', 'rotation_y', 'rotation_z', 'rotation_from_quaternion', 'rotation_from_axis_angle', 'box', 'sphere', 'cylinder', 'cone', 'mesh_from_file', 'convex_mesh_from_file', 'create_obstacle', 'create_fixed_joint', 'PlanningResult', 'plan_freespace', 'plan_ompl', 'plan_cartesian', 'PlannerConfig', 'assign_current_state_as_seed', 'TaskComposer', 'TrajectoryPoint', 'STANDARD_PROFILE_NAMES', 'create_trajopt_default_profiles', 'create_trajopt_ifopt_default_profiles', 'create_ompl_default_profiles', 'create_ompl_planner_configurators', 'create_descartes_default_profiles', 'create_freespace_pipeline_profiles', 'create_cartesian_pipeline_profiles', 'create_time_optimal_parameterization', 'create_iterative_spline_parameterization']

TaskComposer

High-level interface for task composer planning pipelines.

Wraps the TaskComposerPluginFactory and handles all the AnyPoly boilerplate for setting up and running planning tasks.

Available Pipelines

FreespaceMotionPipeline: OMPL + TrajOpt smoothing + time param (recommended) CartesianMotionPipeline: Cartesian path with TrajOpt OMPLPipeline: OMPL sampling-based planning only TrajOptPipeline: TrajOpt optimization only DescartesPipeline: Descartes graph search

Example

composer = TaskComposer.from_config()

Plan with TrajOpt (optimization-based)

result = composer.plan_freespace(robot, program)

Plan with OMPL (sampling-based: RRT, RRT*, PRM, etc.)

result = composer.plan_ompl(robot, program)

Plan Cartesian path

result = composer.plan_cartesian(robot, program)

Or specify pipeline directly

result = composer.plan(robot, program, pipeline="TrajOptPipeline")

factory instance-attribute

Python
factory = factory

locator instance-attribute

Python
locator = locator or GeneralResourceLocator()

executor property

Python
executor: TaskflowTaskComposerExecutor

Get or create task executor (lazy initialization).

__init__

Python
__init__(factory: TaskComposerPluginFactory, locator: GeneralResourceLocator | None = None, num_threads: int | None = None, executor: TaskComposerExecutor | None = None, config_path: str | Path | None = None)

Initialize TaskComposer.

Parameters:

Name Type Description Default
factory TaskComposerPluginFactory

Initialized TaskComposerPluginFactory

required
locator GeneralResourceLocator | None

Resource locator

None
num_threads int | None

Number of threads for executor (overrides YAML config)

None
executor TaskComposerExecutor | None

Pre-configured executor (overrides num_threads and YAML)

None
config_path str | Path | None

Path to config YAML (for get_available_pipelines)

None

Raises:

Type Description
TypeError

If factory is not a TaskComposerPluginFactory

ValueError

If both num_threads and executor are provided

Note

Use TaskComposer.from_config() for simpler initialization. Do not pass a Robot or Environment - use the factory pattern.

from_config classmethod

Python
from_config(config_path: str | Path | None = None, locator: GeneralResourceLocator | None = None, num_threads: int | None = None, executor: TaskComposerExecutor | None = None) -> TaskComposer

Create TaskComposer from config file.

If no config_path is provided, uses TESSERACT_TASK_COMPOSER_CONFIG_FILE environment variable or falls back to the default config.

Parameters:

Name Type Description Default
config_path str | Path | None

Path to task composer config YAML

None
locator GeneralResourceLocator | None

Resource locator

None
num_threads int | None

Number of threads for executor (overrides YAML config)

None
executor TaskComposerExecutor | None

Pre-configured executor (overrides num_threads and YAML)

None

Returns:

Type Description
TaskComposer

Initialized TaskComposer

Example

Use YAML config (default)

composer = TaskComposer.from_config()

Override thread count

composer = TaskComposer.from_config(num_threads=4)

Use custom executor

from tesseract_robotics.tesseract_task_composer import TaskflowTaskComposerExecutor executor = TaskflowTaskComposerExecutor("MyExecutor", 8) composer = TaskComposer.from_config(executor=executor)

plan

Python
plan(robot: Robot, program: MotionProgram | CompositeInstruction, pipeline: str = 'TrajOptPipeline', profiles: ProfileDictionary | None = None) -> PlanningResult

Plan a motion program using specified pipeline.

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program or CompositeInstruction

required
pipeline str

Pipeline name (e.g., "TrajOptPipeline", "OMPLPipeline")

'TrajOptPipeline'
profiles ProfileDictionary | None

Custom profiles (uses defaults if None)

None

Returns:

Type Description
PlanningResult

PlanningResult with trajectory if successful

plan_freespace

Python
plan_freespace(robot: Robot, program: MotionProgram | CompositeInstruction, profiles: ProfileDictionary | None = None) -> PlanningResult

Plan freespace motion using TrajOpt pipeline.

Convenience method that uses TrajOptPipeline for optimization-based collision-free motion planning. For sampling-based planning, use plan_ompl().

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program

required
profiles ProfileDictionary | None

Custom profiles

None

Returns:

Type Description
PlanningResult

PlanningResult

plan_ompl

Python
plan_ompl(robot: Robot, program: MotionProgram | CompositeInstruction, profiles: ProfileDictionary | None = None) -> PlanningResult

Plan freespace motion using OMPL pipeline.

Uses sampling-based planners (RRT, RRT*, PRM, etc.) for collision-free motion planning. Good for complex environments where optimization-based planners may get stuck in local minima.

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program

required
profiles ProfileDictionary | None

Custom profiles (use to configure specific OMPL planner)

None

Returns:

Type Description
PlanningResult

PlanningResult

plan_cartesian

Python
plan_cartesian(robot: Robot, program: MotionProgram | CompositeInstruction, profiles: ProfileDictionary | None = None) -> PlanningResult

Plan Cartesian motion using Descartes pipeline.

For motions requiring precise Cartesian paths.

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program

required
profiles ProfileDictionary | None

Custom profiles

None

Returns:

Type Description
PlanningResult

PlanningResult

get_available_pipelines

Python
get_available_pipelines() -> list[str]

Get list of available pipeline names by introspecting the factory.

Actually attempts to create each node from the config to verify the C++ plugin can be loaded.

Returns:

Type Description
list[str]

List of pipeline names that can be used with plan().

list[str]

Common pipelines include: - FreespacePipeline: OMPL + TrajOpt smoothing + time param - CartesianPipeline: Cartesian path with TrajOpt - OMPLPipeline: OMPL sampling-based planning only - TrajOptPipeline: TrajOpt optimization only - DescartesFPipeline: Descartes graph search

TrajectoryPoint dataclass

Single point in a planned trajectory.

Attributes:

Name Type Description
joint_names list[str]

Names of joints

positions ndarray

Joint positions (radians)

velocities ndarray | None

Joint velocities (optional)

accelerations ndarray | None

Joint accelerations (optional)

time float | None

Time from start (optional)

joint_names instance-attribute

Python
joint_names: list[str]

positions instance-attribute

Python
positions: ndarray

velocities class-attribute instance-attribute

Python
velocities: ndarray | None = None

accelerations class-attribute instance-attribute

Python
accelerations: ndarray | None = None

time class-attribute instance-attribute

Python
time: float | None = None

as_dict

Python
as_dict() -> dict[str, float]

Return positions as {name: position} dictionary.

__repr__

Python
__repr__() -> str

__init__

Python
__init__(joint_names: list[str], positions: ndarray, velocities: ndarray | None = None, accelerations: ndarray | None = None, time: float | None = None) -> None

Robot

High-level interface for robot environment management.

Wraps the Tesseract Environment with a Pythonic interface for loading robots, managing state, and accessing kinematic information.

Attributes:

Name Type Description
env

Underlying Tesseract Environment

locator

Resource locator for resolving package:// URLs

Example

robot = Robot.from_urdf( "package://my_robot/urdf/robot.urdf", "package://my_robot/urdf/robot.srdf" )

Get joint names for a manipulator

joints = robot.get_joint_names("manipulator")

Compute forward kinematics

pose = robot.fk("manipulator", [0, 0, 0, 0, 0, 0])

Compute inverse kinematics

solutions = robot.ik("manipulator", target_pose)

env instance-attribute

Python
env = env

locator instance-attribute

Python
locator = locator or GeneralResourceLocator()

scene_graph property

Python
scene_graph: SceneGraph

Access the underlying scene graph.

__init__

Python
__init__(env: Environment, locator: GeneralResourceLocator | None = None)

Initialize Robot wrapper.

Parameters:

Name Type Description Default
env Environment

Initialized Tesseract Environment

required
locator GeneralResourceLocator | None

Resource locator (created if not provided)

None

from_urdf classmethod

Python
from_urdf(urdf_url: str, srdf_url: str, locator: GeneralResourceLocator | None = None) -> Robot

Load robot from URDF and SRDF URLs.

Supports both package:// URLs and file:// URLs.

Parameters:

Name Type Description Default
urdf_url str

URL to URDF file (e.g., "package://my_robot/urdf/robot.urdf")

required
srdf_url str

URL to SRDF file (e.g., "package://my_robot/urdf/robot.srdf")

required
locator GeneralResourceLocator | None

Resource locator (uses GeneralResourceLocator if not provided)

None

Returns:

Type Description
Robot

Initialized Robot instance

Raises:

Type Description
RuntimeError

If environment initialization fails

from_files classmethod

Python
from_files(urdf_path: str | Path, srdf_path: str | Path, locator: GeneralResourceLocator | None = None) -> Robot

Load robot from local URDF and SRDF files.

Parameters:

Name Type Description Default
urdf_path str | Path

Path to URDF file

required
srdf_path str | Path

Path to SRDF file

required
locator GeneralResourceLocator | None

Resource locator for resolving mesh references

None

Returns:

Type Description
Robot

Initialized Robot instance

from_tesseract_support classmethod

Python
from_tesseract_support(robot_name: str, locator: GeneralResourceLocator | None = None) -> Robot

Load robot from tesseract_support package.

Convenience method for loading standard test robots.

Parameters:

Name Type Description Default
robot_name str

Name of robot (e.g., "abb_irb2400", "lbr_iiwa_14_r820")

required

Returns:

Type Description
Robot

Initialized Robot instance

get_state

Python
get_state(joint_names: list[str] | None = None) -> RobotState

Get current robot state.

Parameters:

Name Type Description Default
joint_names list[str] | None

Specific joints to query (all if None)

None

Returns:

Type Description
RobotState

Current robot state

set_joints

Python
set_joints(joint_values: dict[str, float] | Sequence[float], joint_names: list[str] | None = None) -> None

Set robot joint positions.

Parameters:

Name Type Description Default
joint_values dict[str, float] | Sequence[float]

Joint positions as dict or sequence

required
joint_names list[str] | None

Joint names (required if joint_values is sequence)

None

get_joint_names

Python
get_joint_names(group_name: str) -> list[str]

Get joint names for a kinematic group.

Parameters:

Name Type Description Default
group_name str

Name of the kinematic group (e.g., "manipulator")

required

Returns:

Type Description
list[str]

List of joint names

Python
get_link_names() -> list[str]

Get all link names in the robot.

get_joint_limits

Python
get_joint_limits(group_name: str) -> dict[str, dict[str, float]]

Get joint limits for a kinematic group.

Parameters:

Name Type Description Default
group_name str

Name of the kinematic group

required

Returns:

Type Description
dict[str, dict[str, float]]

Dictionary mapping joint name to {lower, upper, velocity, acceleration}

fk

Python
fk(group_name: str, joint_positions: ArrayLike, tip_link: str | None = None) -> Pose

Compute forward kinematics.

Parameters:

Name Type Description Default
group_name str

Kinematic group name

required
joint_positions ArrayLike

Joint positions array

required
tip_link str | None

Target link (uses default TCP if None)

None

Returns:

Type Description
Pose

Pose of the tip link

ik

Python
ik(group_name: str, target_pose: Pose | Isometry3d, seed: ArrayLike | None = None, tip_link: str | None = None, all_solutions: bool = False) -> np.ndarray | list[np.ndarray] | None

Compute inverse kinematics.

Parameters:

Name Type Description Default
group_name str

Kinematic group name

required
target_pose Pose | Isometry3d

Desired end-effector pose

required
seed ArrayLike | None

Initial joint configuration (current state if None)

None
tip_link str | None

Target link name

None
all_solutions bool

If True, return all solutions; otherwise return first

False

Returns:

Type Description
ndarray | list[ndarray] | None

If all_solutions=False: Joint positions array, or None if no solution

ndarray | list[ndarray] | None

If all_solutions=True: List of joint positions arrays, or None if none found

get_manipulator_info

Python
get_manipulator_info(group_name: str, tcp_frame: str | None = None, working_frame: str = 'base_link') -> ManipulatorInfo

Get or create ManipulatorInfo for a kinematic group.

Parameters:

Name Type Description Default
group_name str

Kinematic group name

required
tcp_frame str | None

TCP frame name (auto-detected if None)

None
working_frame str

Working frame name

'base_link'

Returns:

Type Description
ManipulatorInfo

Configured ManipulatorInfo

Python
add_link(link: Link, joint: Joint) -> bool

Add a new link to the environment.

Parameters:

Name Type Description Default
link Link

Link to add

required
joint Joint

Joint connecting link to parent

required

Returns:

Type Description
bool

True if successful

Python
remove_link(link_name: str) -> bool

Remove a link from the environment.

Parameters:

Name Type Description Default
link_name str

Name of link to remove

required

Returns:

Type Description
bool

True if successful

Python
move_link(joint: Joint) -> bool

Move a link by providing a new joint configuration.

This attaches the child link to a new parent link via the joint.

Parameters:

Name Type Description Default
joint Joint

Joint object specifying new parent-child relationship

required

Returns:

Type Description
bool

True if successful

add_allowed_collision

Python
add_allowed_collision(link1: str, link2: str, reason: str = 'Adjacent') -> bool

Add an allowed collision pair.

Parameters:

Name Type Description Default
link1 str

First link name

required
link2 str

Second link name

required
reason str

Reason for allowing collision

'Adjacent'

Returns:

Type Description
bool

True if successful

set_collision_margin

Python
set_collision_margin(margin: float) -> bool

Set default collision margin distance.

Parameters:

Name Type Description Default
margin float

Collision margin in meters

required

Returns:

Type Description
bool

True if successful

__repr__

Python
__repr__() -> str

RobotState dataclass

Snapshot of robot joint state.

Attributes:

Name Type Description
joint_names list[str]

List of joint names

joint_positions ndarray

Array of joint positions (radians for revolute)

joint_velocities ndarray | None

Array of joint velocities (optional)

joint_accelerations ndarray | None

Array of joint accelerations (optional)

joint_names instance-attribute

Python
joint_names: list[str]

joint_positions instance-attribute

Python
joint_positions: ndarray

joint_velocities class-attribute instance-attribute

Python
joint_velocities: ndarray | None = None

joint_accelerations class-attribute instance-attribute

Python
joint_accelerations: ndarray | None = None

__post_init__

Python
__post_init__()

Convert arrays to numpy float64 for C++ interop.

as_dict

Python
as_dict() -> dict[str, float]

Return joint positions as {name: position} dictionary.

__getitem__

Python
__getitem__(joint_name: str) -> float

Get position of a specific joint by name.

__repr__

Python
__repr__() -> str

__init__

Python
__init__(joint_names: list[str], joint_positions: ndarray, joint_velocities: ndarray | None = None, joint_accelerations: ndarray | None = None) -> None

PlannerConfig dataclass

Configuration options for planning.

Attributes:

Name Type Description
pipeline str

Planning pipeline name

max_velocity_scaling float

Scale factor for velocity limits (0-1)

max_acceleration_scaling float

Scale factor for acceleration limits (0-1)

collision_safety_margin float

Minimum distance from obstacles

smoothing bool

Enable trajectory smoothing

time_parameterization bool

Enable time parameterization

pipeline class-attribute instance-attribute

Python
pipeline: str = 'TrajOptPipeline'

max_velocity_scaling class-attribute instance-attribute

Python
max_velocity_scaling: float = 1.0

max_acceleration_scaling class-attribute instance-attribute

Python
max_acceleration_scaling: float = 1.0

collision_safety_margin class-attribute instance-attribute

Python
collision_safety_margin: float = 0.025

smoothing class-attribute instance-attribute

Python
smoothing: bool = True

time_parameterization class-attribute instance-attribute

Python
time_parameterization: bool = True

__init__

Python
__init__(pipeline: str = 'TrajOptPipeline', max_velocity_scaling: float = 1.0, max_acceleration_scaling: float = 1.0, collision_safety_margin: float = 0.025, smoothing: bool = True, time_parameterization: bool = True) -> None

PlanningResult dataclass

Result from a planning operation.

Attributes:

Name Type Description
successful bool

Whether planning succeeded

message str

Status or error message

trajectory list[TrajectoryPoint]

List of trajectory points (if successful)

raw_results CompositeInstruction | None

Raw CompositeInstruction output

successful instance-attribute

Python
successful: bool

message class-attribute instance-attribute

Python
message: str = ''

trajectory class-attribute instance-attribute

Python
trajectory: list[TrajectoryPoint] = field(default_factory=list)

raw_results class-attribute instance-attribute

Python
raw_results: CompositeInstruction | None = None

__bool__

Python
__bool__() -> bool

Allow if result: checks.

__len__

Python
__len__() -> int

Return number of waypoints in trajectory.

__iter__

Python
__iter__() -> Iterator[TrajectoryPoint]

Iterate over trajectory points.

__getitem__

Python
__getitem__(idx: int) -> TrajectoryPoint

Get trajectory point by index.

to_numpy

Python
to_numpy() -> np.ndarray

Convert trajectory to numpy array.

Returns:

Type Description
ndarray

Array of shape (N, num_joints) with joint positions

__init__

Python
__init__(successful: bool, message: str = '', trajectory: list[TrajectoryPoint] = list(), raw_results: CompositeInstruction | None = None) -> None

CartesianTarget dataclass

Cartesian waypoint target (pose in Cartesian space).

Attributes:

Name Type Description
pose Pose | None

Target pose as Pose or position/quaternion

move_type MoveType

Motion type (FREESPACE or LINEAR)

profile str

Motion profile name

Example

From Pose

target = CartesianTarget(Pose.from_xyz(0.5, 0, 0.5))

From position and quaternion

target = CartesianTarget( position=[0.5, 0, 0.5], quaternion=[0, 0, 0.707, 0.707], )

Linear motion

target = CartesianTarget( Pose.from_xyz(0.5, 0, 0.5), move_type=MoveType.LINEAR, )

pose class-attribute instance-attribute

Python
pose: Pose | None = None

position class-attribute instance-attribute

Python
position: ArrayLike | None = None

quaternion class-attribute instance-attribute

Python
quaternion: ArrayLike | None = None

move_type class-attribute instance-attribute

Python
move_type: MoveType = FREESPACE

profile class-attribute instance-attribute

Python
profile: str = DEFAULT_PROFILE_KEY

__post_init__

Python
__post_init__()

to_waypoint

Python
to_waypoint() -> CartesianWaypoint

Convert to low-level CartesianWaypoint.

__init__

Python
__init__(pose: Pose | None = None, position: ArrayLike | None = None, quaternion: ArrayLike | None = None, move_type: MoveType = MoveType.FREESPACE, profile: str = DEFAULT_PROFILE_KEY) -> None

JointTarget dataclass

Joint waypoint target (joint positions).

Attributes:

Name Type Description
positions ArrayLike

Target joint positions (radians for revolute joints)

names list[str] | None

Joint names (auto-populated from robot if None)

move_type MoveType

Motion type (FREESPACE or LINEAR)

profile str

Motion profile name

Example

Just positions (names from robot)

target = JointTarget([0, 0, 0, -1.57, 0, 0])

With explicit names

target = JointTarget( positions=[0, 0, 0, -1.57, 0, 0], names=["joint_1", "joint_2", "joint_3", "joint_4", "joint_5", "joint_6"], )

positions instance-attribute

Python
positions: ArrayLike

names class-attribute instance-attribute

Python
names: list[str] | None = None

move_type class-attribute instance-attribute

Python
move_type: MoveType = FREESPACE

profile class-attribute instance-attribute

Python
profile: str = DEFAULT_PROFILE_KEY

__post_init__

Python
__post_init__()

to_waypoint

Python
to_waypoint(joint_names: list[str] | None = None) -> JointWaypoint

Convert to low-level JointWaypoint.

Parameters:

Name Type Description Default
joint_names list[str] | None

Joint names to use if not set on target

None

__init__

Python
__init__(positions: ArrayLike, names: list[str] | None = None, move_type: MoveType = MoveType.FREESPACE, profile: str = DEFAULT_PROFILE_KEY) -> None

MotionProgram

Fluent builder for motion programs.

Provides a high-level API for building motion programs with automatic poly-type wrapping. Supports chaining with method calls.

Attributes:

Name Type Description
group_name

Kinematic group name (e.g., "manipulator")

profile

Default motion profile

targets list[Target]

List of motion targets

Example

Build program with chained calls

program = (MotionProgram("manipulator") .start_at(JointTarget([0, 0, 0, 0, 0, 0])) .move_to(CartesianTarget(Pose.from_xyz(0.5, 0, 0.5))) .linear_to(CartesianTarget(Pose.from_xyz(0.5, 0.2, 0.5))) .move_to(JointTarget([0, 0, 0, 0, 0, 0])) )

Or add targets individually

program = MotionProgram("manipulator") program.add_target(JointTarget([0, 0, 0, 0, 0, 0])) program.add_target(CartesianTarget(pose))

group_name instance-attribute

Python
group_name = group_name

tcp_frame instance-attribute

Python
tcp_frame = tcp_frame

working_frame instance-attribute

Python
working_frame = working_frame

profile instance-attribute

Python
profile = profile

targets property

Python
targets: list[Target]

Get list of motion targets.

__init__

Python
__init__(group_name: str, tcp_frame: str | None = None, working_frame: str = 'base_link', profile: str = DEFAULT_PROFILE_KEY)

Initialize motion program builder.

Parameters:

Name Type Description Default
group_name str

Kinematic group name

required
tcp_frame str | None

TCP frame name (auto-detected if None)

None
working_frame str

Working/base frame name

'base_link'
profile str

Default motion profile name

DEFAULT_PROFILE_KEY

set_joint_names

Python
set_joint_names(names: list[str]) -> MotionProgram

Set joint names for the program.

Required if using JointTarget without explicit names.

Parameters:

Name Type Description Default
names list[str]

List of joint names

required

Returns:

Type Description
MotionProgram

Self for chaining

start_at

Python
start_at(target: Target) -> MotionProgram

Set the starting position (alias for add_target).

Parameters:

Name Type Description Default
target Target

Starting position target

required

Returns:

Type Description
MotionProgram

Self for chaining

move_to

Python
move_to(target: Target) -> MotionProgram

Add a freespace motion to target.

Sets target move_type to FREESPACE.

Parameters:

Name Type Description Default
target Target

Motion target

required

Returns:

Type Description
MotionProgram

Self for chaining

linear_to

Python
linear_to(target: Target) -> MotionProgram

Add a linear motion to target.

Sets target move_type to LINEAR.

Parameters:

Name Type Description Default
target Target

Motion target

required

Returns:

Type Description
MotionProgram

Self for chaining

add_target

Python
add_target(target: Target) -> MotionProgram

Add a target to the program.

Parameters:

Name Type Description Default
target Target

Motion target (CartesianTarget, JointTarget, or StateTarget)

required

Returns:

Type Description
MotionProgram

Self for chaining

add_targets

Python
add_targets(targets: Sequence[Target]) -> MotionProgram

Add multiple targets to the program.

Parameters:

Name Type Description Default
targets Sequence[Target]

Sequence of motion targets

required

Returns:

Type Description
MotionProgram

Self for chaining

__len__

Python
__len__() -> int

Return number of targets in program.

to_composite_instruction

Python
to_composite_instruction(joint_names: list[str] | None = None, tcp_frame: str | None = None) -> CompositeInstruction

Convert to low-level CompositeInstruction.

Handles all poly-type wrapping automatically.

Parameters:

Name Type Description Default
joint_names list[str] | None

Joint names (required for JointTarget without names)

None
tcp_frame str | None

Override TCP frame

None

Returns:

Type Description
CompositeInstruction

CompositeInstruction ready for planning

__repr__

Python
__repr__() -> str

MoveType

Bases: Enum

Motion type for move instructions.

FREESPACE class-attribute instance-attribute

Python
FREESPACE = auto()

LINEAR class-attribute instance-attribute

Python
LINEAR = auto()

StateTarget dataclass

State waypoint target (joint positions with optional velocities/accelerations).

Used for time-parameterized trajectories or when specifying full state.

Attributes:

Name Type Description
positions ArrayLike

Joint positions

names list[str] | None

Joint names

velocities ArrayLike | None

Optional joint velocities

accelerations ArrayLike | None

Optional joint accelerations

time float | None

Optional timestamp

move_type MoveType

Motion type

profile str

Motion profile name

positions instance-attribute

Python
positions: ArrayLike

names class-attribute instance-attribute

Python
names: list[str] | None = None

velocities class-attribute instance-attribute

Python
velocities: ArrayLike | None = None

accelerations class-attribute instance-attribute

Python
accelerations: ArrayLike | None = None

time class-attribute instance-attribute

Python
time: float | None = None

move_type class-attribute instance-attribute

Python
move_type: MoveType = FREESPACE

profile class-attribute instance-attribute

Python
profile: str = DEFAULT_PROFILE_KEY

__post_init__

Python
__post_init__()

to_waypoint

Python
to_waypoint(joint_names: list[str] | None = None) -> StateWaypoint

Convert to low-level StateWaypoint.

__init__

Python
__init__(positions: ArrayLike, names: list[str] | None = None, velocities: ArrayLike | None = None, accelerations: ArrayLike | None = None, time: float | None = None, move_type: MoveType = MoveType.FREESPACE, profile: str = DEFAULT_PROFILE_KEY) -> None

Pose dataclass

A 3D pose (position + orientation).

This class provides a Pythonic interface for working with 3D poses, wrapping numpy arrays and providing convenient factory methods.

Attributes:

Name Type Description
matrix ndarray

4x4 homogeneous transformation matrix

Example

From position and orientation

p = Pose.from_xyz_quat(0.5, 0, 0.3, 0, 0, 0.707, 0.707)

From numpy matrix

p = Pose(np.eye(4))

Chain poses (compose transformations)

result = p1 @ p2

Access components

pos = p.position # [x, y, z] rot = p.rotation_matrix # 3x3

matrix instance-attribute

Python
matrix: ndarray

position property

Python
position: ndarray

Get translation component as [x, y, z].

x property

Python
x: float

Get x position.

y property

Python
y: float

Get y position.

z property

Python
z: float

Get z position.

rotation_matrix property

Python
rotation_matrix: ndarray

Get 3x3 rotation matrix.

quaternion property

Python
quaternion: ndarray

Get quaternion as [qx, qy, qz, qw] (scalar-last).

rpy property

Python
rpy: tuple[float, float, float]

Get roll-pitch-yaw angles in radians.

__post_init__

Python
__post_init__()

Validate and convert matrix to numpy array.

identity classmethod

Python
identity() -> Pose

Create identity pose (no rotation, no translation).

from_xyz classmethod

Python
from_xyz(x: float, y: float, z: float) -> Pose

Create pure translation pose.

from_position classmethod

Python
from_position(position: ArrayLike) -> Pose

Create pure translation from position array [x, y, z].

from_xyz_quat classmethod

Python
from_xyz_quat(x: float, y: float, z: float, qx: float, qy: float, qz: float, qw: float) -> Pose

Create pose from position and quaternion.

Parameters:

Name Type Description Default
x, y, z

Position coordinates

required
qx, qy, qz, qw

Quaternion components (scalar-last convention)

required

from_position_quaternion classmethod

Python
from_position_quaternion(position: ArrayLike, quaternion: ArrayLike) -> Pose

Create pose from position and quaternion arrays.

Parameters:

Name Type Description Default
position ArrayLike

[x, y, z] position

required
quaternion ArrayLike

[qx, qy, qz, qw] quaternion (scalar-last)

required

from_xyz_rpy classmethod

Python
from_xyz_rpy(x: float, y: float, z: float, roll: float, pitch: float, yaw: float) -> Pose

Create pose from position and roll-pitch-yaw angles.

Parameters:

Name Type Description Default
x, y, z

Position coordinates

required
roll, pitch, yaw

Euler angles in radians (XYZ convention)

required

from_matrix classmethod

Python
from_matrix(matrix: ArrayLike) -> Pose

Create pose from 4x4 homogeneous matrix.

from_matrix_position classmethod

Python
from_matrix_position(rotation: ArrayLike, position: ArrayLike) -> Pose

Create pose from 3x3 rotation matrix and position.

Parameters:

Name Type Description Default
rotation ArrayLike

3x3 rotation matrix

required
position ArrayLike

[x, y, z] position

required

Example

R = np.array([[-1, 0, 0], [0, 1, 0], [0, 0, -1]]) p = Pose.from_matrix_position(R, [0.5, 0, 0.3])

from_isometry classmethod

Python
from_isometry(isometry: Isometry3d) -> Pose

Create pose from Tesseract Isometry3d.

to_isometry

Python
to_isometry() -> Isometry3d

Convert to Tesseract Isometry3d.

inverse

Python
inverse() -> Pose

Return the inverse pose.

__matmul__

Python
__matmul__(other: Pose) -> Pose

Chain poses: result = self @ other.

__repr__

Python
__repr__() -> str

__init__

Python
__init__(matrix: ndarray) -> None

box

Python
box(x: float, y: float, z: float) -> Box

Create a box geometry.

Parameters:

Name Type Description Default
x float

Size in X direction (meters)

required
y float

Size in Y direction (meters)

required
z float

Size in Z direction (meters)

required

Returns:

Type Description
Box

Box geometry

cone

Python
cone(radius: float, length: float) -> Cone

Create a cone geometry.

Parameters:

Name Type Description Default
radius float

Base radius (meters)

required
length float

Cone height (meters)

required

Returns:

Type Description
Cone

Cone geometry

convex_mesh_from_file

Python
convex_mesh_from_file(filepath: str | Path, scale: ndarray | None = None) -> ConvexMesh

Load convex mesh geometry from file.

Creates a convex hull from the loaded mesh, suitable for efficient collision checking.

Parameters:

Name Type Description Default
filepath str | Path

Path to mesh file or package:// URL

required
scale ndarray | None

Optional scale factors [sx, sy, sz]

None

Returns:

Type Description
ConvexMesh

ConvexMesh geometry

create_fixed_joint

Python
create_fixed_joint(name: str, parent_link: str, child_link: str, origin: Transform | None = None) -> Joint

Create a fixed joint between two links.

Parameters:

Name Type Description Default
name str

Joint name

required
parent_link str

Parent link name

required
child_link str

Child link name

required
origin Transform | None

Transform from parent to child (identity if None)

None

Returns:

Type Description
Joint

Configured Joint object

create_obstacle

Python
create_obstacle(robot: Robot, name: str, geometry: Geometry, transform: Transform | None = None, parent_link: str = 'base_link', color: tuple | None = None) -> bool

Add a collision obstacle to the robot environment.

Creates a new link with visual and collision geometry, attached to the parent link with a fixed joint.

Parameters:

Name Type Description Default
robot Robot

Robot instance to add obstacle to

required
name str

Name for the obstacle link

required
geometry Geometry

Geometry object (box, sphere, etc.)

required
transform Transform | None

Pose of the obstacle (identity if None)

None
parent_link str

Link to attach obstacle to

'base_link'
color tuple | None

Optional RGBA color tuple (0-1 range)

None

Returns:

Type Description
bool

True if obstacle was added successfully

Example

create_obstacle( robot, name="box_obstacle", geometry=box(0.5, 0.5, 0.5), transform=Transform.from_xyz(0.5, 0, 0.3), color=(0.8, 0.2, 0.2, 1.0), )

cylinder

Python
cylinder(radius: float, length: float) -> Cylinder

Create a cylinder geometry.

Parameters:

Name Type Description Default
radius float

Cylinder radius (meters)

required
length float

Cylinder length/height (meters)

required

Returns:

Type Description
Cylinder

Cylinder geometry

mesh_from_file

Python
mesh_from_file(filepath: str | Path, scale: ndarray | None = None) -> Mesh

Load mesh geometry from file.

Supports common mesh formats (STL, DAE, OBJ, etc.)

Parameters:

Name Type Description Default
filepath str | Path

Path to mesh file

required
scale ndarray | None

Optional scale factors [sx, sy, sz]

None

Returns:

Type Description
Mesh

Mesh geometry

sphere

Python
sphere(radius: float) -> Sphere

Create a sphere geometry.

Parameters:

Name Type Description Default
radius float

Sphere radius (meters)

required

Returns:

Type Description
Sphere

Sphere geometry

assign_current_state_as_seed

Python
assign_current_state_as_seed(program: CompositeInstruction, robot: Robot) -> None

Assign current robot state as seed for Cartesian waypoints.

This is required for planning with Cartesian waypoints to provide an initial joint configuration hint.

Parameters:

Name Type Description Default
program CompositeInstruction

CompositeInstruction to seed

required
robot Robot

Robot instance with current state

required

plan_cartesian

Python
plan_cartesian(robot: Robot, program: MotionProgram | CompositeInstruction, config: PlannerConfig | None = None, profiles: ProfileDictionary | None = None) -> PlanningResult

Plan Cartesian motion.

Uses Descartes for precise Cartesian path following.

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program with linear/Cartesian targets

required
config PlannerConfig | None

Planner configuration

None
profiles ProfileDictionary | None

Custom motion profiles

None

Returns:

Type Description
PlanningResult

PlanningResult with trajectory if successful

Example

from tesseract_robotics.planning import ( Robot, MotionProgram, CartesianTarget, Transform, plan_cartesian )

robot = Robot.from_tesseract_support("abb_irb2400")

Create linear path

program = (MotionProgram("manipulator") .move_to(CartesianTarget(Transform.from_xyz(0.5, -0.2, 0.5))) .linear_to(CartesianTarget(Transform.from_xyz(0.5, 0.2, 0.5))) )

result = plan_cartesian(robot, program)

plan_freespace

Python
plan_freespace(robot: Robot, program: MotionProgram | CompositeInstruction, config: PlannerConfig | None = None, profiles: ProfileDictionary | None = None) -> PlanningResult

Plan freespace motion.

Uses TrajOpt for collision-free point-to-point motion.

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program or CompositeInstruction

required
config PlannerConfig | None

Planner configuration

None
profiles ProfileDictionary | None

Custom motion profiles

None

Returns:

Type Description
PlanningResult

PlanningResult with trajectory if successful

Example

from tesseract_robotics.planning import ( Robot, MotionProgram, JointTarget, plan_freespace )

robot = Robot.from_tesseract_support("abb_irb2400") program = (MotionProgram("manipulator") .move_to(JointTarget([0, 0, 0, 0, 0, 0])) .move_to(JointTarget([0.5, 0, 0, 0, 0, 0])) )

result = plan_freespace(robot, program) if result: for point in result: print(point.positions)

plan_ompl

Python
plan_ompl(robot: Robot, program: MotionProgram | CompositeInstruction, config: PlannerConfig | None = None, profiles: ProfileDictionary | None = None) -> PlanningResult

Plan freespace motion using OMPL sampling-based planners.

Uses OMPL (RRT, RRT*, PRM, etc.) for collision-free motion planning. Good for complex environments where optimization-based planners may get stuck in local minima.

Parameters:

Name Type Description Default
robot Robot

Robot instance

required
program MotionProgram | CompositeInstruction

Motion program or CompositeInstruction

required
config PlannerConfig | None

Planner configuration

None
profiles ProfileDictionary | None

Custom motion profiles

None

Returns:

Type Description
PlanningResult

PlanningResult with trajectory if successful

Example

from tesseract_robotics.planning import ( Robot, MotionProgram, JointTarget, plan_ompl )

robot = Robot.from_tesseract_support("abb_irb2400") program = (MotionProgram("manipulator") .move_to(JointTarget([0, 0, 0, 0, 0, 0])) .move_to(JointTarget([0.5, 0.5, 0.5, 0, 0, 0])) )

result = plan_ompl(robot, program) if result: for point in result: print(point.positions)

create_cartesian_pipeline_profiles

Python
create_cartesian_pipeline_profiles(profile_names: list[str] | None = None, num_threads: int | None = None) -> ProfileDictionary

Create profiles for CartesianPipeline (Descartes + TrajOpt).

The CartesianPipeline handles motion with Cartesian (tool pose) constraints: 1. Descartes samples IK solutions and finds minimum-cost joint path 2. TrajOpt optimizes the path for smoothness and collision margins

This is ideal for tasks with tool orientation constraints (welding, painting, milling, etc.) where the tool must follow a specific Cartesian path.

Pipeline Flow

Input: Cartesian waypoints (tool poses) -> Descartes: Sample IK solutions at each waypoint -> Descartes: Find minimum-cost path through ladder graph -> TrajOpt: Optimize path for smoothness + collision margins -> Output: Smooth trajectory following Cartesian path

Parameters:

Name Type Description Default
profile_names list[str] | None

Profile names to register (default: STANDARD_PROFILE_NAMES) Standard names: ["DEFAULT", "FREESPACE", "CARTESIAN", "RASTER", "UPRIGHT"]

None
num_threads int | None

Number of Descartes solver threads (default: CPU count) More threads = faster graph search for long paths

None

Returns:

Type Description
ProfileDictionary

ProfileDictionary with both Descartes and TrajOpt profiles

Usage

from tesseract_robotics.planning.profiles import ( create_cartesian_pipeline_profiles )

Standard Cartesian planning

profiles = create_cartesian_pipeline_profiles()

Custom thread count for large raster paths

profiles = create_cartesian_pipeline_profiles( num_threads=8 )

create_descartes_default_profiles

Python
create_descartes_default_profiles(profile_names: list[str] | None = None, enable_collision: bool = True, enable_edge_collision: bool = False, num_threads: int | None = None) -> ProfileDictionary

Create Descartes profiles with sensible defaults.

Descartes is a Cartesian path planner that uses a ladder graph approach to find joint configurations for Cartesian waypoints. It samples IK solutions at each waypoint and finds the minimum-cost path through the graph.

Creates both plan profiles (waypoint sampling) and solver profiles (ladder graph solver configuration).

Profile Configuration

Plan Profile: - enable_collision: Check vertex (waypoint) collisions - enable_edge_collision: Check edge (transition) collisions

Solver Profile: - num_threads: Parallel graph solver threads (default: all CPUs)

Parameters:

Name Type Description Default
profile_names list[str] | None

Profile names to register (default: DESCARTES_PROFILE_NAMES) Relevant names: ["DEFAULT", "CARTESIAN", "RASTER"] (Descartes doesn't apply to freespace tasks)

None
enable_collision bool

Enable vertex collision checking (default: True) Checks each waypoint configuration for collisions

True
enable_edge_collision bool

Enable edge collision checking (default: False) Checks transitions between waypoints for collisions Warning: Significantly slower, use only if needed

False
num_threads int | None

Number of threads for solver (default: CPU count) More threads = faster graph search

None

Returns:

Type Description
ProfileDictionary

ProfileDictionary with configured Descartes profiles

Usage

from tesseract_robotics.planning.profiles import ( create_descartes_default_profiles )

Standard configuration

profiles = create_descartes_default_profiles()

With edge collision checking (slower but safer)

profiles = create_descartes_default_profiles( enable_edge_collision=True )

Custom thread count

profiles = create_descartes_default_profiles( num_threads=4 )

create_freespace_pipeline_profiles

Python
create_freespace_pipeline_profiles(profile_names: list[str] | None = None, num_planners: int | None = None, planning_time: float = 10.0, optimize: bool = True, max_solutions: int = 10, planner_range: float = 0.0) -> ProfileDictionary

Create profiles for FreespacePipeline (OMPL + TrajOpt).

The FreespacePipeline is a two-stage approach for collision-free motion: 1. OMPL finds a feasible collision-free path (fast, approximate) 2. TrajOpt optimizes the path for smoothness and exact collision margins

This combines the strengths of sampling-based planning (global search) and optimization-based planning (solution quality).

Pipeline Flow

Input: Start/goal joint states -> OMPL: Parallel RRTConnect planners find collision-free path -> TrajOpt: Optimize path for smoothness + collision margins -> Output: Smooth, collision-free trajectory

Parameters:

Name Type Description Default
profile_names list[str] | None

Profile names to register (default: STANDARD_PROFILE_NAMES) Standard names: ["DEFAULT", "FREESPACE", "CARTESIAN", "RASTER", "UPRIGHT"]

None
num_planners int | None

Number of parallel OMPL planners (default: CPU count) More planners = higher success rate for difficult problems

None
planning_time float

OMPL planning time in seconds (default: 10.0) TrajOpt has no timeout (runs until convergence)

10.0
optimize bool

Continue planning to find better solutions (default: True) If True, runs for full planning_time to improve solution quality If False, returns first valid solution (faster, shows parallel speedup)

True
max_solutions int

Stop early after finding this many solutions (default: 10)

10

Returns:

Type Description
ProfileDictionary

ProfileDictionary with both OMPL and TrajOpt profiles

Usage

from tesseract_robotics.planning.profiles import ( create_freespace_pipeline_profiles )

Standard freespace planning

profiles = create_freespace_pipeline_profiles()

Difficult environments: more time + parallelism

profiles = create_freespace_pipeline_profiles( planning_time=10.0, num_planners=16 )

create_iterative_spline_parameterization

Python
create_iterative_spline_parameterization(add_points: bool = True)

Create Iterative Spline Parameterization (ISP).

ISP iteratively fits a spline to the trajectory while respecting velocity, acceleration, and jerk limits. Generally faster than TOTG but may produce slower trajectories.

Parameters:

Name Type Description Default
add_points bool

Whether to add intermediate points (default: True) If True, adds waypoints between existing ones to better satisfy constraints. If False, only uses existing waypoints (faster but may violate limits).

True

Returns:

Type Description

IterativeSplineParameterization instance

Usage

from tesseract_robotics.planning.profiles import ( create_iterative_spline_parameterization ) from tesseract_robotics.tesseract_time_parameterization import ( InstructionsTrajectory )

Create time parameterization

isp = create_iterative_spline_parameterization(add_points=True)

Apply to trajectory

trajectory = InstructionsTrajectory(program) success = isp.compute( trajectory, velocity_limits, acceleration_limits, jerk_limits )

Note

ISP is typically faster to compute than TOTG, but TOTG produces time-optimal trajectories. Use ISP when computation speed matters more than trajectory time.

create_ompl_default_profiles

Python
create_ompl_default_profiles(profile_names: list[str] | None = None, planning_time: float = 10.0, max_solutions: int = 10, optimize: bool = True, simplify: bool = False, num_planners: int | None = None, planner_range: float = 0.0) -> ProfileDictionary

Create OMPL profiles with sensible defaults.

OMPL (Open Motion Planning Library) provides sampling-based motion planners that search the configuration space for collision-free paths. This function creates profiles configured with parallel RRTConnect planners.

Profile Configuration

  • Parallel RRTConnect planners (one per CPU by default)
  • Planning runs until timeout OR max_solutions found
  • Optimization enabled to improve solution quality
  • Simplification disabled (preserves waypoints)

Parameters:

Name Type Description Default
profile_names list[str] | None

Profile names to register (default: OMPL_PROFILE_NAMES) Relevant names: ["DEFAULT", "FREESPACE"] (OMPL doesn't apply to Cartesian/Raster/Upright tasks)

None
planning_time float

Max planning time in seconds (default: 10.0) Total time budget for all parallel planners

10.0
max_solutions int

Max solutions to find before exiting (default: 10) Stops early if this many solutions found

10
optimize bool

Use all planning time to optimize trajectory (default: True) If True, continues improving solution until timeout If False, stops at first solution

True
simplify bool

Simplify trajectory after planning (default: False) If True, removes waypoints (may violate constraints) If False, preserves all waypoints

False
num_planners int | None

Number of parallel RRTConnect planners (default: min(4, CPU count)) More planners = higher chance of finding solution quickly

None

Returns:

Type Description
ProfileDictionary

ProfileDictionary with configured OMPL profiles

Usage

from tesseract_robotics.planning.profiles import ( create_ompl_default_profiles )

Quick planning with defaults

profiles = create_ompl_default_profiles()

Custom planning time and parallelism

profiles = create_ompl_default_profiles( planning_time=10.0, num_planners=8 )

Fast first-solution mode

profiles = create_ompl_default_profiles( planning_time=2.0, optimize=False, max_solutions=1 )

create_ompl_planner_configurators

Python
create_ompl_planner_configurators(planners: list[str] | None = None, num_planners: int | None = None, **kwargs) -> list

Create OMPL planner configurators with custom parameters.

Supports multiple planner types with their specific parameters: - RRTConnect: range (default: 0.0 = auto) - RRTstar: range, goal_bias (0.05), delay_collision_checking (True) - SBL: range (default: 0.0 = auto)

Parameters:

Name Type Description Default
planners list[str] | None

List of planner names (default: ["RRTConnect"]) Supported: "RRTConnect", "RRTstar", "SBL"

None
num_planners int | None

Number of instances per planner type (default: 1) Use multiple instances for parallel planning

None
**kwargs

Planner-specific parameters: range: Step size for tree extension (0.0 = auto) goal_bias: Probability of sampling goal (RRTstar only) delay_collision_checking: Delay collision checks (RRTstar only)

{}

Returns:

Type Description
list

List of configured OMPLPlannerConfigurator instances

Example

Single RRTConnect with default settings

planners = create_ompl_planner_configurators()

Multiple parallel RRTConnect planners

planners = create_ompl_planner_configurators( planners=["RRTConnect"], num_planners=4 )

Mix of planner types with custom parameters

planners = create_ompl_planner_configurators( planners=["RRTConnect", "RRTstar"], num_planners=2, range=0.1, goal_bias=0.1, delay_collision_checking=False )

create_time_optimal_parameterization

Python
create_time_optimal_parameterization(path_tolerance: float = 0.1, min_angle_change: float = 0.001)

Create Time-Optimal Trajectory Generation (TOTG) parameterization.

TOTG finds the time-optimal trajectory that respects velocity, acceleration, and jerk limits. It uses a numerical integration approach to find the fastest trajectory along a given geometric path.

Parameters:

Name Type Description Default
path_tolerance float

Path deviation tolerance in radians (default: 0.1) Controls how closely the time-parameterized trajectory follows the original path. Smaller values = closer following but slower.

0.1
min_angle_change float

Minimum angle change in radians (default: 0.001) Used to detect linear segments vs curves. Smaller values = more sensitive curve detection.

0.001

Returns:

Type Description

TimeOptimalTrajectoryGeneration instance

Usage

from tesseract_robotics.planning.profiles import ( create_time_optimal_parameterization ) from tesseract_robotics.tesseract_time_parameterization import ( InstructionsTrajectory )

Create time parameterization

totg = create_time_optimal_parameterization(path_tolerance=0.05)

Apply to trajectory

trajectory = InstructionsTrajectory(program) success = totg.compute( trajectory, velocity_limits, acceleration_limits, jerk_limits )

Reference

Kunz & Stilman, "Time-Optimal Trajectory Generation for Path Following with Bounded Acceleration and Velocity", RSS 2012

create_trajopt_default_profiles

Python
create_trajopt_default_profiles(profile_names: list[str] | None = None) -> ProfileDictionary

Create TrajOpt profiles matching C++ example defaults.

This creates profiles with collision and cost/constraint settings that match the tesseract_examples C++ code (car_seat_example.cpp, etc.).

TrajOpt uses Sequential Convex Optimization (SCO) to optimize trajectories by minimizing costs (smoothness, collision distance) while satisfying constraints (joint limits, collision avoidance, waypoint targets).

Profile Configuration (0.33 API): Composite Profile (applies to entire trajectory): - collision_constraint: margin=0.00, collision_margin_buffer=0.005, coeff=10 - collision_cost: margin=0.005, collision_margin_buffer=0.01, coeff=50

Text Only
Plan Profile (applies per waypoint):
- cartesian_constraint: enabled (enforce Cartesian targets exactly)
- joint_constraint: enabled (enforce joint targets exactly)
- cartesian_cost: disabled (no soft Cartesian costs)
- joint_cost: disabled (no soft joint costs)

Parameters:

Name Type Description Default
profile_names list[str] | None

Profile names to register (default: TRAJOPT_PROFILE_NAMES) Standard names: ["DEFAULT", "FREESPACE", "CARTESIAN", "RASTER", "UPRIGHT"]

None

Returns:

Type Description
ProfileDictionary

ProfileDictionary with configured TrajOpt profiles

Usage

from tesseract_robotics.planning.profiles import ( create_trajopt_default_profiles )

Create profiles with standard names

profiles = create_trajopt_default_profiles()

Or specify custom profile names

profiles = create_trajopt_default_profiles( profile_names=["MY_PROFILE"] )

create_trajopt_ifopt_default_profiles

Python
create_trajopt_ifopt_default_profiles(profile_names: list[str] | None = None) -> ProfileDictionary

Create TrajOptIfopt profiles matching C++ example defaults.

TrajOptIfopt uses Sequential Quadratic Programming (SQP) with OSQP solver to optimize trajectories. It provides a modern alternative to the original TrajOpt implementation using the IFOPT interface.

Profile Configuration

Composite Profile (applies to entire trajectory): - smooth_velocities: True (penalize velocity changes) - smooth_accelerations: False - smooth_jerks: False

Plan Profile (applies per waypoint): - cartesian_constraint: enabled (enforce Cartesian targets exactly) - joint_constraint: enabled (enforce joint targets exactly)

Solver Profile (OSQP configuration): - Uses default OSQP settings for QP solving

Parameters:

Name Type Description Default
profile_names list[str] | None

Profile names to register (default: TRAJOPT_PROFILE_NAMES) Standard names: ["DEFAULT", "FREESPACE", "CARTESIAN", "RASTER", "UPRIGHT"]

None

Returns:

Type Description
ProfileDictionary

ProfileDictionary with configured TrajOptIfopt profiles

Usage

from tesseract_robotics.planning.profiles import ( create_trajopt_ifopt_default_profiles )

Create profiles with standard names

profiles = create_trajopt_ifopt_default_profiles()

Use with TrajOptIfoptPipeline

result = composer.plan(robot, program, pipeline='TrajOptIfoptPipeline', profiles=profiles)

rotation_from_axis_angle

Python
rotation_from_axis_angle(axis: ArrayLike, angle: float) -> Pose

Create pure rotation from axis-angle representation.

Parameters:

Name Type Description Default
axis ArrayLike

[ax, ay, az] unit axis of rotation

required
angle float

rotation angle in radians

required

rotation_from_quaternion

Python
rotation_from_quaternion(qx: float, qy: float, qz: float, qw: float) -> Pose

Create pure rotation from quaternion (scalar-last: qx, qy, qz, qw).

rotation_x

Python
rotation_x(angle: float) -> Pose

Create rotation around X axis (radians).

rotation_y

Python
rotation_y(angle: float) -> Pose

Create rotation around Y axis (radians).

rotation_z

Python
rotation_z(angle: float) -> Pose

Create rotation around Z axis (radians).

translation

Python
translation(x: float, y: float, z: float) -> Pose

Create pure translation pose.

Classes

Robot

The main entry point for working with a robot.

Python
from tesseract_robotics.planning import Robot

# Load from bundled models
robot = Robot.from_tesseract_support("abb_irb2400")

# Load from URDF/SRDF
robot = Robot.from_urdf("robot.urdf", "robot.srdf")

# Access environment
env = robot.env

# Forward kinematics
pose = robot.fk(joints, group="manipulator")

# Inverse kinematics
solutions = robot.ik(target_pose, group="manipulator")

# Collision checking
is_safe = robot.check_collision(joints)
contacts = robot.get_contacts(joints)

Methods

Method Description
from_tesseract_support(name) Load bundled robot model
from_urdf(urdf, srdf) Load from URDF/SRDF files
fk(joints, group) Forward kinematics
ik(pose, group, seed) Inverse kinematics
check_collision(joints) Collision check (bool)
get_contacts(joints) Detailed collision info
get_joint_names(group) Joint names for group
get_joint_limits(group) Position/velocity limits

Planner

Motion planner wrapper.

Python
from tesseract_robotics.planning import Planner

planner = Planner(robot)

# Joint-space planning
trajectory = planner.plan(
    start=start_joints,
    goal=goal_joints,
    planner="ompl"
)

# Cartesian planning
trajectory = planner.plan(
    start=start_joints,
    goal=goal_pose,  # Isometry3d
    planner="trajopt"
)

# Refine existing trajectory
smooth = planner.refine(trajectory, planner="trajopt")

Parameters

Parameter Type Description
start np.ndarray Start joint configuration
goal np.ndarray or Isometry3d Goal (joint or Cartesian)
planner str Planner type: ompl, trajopt, descartes, simple
profile str Profile name (default: "DEFAULT")

Composer

Task composition for complex sequences.

Python
from tesseract_robotics.planning import Composer

composer = Composer(robot)

# Add motion segments
composer.add_freespace(goal_joints=via_point)
composer.add_cartesian(goal_pose=target_pose)
composer.add_linear(goal_joints=final_joints)

# Plan all segments
result = composer.plan()

if result.success:
    trajectories = result.get_trajectories()

Methods

Method Description
add_freespace(goal_joints) Add freespace motion
add_cartesian(goal_pose) Add Cartesian motion
add_linear(goal_pose) Add linear Cartesian motion
clear() Clear all segments
plan() Execute planning pipeline

Trajectory

Planned trajectory result.

Python
if trajectory:
    for waypoint in trajectory:
        print(f"Positions: {waypoint.positions}")
        print(f"Velocities: {waypoint.velocities}")
        print(f"Time: {waypoint.time}")

Attributes

Attribute Type Description
positions np.ndarray Joint positions
velocities np.ndarray Joint velocities
accelerations np.ndarray Joint accelerations
time float Time from start (seconds)

ComposerResult

Result from Composer.plan().

Python
result = composer.plan()

if result.success:
    print(f"Planned {len(result.get_trajectories())} segments")
else:
    print(f"Failed: {result.message}")

Attributes

Attribute Type Description
success bool Planning succeeded
message str Error message if failed
raw_results object Raw TaskComposer output

Methods

Method Returns Description
get_trajectories() list[Trajectory] Extract trajectories

Enums

PlannerType

Python
from tesseract_robotics.planning import PlannerType

PlannerType.OMPL       # Sampling-based (OMPL)
PlannerType.TRAJOPT    # Optimization (TrajOpt)
PlannerType.DESCARTES  # Graph search (Descartes)
PlannerType.SIMPLE     # Interpolation

MotionType

Python
from tesseract_robotics.planning import MotionType

MotionType.FREESPACE  # Any collision-free path
MotionType.LINEAR     # Straight Cartesian line
MotionType.CIRCULAR   # Circular arc