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¶
- Sample waypoints: For each Cartesian waypoint, compute all IK solutions
- Build graph: Create nodes for each solution, edges between consecutive waypoints
- Edge costs: Based on joint motion between solutions
- 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¶
- Use for dense Cartesian paths where every point matters
- Combine with TrajOpt for smoothing afterward
- Reduce waypoint density if planning is too slow
- Check reachability before planning - Descartes fails if any waypoint is unreachable
Auto-generated API Reference¶
DescartesPlanProfileD
module-attribute
¶
DescartesDefaultPlanProfileD
module-attribute
¶
DescartesSolverProfileD
¶
DescartesLadderGraphSolverProfileD
¶
Bases: DescartesSolverProfileD
DescartesMoveProfileD
¶
DescartesDefaultMoveProfileD
¶
Bases: DescartesMoveProfileD
DescartesMotionPlannerD
¶
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)