Skip to content

tesseract_robotics.tesseract_motion_planners_descartes

Descartes graph-based Cartesian planner.

Overview

Descartes solves dense Cartesian paths by building a graph of IK solutions and finding the optimal path through it. Best for industrial toolpaths (welding, milling) where every waypoint must be reached.

Python
from tesseract_robotics.tesseract_motion_planners_descartes import (
    DescartesMotionPlannerD,
    DescartesDefaultPlanProfileD,
    DescartesLadderGraphSolverProfileD,
)

DescartesMotionPlannerD

Python
from tesseract_robotics.tesseract_motion_planners_descartes import DescartesMotionPlannerD
from tesseract_robotics.tesseract_motion_planners import PlannerRequest

planner = DescartesMotionPlannerD()

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

response = planner.solve(request)

Profiles

DescartesDefaultPlanProfileD

Per-waypoint configuration.

Python
from tesseract_robotics.tesseract_motion_planners_descartes import DescartesDefaultPlanProfileD

profile = DescartesDefaultPlanProfileD()

# Target pose sampler settings
# Configure how many IK solutions to sample per waypoint

DescartesLadderGraphSolverProfileD

Solver configuration for the ladder graph.

Python
from tesseract_robotics.tesseract_motion_planners_descartes import DescartesLadderGraphSolverProfileD

profile = DescartesLadderGraphSolverProfileD()

# Graph construction and search settings

How It Works

  1. Sample waypoints: For each Cartesian waypoint, compute all IK solutions
  2. Build graph: Create nodes for each solution, edges between consecutive waypoints
  3. Edge costs: Based on joint motion between solutions
  4. Find path: Dijkstra's algorithm finds minimum-cost path
Text Only
Waypoint 1      Waypoint 2      Waypoint 3
    ○──────────────○──────────────○
    │              │              │
    ○──────────────○──────────────○
    │              │              │
    ○──────────────○──────────────○
   (IK solutions)

Use Cases

  • Welding: Dense linear paths with tool orientation constraints
  • Milling: Toolpaths from CAM software
  • Painting: Spray patterns with coverage requirements
  • Inspection: Camera positioning paths

Limitations

  • Computationally expensive: O(n × k²) where n=waypoints, k=IK solutions
  • Requires IK solutions: Won't work if waypoints are unreachable
  • No obstacle avoidance: Use with collision checking post-filter

Tips

  1. Use for dense Cartesian paths where every point matters
  2. Combine with TrajOpt for smoothing afterward
  3. Reduce waypoint density if planning is too slow
  4. Check reachability before planning - Descartes fails if any waypoint is unreachable

Auto-generated API Reference

DescartesPlanProfileD module-attribute

Python
DescartesPlanProfileD: TypeAlias = DescartesMoveProfileD

DescartesDefaultPlanProfileD module-attribute

Python
DescartesDefaultPlanProfileD: TypeAlias = DescartesDefaultMoveProfileD

DescartesSolverProfileD

Bases: Profile

getKey

Python
getKey() -> int

getStaticKey staticmethod

Python
getStaticKey() -> int

DescartesLadderGraphSolverProfileD

Bases: DescartesSolverProfileD

num_threads property writable

Python
num_threads: int

Number of threads to use during planning (default: 1)

__init__

Python
__init__() -> None

DescartesMoveProfileD

Bases: Profile

getKey

Python
getKey() -> int

getStaticKey staticmethod

Python
getStaticKey() -> int

DescartesDefaultMoveProfileD

Bases: DescartesMoveProfileD

target_pose_fixed property writable

Python
target_pose_fixed: bool

target_pose_sample_axis property writable

Python
target_pose_sample_axis: Annotated[NDArray[float64], dict(shape=3, order=C)]

target_pose_sample_resolution property writable

Python
target_pose_sample_resolution: float

target_pose_sample_min property writable

Python
target_pose_sample_min: float

target_pose_sample_max property writable

Python
target_pose_sample_max: float

manipulator_ik_solver property writable

Python
manipulator_ik_solver: str

allow_collision property writable

Python
allow_collision: bool

enable_collision property writable

Python
enable_collision: bool

vertex_collision_check_config property writable

Python
vertex_collision_check_config: CollisionCheckConfig

enable_edge_collision property writable

Python
enable_edge_collision: bool

edge_collision_check_config property writable

Python
edge_collision_check_config: CollisionCheckConfig

use_redundant_joint_solutions property writable

Python
use_redundant_joint_solutions: bool

debug property writable

Python
debug: bool

__init__

Python
__init__() -> None

DescartesMotionPlannerD

__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

cast_DescartesSolverProfileD

Python
cast_DescartesSolverProfileD(profile: DescartesLadderGraphSolverProfileD) -> tesseract_robotics.tesseract_command_language._tesseract_command_language.Profile

Cast DescartesLadderGraphSolverProfileD to Profile for use with ProfileDictionary

cast_DescartesMoveProfileD

Python
cast_DescartesMoveProfileD(profile: DescartesDefaultMoveProfileD) -> tesseract_robotics.tesseract_command_language._tesseract_command_language.Profile

Cast DescartesDefaultMoveProfileD to Profile for use with ProfileDictionary

cast_DescartesPlanProfileD

Python
cast_DescartesPlanProfileD(profile: DescartesDefaultMoveProfileD) -> tesseract_robotics.tesseract_command_language._tesseract_command_language.Profile

Cast DescartesDefaultPlanProfileD to Profile (legacy alias)