curobo.motion_retargeter module

Retargeter module for motion retargeting.

This module provides IK and MPC-based motion retargeting. Given per-frame tool pose targets, the retargeter produces joint trajectories suitable for humanoid robots.

Example:

from curobo.motion_retargeter import MotionRetargeter, MotionRetargeterCfg
from curobo.types import ToolPoseCriteria

cfg = MotionRetargeterCfg.create(
    robot="unitree_g1_29dof_retarget.yml",
    tool_pose_criteria={
        "pelvis": ToolPoseCriteria.track_position_and_orientation(
            xyz=[1.0, 1.0, 1.0], rpy=[0.5, 0.5, 0.5],
        ),
        "left_hand": ToolPoseCriteria.track_position_and_orientation(
            xyz=[1.0, 1.0, 1.0], rpy=[0.3, 0.3, 0.3],
        ),
        "right_hand": ToolPoseCriteria.track_position_and_orientation(
            xyz=[1.0, 1.0, 1.0], rpy=[0.3, 0.3, 0.3],
        ),
    },
)
retargeter = MotionRetargeter(cfg)
result = retargeter.solve_frame(goal_tool_pose)
class GoalToolPose(
tool_frames,
position,
quaternion,
)

Bases: Sequence

5D goal specification: [batch, horizon, num_links, num_goalset, 3/4].

Used only on the goal/target side. horizon=1 for static goals, horizon>1 for per-timestep targets.

Parameters:
tool_frames: List[str]

Link/frame names, length must equal position.shape[2].

position: torch.Tensor

Position tensor [batch, horizon, num_links, num_goalset, 3].

quaternion: torch.Tensor

Quaternion tensor [batch, horizon, num_links, num_goalset, 4] (wxyz).

property batch_size: int
property horizon: int
property num_goalset: int
property shape
property ndim
property device
classmethod from_poses(
pose_dict,
ordered_tool_frames=None,
num_goalset=1,
)

Build from per-link Pose objects.

Each Pose has position [batch, 3] or [batch * num_goalset, 3].

Return type:

GoalToolPose

Returns:

GoalToolPose [batch, 1, num_links, num_goalset, 3/4] (horizon=1).

Parameters:

Extract a single link as a 2D Pose [B*H*G, 3/4].

Return type:

Pose

Parameters:
  • link_name (str)

  • make_contiguous (bool)

to_dict(
make_contiguous=True,
)
Return type:

Dict[str, Pose]

Parameters:

make_contiguous (bool)

copy_(other)
Parameters:

other (curobo._src.types.tool_pose.GoalToolPose)

requires_grad_(
requires_grad,
)
Parameters:

requires_grad (bool)

clone()
Return type:

GoalToolPose

detach()
Return type:

GoalToolPose

Return type:

GoalToolPose

Parameters:

ordered_tool_frames (List[str])

__init__(
tool_frames,
position,
quaternion,
)
Parameters:
Return type:

None

class MotionRetargeter(config)

Bases: object

IK / MPC-based motion retargeter.

Tracks internal state across calls to solve_frame. The first call uses global IK (many seeds). Subsequent calls use either warm-started local IK or MPC depending on config.use_mpc.

Call reset to clear state and start a new sequence.

Parameters:

config (MotionRetargeterCfg)

__init__(config)
Parameters:

config (curobo._src.motion.motion_retargeter_cfg.MotionRetargeterCfg)

property joint_names: List[str]

Joint names in solver DOF order.

property action_dim: int
property tool_frames: List[str]
property kinematics: curobo._src.robot.kinematics.kinematics.Kinematics
property default_joint_state: curobo._src.state.state_joint.JointState
property num_dof: int

Deprecated alias for action_dim.

property config: curobo._src.motion.motion_retargeter_cfg.MotionRetargeterCfg

Current configuration.

reset()

Clear warm-start state. Next solve_frame uses global IK.

Return type:

None

solve_frame(
goal_tool_poses,
)

Solve one frame of retargeting.

Parameters:

goal_tool_poses (GoalToolPose) – Target poses for tracked links. Position shape (num_envs, 1, num_links, num_goalset, 3), quaternion wxyz shape (num_envs, 1, num_links, num_goalset, 4).

Return type:

RetargetResult

Returns:

RetargetResult with joint_state shape (num_envs, num_dof) and optional MPC trajectory.

Raises:

ValueError – If goal_tool_poses batch size does not match num_envs from the config.

solve_sequence(
tool_poses,
)

Solve a full sequence of retargeting targets.

Parameters:

tool_poses (SequenceGoalToolPose) – Sequence of goal tool poses with shape (num_frames, num_envs, num_links, num_goalset, 3/4).

Return type:

RetargetResult

Returns:

RetargetResult with joint_state position shape (num_envs, num_output_frames, num_dof) and optional stacked MPC trajectory.

Raises:

ValueError – If tool_poses.num_envs does not match num_envs from the config.

class MotionRetargeterCfg(
robot,
tool_pose_criteria,
num_envs=1,
use_mpc=False,
self_collision_check=True,
scene_model=None,
optimization_dt=0.05,
num_seeds_global=64,
position_tolerance=0.005,
orientation_tolerance=0.05,
device_cfg=<factory>,
load_collision_spheres=True,
ik_optimizer_configs=<factory>,
mpc_optimizer_configs=<factory>,
num_seeds_local=1,
num_control_points=None,
steps_per_target=8,
velocity_regularization_weight=None,
acceleration_regularization_weight=None,
collision_activation_distance=0.01,
global_ik_num_iters=None,
local_ik_num_iters=None,
mpc_warm_start_num_iters=100,
mpc_cold_start_num_iters=300,
)

Bases: object

Configuration for MotionRetargeter.

Use create to construct from simple arguments.

Parameters:
robot: str | Dict[str, Any]

Robot config YAML filename or dict.

tool_pose_criteria: Dict[str, curobo._src.cost.tool_pose_criteria.ToolPoseCriteria]

Dict of link name to ToolPoseCriteria. Each entry sets independent position (xyz) and rotation (rpy) weights for a tracked link. Use high weights (1.0) on feet/pelvis for balance and lower weights on mid-chain links like shoulders.

num_envs: int = 1

number of clips retargeted in parallel on GPU. Shorter clips are padded by repeating the last frame’s target. Increase to saturate GPU throughput when retargeting many clips.

Type:

Batch size

use_mpc: bool = False

Use MPC for frames 1+ instead of warm-started IK. MPC produces smoother trajectories (acceleration/jerk costs) but is 2-4x slower per frame.

self_collision_check: bool = True

Enable self-collision avoidance. Disabling speeds up solving but may produce interpenetrating limbs.

scene_model: str | Dict[str, Any] | None = None

Scene config (YAML or dict) for environment collision checking (ground plane, obstacles). None disables scene collision.

optimization_dt: float = 0.05

Time step (seconds) for velocity-limited IK or MPC. Decreasing enforces tighter velocity limits, producing smoother but potentially less accurate tracking. Increasing allows larger per-frame jumps.

num_seeds_global: int = 64

Random seeds for frame-0 global IK. Increasing explores more of the configuration space (better initial pose) at the cost of longer first-frame solve time. Decreasing speeds up initialization but may land in a poor local minimum.

position_tolerance: float = 0.005

Position convergence tolerance in meters. The solver stops early if all links are within this threshold. Tightening (e.g. 0.001) improves accuracy but may use more iterations. Loosening (e.g. 0.01) speeds up solving.

orientation_tolerance: float = 0.05

Orientation convergence tolerance in radians. Same trade-off as position_tolerance.

device_cfg: curobo._src.types.device_cfg.DeviceCfg

Device and dtype configuration.

load_collision_spheres: bool = True

Load collision spheres for the robot. Auto-disabled when both self_collision_check=False and scene_model=None. Set to False explicitly for faster initialization when collision checking is not needed.

ik_optimizer_configs: List[str | Dict[str, Any]]

Override the IK optimizer YAML config. The default runs 200 L-BFGS iterations.

mpc_optimizer_configs: List[str | Dict[str, Any]]

Override the MPC optimizer YAML config. The default runs 100 L-BFGS iterations. Ignored when use_mpc=False.

num_seeds_local: int = 1

Seeds for warm-started local IK. Ignored when use_mpc=True.

num_control_points: int | None = None

B-spline control points for MPC trajectory parameterization. More points allow the trajectory to represent higher-frequency motion but increase the optimization problem size. Ignored when use_mpc=False.

steps_per_target: int = 8

MPC optimization steps per input target frame. Increasing improves tracking quality and smoothness. Decreasing speeds up solving but pose reaching error will be higher. Ignored when use_mpc=False.

velocity_regularization_weight: float | None = None

Penalizes (q - q_prev) / dt. None uses the YAML default (0.001 for IK). Increasing produces smoother joint velocities but the solver may lag behind fast-moving targets.

acceleration_regularization_weight: float | None = None

Penalizes (v - v_prev) / dt. None uses the YAML default (0.01 for IK). Increasing produces smoother accelerations, particularly impactful in MPC mode.

collision_activation_distance: float = 0.01

Activation distance [m] for collision cost. Collision penalties begin ramping when sphere surfaces are within this distance. Increasing creates a wider safety margin around obstacles but may reduce tracking accuracy in tight spaces.

global_ik_num_iters: int | None = None

L-BFGS iterations for frame-0 global IK (cold start, many seeds). None uses the optimizer YAML default (200 for lbfgs_retarget_ik.yml). Increasing explores more thoroughly at the cost of longer first-frame time.

local_ik_num_iters: int | None = None

L-BFGS iterations for warm-started local IK (frames 1+). None uses the optimizer YAML default (200 for lbfgs_retarget_ik.yml). Can often be reduced (e.g. 100) since warm-starting provides a good seed. Ignored when use_mpc=True.

mpc_warm_start_num_iters: int = 100

Optimizer iterations for warm-started MPC steps (frames 1+). Ignored when use_mpc=False.

mpc_cold_start_num_iters: int = 300

Optimizer iterations for the first MPC step (cold start, no warm start). Should be >= mpc_warm_start_num_iters. Ignored when use_mpc=False.

property tool_frames: List[str]

Ordered list of tool frame link names (derived from criteria keys).

static create(
robot,
tool_pose_criteria,
num_envs=1,
use_mpc=False,
self_collision_check=True,
scene_model=None,
optimization_dt=0.05,
num_seeds_global=64,
load_collision_spheres=True,
ik_optimizer_configs=None,
mpc_optimizer_configs=None,
num_seeds_local=1,
num_control_points=12,
steps_per_target=4,
position_tolerance=0.005,
orientation_tolerance=0.05,
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),
velocity_regularization_weight=None,
acceleration_regularization_weight=None,
collision_activation_distance=0.01,
global_ik_num_iters=None,
local_ik_num_iters=None,
mpc_warm_start_num_iters=100,
mpc_cold_start_num_iters=300,
)

Create a MotionRetargeterCfg from simple arguments.

Return type:

MotionRetargeterCfg

Parameters:
__init__(
robot,
tool_pose_criteria,
num_envs=1,
use_mpc=False,
self_collision_check=True,
scene_model=None,
optimization_dt=0.05,
num_seeds_global=64,
position_tolerance=0.005,
orientation_tolerance=0.05,
device_cfg=<factory>,
load_collision_spheres=True,
ik_optimizer_configs=<factory>,
mpc_optimizer_configs=<factory>,
num_seeds_local=1,
num_control_points=None,
steps_per_target=8,
velocity_regularization_weight=None,
acceleration_regularization_weight=None,
collision_activation_distance=0.01,
global_ik_num_iters=None,
local_ik_num_iters=None,
mpc_warm_start_num_iters=100,
mpc_cold_start_num_iters=300,
)
Parameters:
Return type:

None

class RetargetResult(
joint_state,
trajectory=None,
)

Bases: object

Result returned by MotionRetargeter.solve_frame and MotionRetargeter.solve_sequence.

For solve_frame, shapes have no time dimension. For solve_sequence, joint_state is stacked over frames.

Parameters:
joint_state: curobo._src.state.state_joint.JointState

position shape (num_envs, num_dof). For solve_sequence: position shape (num_envs, num_output_frames, num_dof).

Type:

Final joint state. For solve_frame

trajectory: curobo._src.state.state_joint.JointState | None = None

Full intermediate MPC trajectory (MPC mode only, None for IK mode). For solve_frame: position shape (num_envs, num_intermediate_frames, num_dof). For solve_sequence: position shape (num_envs, total_intermediate_frames, num_dof).

__init__(
joint_state,
trajectory=None,
)
Parameters:
Return type:

None

class SequenceGoalToolPose(
tool_frames,
position,
quaternion,
)

Bases: object

Time-series of goal tool poses for batch offline retargeting.

Layout is (num_frames, num_envs, num_links, num_goalset, 3/4), time-first for per-frame contiguity. get_frame converts a single timestep to a GoalToolPose with horizon=1.

Parameters:
tool_frames: List[str]

Link names matching dim 2 of position/quaternion.

position: torch.Tensor

(num_frames, num_envs, num_links, num_goalset, 3).

quaternion: torch.Tensor

(num_frames, num_envs, num_links, num_goalset, 4) wxyz convention.

property num_frames: int
property num_envs: int
property num_goalset: int
get_frame(t)

Return frame t as a GoalToolPose (view, no copy).

Return type:

GoalToolPose

Returns:

GoalToolPose [num_envs, 1, num_links, num_goalset, 3/4] (horizon=1).

Parameters:

t (int)

clone()
Return type:

SequenceGoalToolPose

property device: torch.device
__init__(
tool_frames,
position,
quaternion,
)
Parameters:
Return type:

None