curobo.motion_planner module

Motion planning module.

This module provides high-level motion planning combining trajectory optimization and graph planning.

Example

```python from curobo import MotionPlanner, MotionPlannerCfg

config = MotionPlannerCfg.create(robot=”franka.yml”) planner = MotionPlanner(config) result = planner.plan_pose(goal_tool_poses, current_state) ```

class MotionPlanner(config)

Bases: object

Single-problem motion planner with retry logic and graph-planner seeding.

Solves one planning problem at a time (batch_size=1). For batched planning see BatchMotionPlanner.

Parameters:

config (MotionPlannerCfg)

__init__(config)
Parameters:

config (curobo._src.motion.motion_planner_cfg.MotionPlannerCfg)

destroy()

Release all CUDA graph resources.

Call before dropping the last reference to avoid cudaMallocAsync warnings about captured allocations freed outside graph replay.

Does not synchronize, the gc.collect() + synchronize() fence in GraphExecutor._initialize_cuda_graph ensures stale cuGraphExecDestroy calls complete before any new capture begins.

property attachment_manager

Attachment manager for attaching/detaching obstacles to robot links.

property joint_names: List[str]
property action_dim: int
property tool_frames: List[str]
property default_joint_state: curobo._src.state.state_joint.JointState
property kinematics: curobo._src.robot.kinematics.kinematics.Kinematics
compute_kinematics(state)
Return type:

KinematicsState

Parameters:

state (curobo._src.state.state_joint.JointState)

warmup(
enable_graph=True,
warmup_joint_index=0,
warmup_joint_delta=0.2,
num_warmup_iterations=10,
)
Return type:

bool

Parameters:
  • enable_graph (bool)

  • warmup_joint_index (int)

  • warmup_joint_delta (float)

  • num_warmup_iterations (int)

plan_pose(
goal_tool_poses,
current_state,
use_implicit_goal=True,
max_attempts=5,
enable_graph_attempt=1,
)

Plan a trajectory to reach target tool poses.

Goalset is auto-detected from goal_tool_poses.num_goalset. When num_goalset > 1 the planner uses a simpler IK+TrajOpt loop without graph seeding.

Return type:

Optional[TrajOptSolverResult]

Parameters:
plan_cspace(
goal_state,
current_state,
max_attempts=5,
enable_graph_attempt=1,
)

Plan a collision-free trajectory to a joint configuration.

Parameters:
  • goal_state (JointState) – Target joint configuration.

  • current_state (JointState) – Initial joint state.

  • max_attempts (int) – Maximum planning attempts.

  • enable_graph_attempt (int) – Attempt at which to start graph seeding.

Return type:

Optional[TrajOptSolverResult]

Returns:

TrajOptSolverResult, or None if planning failed.

plan_grasp(
grasp_poses,
current_state,
grasp_approach_axis='z',
grasp_approach_offset=-0.15,
grasp_approach_in_tool_frame=True,
grasp_lift_axis='z',
grasp_lift_offset=-0.15,
grasp_lift_in_tool_frame=True,
plan_approach_to_grasp=True,
plan_grasp_to_lift=True,
disable_collision_links=None,
)

Plan a grasp motion: goalset -> approach -> grasp -> lift.

Parameters:
  • grasp_poses (GoalToolPose) – Candidate grasp poses with num_goalset entries per link. Construct via GoalToolPose with the desired goalset size.

  • current_state (curobo._src.state.state_joint.JointState)

  • grasp_approach_axis (str)

  • grasp_approach_offset (float)

  • grasp_approach_in_tool_frame (bool)

  • grasp_lift_axis (str)

  • grasp_lift_offset (float)

  • grasp_lift_in_tool_frame (bool)

  • plan_approach_to_grasp (bool)

  • plan_grasp_to_lift (bool)

  • disable_collision_links (List[str])

Return type:

GraspPlanResult

Parameters:

enable_collision_links (List[str])

Parameters:

disable_collision_links (List[str])

update_world(scene_cfg)
Parameters:

scene_cfg (curobo._src.geom.types.SceneCfg)

clear_scene_cache()
reset_seed()
Return type:

None

Parameters:
Return type:

None

Parameters:

link_properties (dict[str, dict[str, float | torch.Tensor]])

update_tool_pose_criteria(
tool_pose_criteria,
)
Parameters:

tool_pose_criteria (Dict[str, curobo._src.cost.tool_pose_criteria.ToolPoseCriteria])

class MotionPlannerCfg(
ik_solver_config,
trajopt_solver_config,
graph_planner_config=None,
scene_collision_cfg=None,
device_cfg=DeviceCfg(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
)

Bases: object

Configuration for the motion planner.

Parameters:
  • ik_solver_config (curobo._src.solver.solver_ik_cfg.IKSolverCfg)

  • trajopt_solver_config (curobo._src.solver.solver_trajopt_cfg.TrajOptSolverCfg)

  • graph_planner_config (curobo._src.graph_planner.graph_planner_prm_cfg.PRMGraphPlannerCfg)

  • scene_collision_cfg (curobo._src.geom.collision.collision_scene.SceneCollisionCfg | None)

  • device_cfg (curobo._src.types.device_cfg.DeviceCfg)

ik_solver_config: curobo._src.solver.solver_ik_cfg.IKSolverCfg
trajopt_solver_config: curobo._src.solver.solver_trajopt_cfg.TrajOptSolverCfg
graph_planner_config: curobo._src.graph_planner.graph_planner_prm_cfg.PRMGraphPlannerCfg = None
scene_collision_cfg: curobo._src.geom.collision.collision_scene.SceneCollisionCfg | None = None
device_cfg: curobo._src.types.device_cfg.DeviceCfg = DeviceCfg(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32)
static create(robot, ik_optimizer_configs=['ik/lbfgs_ik.yml'], ik_transition_model='ik/transition_ik.yml', metrics_rollout='metrics_base.yml', trajopt_optimizer_configs=['trajopt/lbfgs_bspline_trajopt.yml'], trajopt_transition_model='trajopt/transition_bspline_trajopt.yml', graph_planner_config='graph_planner/exact_graph_planner.yml', graph_planner_rollout='metrics_base.yml', graph_planner_transition_model='graph_planner/transition_graph_planner.yml', scene_model=None, collision_cache=None, self_collision_check=True, device_cfg=DeviceCfg(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32), num_ik_seeds=32, num_trajopt_seeds=4, position_tolerance=0.005, orientation_tolerance=0.05, use_cuda_graph=True, random_seed=123, optimizer_collision_activation_distance=0.01, store_debug=False, transition_model_config_instance_type=<class 'curobo._src.transition.robot_state_transition_cfg.RobotStateTransitionCfg'>, cost_manager_config_instance_type=<class 'curobo._src.rollout.cost_manager.cost_manager_robot_cfg.RobotCostManagerCfg'>, max_batch_size=1, multi_env=False, max_goalset=1)

Create MotionPlannerCfg from flexible inputs.

Each config parameter accepts either a file path (str), a dictionary, or an already-constructed config object.

Parameters:
  • robot (Union[str, Dict[str, Any], RobotCfg]) – Robot configuration - path to YAML, dict, or RobotCfg object.

  • ik_optimizer_configs (List[Union[str, Dict[str, Any]]]) – IK optimizer configs - paths or dicts.

  • ik_transition_model (Union[str, Dict[str, Any]]) – IK transition model config - path or dict.

  • metrics_rollout (Union[str, Dict[str, Any]]) – Metrics rollout config - path or dict.

  • trajopt_optimizer_configs (List[Union[str, Dict[str, Any]]]) – Trajectory optimization optimizer configs.

  • trajopt_transition_model (Union[str, Dict[str, Any]]) – Trajectory optimization transition model.

  • graph_planner_config (Union[str, Dict[str, Any]]) – Graph planner config - path or dict.

  • graph_planner_rollout (Union[str, Dict[str, Any]]) – Graph planner rollout config - path or dict.

  • graph_planner_transition_model (Union[str, Dict[str, Any]]) – Graph planner transition model.

  • scene_model (Union[str, Dict[str, Any], None]) – Optional scene model config - path or dict.

  • collision_cache (Optional[Dict[str, int]]) – Cache configuration for collision checking.

  • self_collision_check (bool) – Whether to check self-collision.

  • device_cfg (DeviceCfg) – Device configuration.

  • num_ik_seeds (int) – Number of IK optimization seeds.

  • num_trajopt_seeds (int) – Number of trajectory optimization seeds.

  • position_tolerance (float) – Position tolerance for success.

  • orientation_tolerance (float) – Orientation tolerance for success.

  • use_cuda_graph (bool) – Whether to use CUDA graphs.

  • random_seed (int) – Random seed for reproducibility.

  • optimizer_collision_activation_distance (float) – Collision activation distance.

  • store_debug (bool) – Whether to store debug information.

  • transition_model_config_instance_type (Type[RobotStateTransitionCfg]) – Transition model config class.

  • cost_manager_config_instance_type (Type[RobotCostManagerCfg]) – Cost manager config class.

  • max_batch_size (int) – Maximum number of problems solved in parallel; fewer may be provided (padded internally).

  • multi_env (bool) – When True, each batched problem uses its own collision environment; when False, all share one environment.

  • max_goalset (int) – Maximum goalset size per problem; fewer goals may be provided (padded internally).

Return type:

MotionPlannerCfg

Returns:

Configured MotionPlannerCfg instance.

__init__(
ik_solver_config,
trajopt_solver_config,
graph_planner_config=None,
scene_collision_cfg=None,
device_cfg=DeviceCfg(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
)
Parameters:
  • ik_solver_config (curobo._src.solver.solver_ik_cfg.IKSolverCfg)

  • trajopt_solver_config (curobo._src.solver.solver_trajopt_cfg.TrajOptSolverCfg)

  • graph_planner_config (curobo._src.graph_planner.graph_planner_prm_cfg.PRMGraphPlannerCfg)

  • scene_collision_cfg (curobo._src.geom.collision.collision_scene.SceneCollisionCfg | None)

  • device_cfg (curobo._src.types.device_cfg.DeviceCfg)

Return type:

None

class GraspPlanResult(
success=None,
approach_success=None,
grasp_success=None,
lift_success=None,
approach_trajectory=None,
approach_trajectory_dt=None,
approach_interpolated_trajectory=None,
grasp_trajectory=None,
grasp_trajectory_dt=None,
grasp_interpolated_trajectory=None,
lift_trajectory=None,
lift_trajectory_dt=None,
lift_interpolated_trajectory=None,
approach_interpolated_last_tstep=None,
grasp_interpolated_last_tstep=None,
lift_interpolated_last_tstep=None,
status=None,
planning_time=0.0,
goalset_index=None,
)

Bases: object

Result of a grasp planning operation.

Parameters:
success: torch.Tensor | None = None
approach_success: torch.Tensor | None = None
grasp_success: torch.Tensor | None = None
lift_success: torch.Tensor | None = None
approach_trajectory: curobo._src.state.state_joint.JointState | None = None
approach_trajectory_dt: torch.Tensor | None = None
approach_interpolated_trajectory: curobo._src.state.state_joint.JointState | None = None
grasp_trajectory: curobo._src.state.state_joint.JointState | None = None
grasp_trajectory_dt: torch.Tensor | None = None
grasp_interpolated_trajectory: curobo._src.state.state_joint.JointState | None = None
lift_trajectory: curobo._src.state.state_joint.JointState | None = None
lift_trajectory_dt: torch.Tensor | None = None
lift_interpolated_trajectory: curobo._src.state.state_joint.JointState | None = None
approach_interpolated_last_tstep: torch.Tensor | None = None
grasp_interpolated_last_tstep: torch.Tensor | None = None
lift_interpolated_last_tstep: torch.Tensor | None = None
status: str | None = None
planning_time: float = 0.0
goalset_index: torch.Tensor | None = None
__init__(
success=None,
approach_success=None,
grasp_success=None,
lift_success=None,
approach_trajectory=None,
approach_trajectory_dt=None,
approach_interpolated_trajectory=None,
grasp_trajectory=None,
grasp_trajectory_dt=None,
grasp_interpolated_trajectory=None,
lift_trajectory=None,
lift_trajectory_dt=None,
lift_interpolated_trajectory=None,
approach_interpolated_last_tstep=None,
grasp_interpolated_last_tstep=None,
lift_interpolated_last_tstep=None,
status=None,
planning_time=0.0,
goalset_index=None,
)
Parameters:
Return type:

None