Humanoid Motion Retargeting¶
SOMA adapter for retargeting BVH motion capture to Unitree G1 using cuRobo IK and MPC.
This guide walks through setting up cuRobo for retargeting human motion capture data to a humanoid robot. We use the Unitree G1 29-DOF robot as an example, but the same approach applies to any humanoid with a URDF.
This script is a SOMA adapter that bridges soma_retargeter I/O with the
cuRobo MotionRetargeter API. All solver
logic (IK, MPC, warm-starting) lives in MotionRetargeter; this file
handles only BVH loading, effector conversion, CSV output, and visualization.
What is Motion Retargeting?¶
Motion retargeting transfers a motion from one character (the source) to another (the target) that may have a different body shape, limb proportions, or degrees of freedom. In humanoid robotics, the source is typically a human performer captured via optical motion capture, and the target is a robot. Copying joint angles directly does not work as the source and target have different kinematic structures, limb lengths, joint limits, and degrees of freedom.
Retargeting breaks down into three sub-problems:
Link mapping: which human joint corresponds to which robot link?
Proportion rescaling: rescale and offset the human mocap poses to match the robot’s limb lengths, body proportions, and joint frame conventions.
Solving for joint angles: find robot joint angles at every frame that best reproduce the rescaled target poses while respecting kinematic constraints.
SOMA Retargeter handles all three: it loads a BVH file, applies a per-robot link mapping and per-joint scale factors/pose offsets, and includes its own IK solver for step 3. This guide shows how to replace the IK solver with cuRobo, leveraging GPU-accelerated collision-free trajectory optimization.
How cuRobo Retargets Motion¶
cuRobo sets up an optimization problem to find robot joint angles that best reproduce
the target poses across all N tracked links, subject to joint limits and (optionally)
self-collision avoidance. Each tracked robot link is a tool_frame that receives an
independent pose target. Links can be weighted differently: feet and pelvis get high
position weight to maintain balance, while shoulder rotations get low weight since the
elbow and wrist targets already constrain the arm.
Two-phase solving. Retargeting a motion clip proceeds frame by frame using two phases:
Global IK (frame 0): The first frame has no prior solution, so the solver runs a broad search using many random seeds (default 64) with no velocity limit. This explores the full configuration space to find a good initial pose.
Local solver (frames 1 … N): Each subsequent frame uses the previous frame’s solution as a warm start. This can be either:
Warm-started IK (
use_mpc=False): a single-seed, velocity-limited IK solve that tracks the motion frame by frame.MPC (
use_mpc=True): model predictive control that optimizes a trajectory over a planning horizon, producing smoother results with acceleration and jerk costs.
Warm-starting is what connects isolated per-frame IK solutions into a temporally coherent motion: the solver starts from a configuration that is already close to the answer, and the velocity limit prevents it from jumping to a distant solution even if one has lower cost.
The MotionRetargeter API encapsulates this
two-phase loop. You provide target poses; it manages solver construction,
warm-starting, and mode switching internally.
Step 1: Floating Base via extra_links¶
Humanoid retargeting requires a floating base: the robot’s pelvis moves freely in
space. cuRobo supports this via extra_links with child_link_name in the YAML
config – no URDF modification needed. Six virtual joints (3 prismatic + 3 revolute)
are inserted between base_link and pelvis:
extra_links:
base_link_x:
parent_link_name: base_link
child_link_name: null # chains to next virtual link
joint_name: base_j_x
joint_type: X_PRISM
...
base_link_ztheta:
parent_link_name: base_link_ytheta
child_link_name: pelvis # re-parents pelvis under the virtual chain
joint_name: base_link_ztheta
joint_type: Z_ROT
...
The URDF itself (g1_29dof_rev_1_0.urdf) has a fixed joint from base_link to
pelvis. The virtual chain is injected at load time by the extra_links mechanism.
Mesh paths in the URDF can use either relative paths (e.g.,
meshes/pelvis.STL) or package:// URIs – cuRobo strips the
package:// prefix automatically and resolves the remainder against the
--asset-path directory.
Step 2: Define Tool Frames¶
Each human skeleton joint maps to a robot link, becoming a tool frame in cuRobo’s IK solver. Each tool frame carries an independent position and rotation weight: feet and hips get high weight to maintain balance, while mid-chain links like shoulders get low weight since the elbow and wrist targets already constrain the arm.
This mapping is read automatically from SOMA’s retargeter config via
pipeline_utils.get_retargeter_config(source_type, target_type). To customize the
mapping or weights for a different robot, edit the corresponding SOMA retargeter config
(ik_map section).
Step 3: Build the Robot Configuration¶
Use the build_robot_model script to build the cuRobo config with
collision spheres and the self-collision matrix:
python -m curobo.examples.getting_started.build_robot_model \
--urdf curobo/content/assets/robot/g1/g1_29dof_rev_1_0.urdf \
--asset-path curobo/content/assets/robot/g1 \
--tool-frames \
pelvis torso_link \
left_shoulder_roll_link left_elbow_link left_wrist_yaw_link \
right_shoulder_roll_link right_elbow_link right_wrist_yaw_link \
left_hip_roll_link left_knee_link left_ankle_roll_link \
right_hip_roll_link right_knee_link right_ankle_roll_link \
--output curobo/content/configs/robot/unitree_g1_29dof_retarget.yml \
--visualize
The --visualize flag opens a Viser web viewer (default http://localhost:8080)
where you can inspect the fitted collision spheres.
A pre-built config is included at
curobo/content/configs/robot/unitree_g1_29dof_retarget.yml.
Step 4: Three Levels of Retargeting¶
MotionRetargeter is the high-level API that
implements the two-phase loop described above. You configure it once, then call
solve_sequence (offline) or solve_frame (streaming); it manages solver
construction, warm-starting, and mode switching internally.
Both IK solvers use ik/lbfgs_retarget_ik.yml, a specialized LBFGS optimizer config
tuned for retargeting. The MPC solver uses mpc/lbfgs_retarget_mpc.yml.
Per-link weighting: each tool frame receives independent position and rotation
weights via ToolPoseCriteria, passed
as a dict in MotionRetargeterCfg.tool_pose_criteria.
The same two-phase solver runs at three fidelity levels. Start with Level 1 to get results quickly, then upgrade to the higher levels as needed.
Level |
Mode |
Flag |
Trade-off |
|---|---|---|---|
1 |
IK, no self-collision |
|
Fastest. Robot links may interpenetrate on constrained poses. |
2 |
IK, with self-collision |
|
~10–20 % slower; prevents robot links interpenetration. |
3 |
MPC |
|
2–4× slower; adds trajectory smoothness (acceleration/jerk costs). |
Level 1: IK without Self-Collision¶
The fastest option. Collision spheres are not loaded, so initialization and per-frame solve time are both minimized. Use this level when speed matters more than physical plausibility, or as a first pass to verify the link mapping.
from curobo.motion_retargeter import (
MotionRetargeter,
MotionRetargeterCfg,
SequenceGoalToolPose,
)
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.067, 0.067, 0.067],
),
"left_ankle_roll_link": ToolPoseCriteria.track_position_and_orientation(
xyz=[1.0, 1.0, 1.0], rpy=[0.067, 0.067, 0.067],
),
# ... one entry per tool frame
},
num_envs=1,
self_collision_check=False, # no self-collision
)
retargeter = MotionRetargeter(cfg)
# positions: (num_frames, num_envs, num_links, num_goalset, 3) torch tensor
# quaternions: (num_frames, num_envs, num_links, num_goalset, 4) torch tensor, wxyz convention
seq = SequenceGoalToolPose(
tool_frames=cfg.tool_frames,
position=positions,
quaternion=quaternions,
)
result = retargeter.solve_sequence(seq)
# result.joint_state.position: (num_envs, num_frames, num_dof)
CLI equivalent:
python -m curobo.examples.getting_started.humanoid_retargeting \
--input motion.bvh --output motion.csv \
--no-self-collision
Level 2: IK with Self-Collision¶
Enables cuRobo’s self-collision avoidance. The solver penalizes configurations where collision spheres overlap, preventing interpenetrating limbs. This is the recommended default for generating training data or deployment motions.
cfg = MotionRetargeterCfg.create(
robot="unitree_g1_29dof_retarget.yml",
tool_pose_criteria={...},
num_envs=1,
self_collision_check=True, # self-collision avoidance enabled
)
retargeter = MotionRetargeter(cfg)
result = retargeter.solve_sequence(seq)
CLI equivalent:
python -m curobo.examples.getting_started.humanoid_retargeting \
--input motion.bvh --output motion.csv
Level 3: MPC (Trajectory-Based)¶
Switches the local solver from frame-by-frame IK to Model Predictive Control. Instead of solving IK independently per frame, MPC optimizes a trajectory over a planning horizon, producing smoother results with acceleration and jerk costs.
cfg = MotionRetargeterCfg.create(
robot="unitree_g1_29dof_retarget.yml",
tool_pose_criteria={...},
num_envs=1,
self_collision_check=True,
use_mpc=True, # MPC local solver
steps_per_target=4,
)
retargeter = MotionRetargeter(cfg)
result = retargeter.solve_sequence(seq)
# result.joint_state: one frame per input target (num_envs, num_frames, num_dof)
# result.trajectory: smooth intermediate frames (MPC only)
CLI equivalent:
python -m curobo.examples.getting_started.humanoid_retargeting \
--input motion.bvh --output motion.csv \
--mpc --steps-per-target 4
Key points (all levels):
Quaternion convention: cuRobo uses
(w, x, y, z)order. Warp and many mocap formats use(x, y, z, w); convert before constructingSequenceGoalToolPose.Output DOFs: The solution contains 35 DOFs: 6 virtual base joints
[x, y, z, roll, pitch, yaw]followed by 29 body joints.Streaming mode: call
retargeter.solve_frame(tool_pose)one frame at a time for online/teleoperation use cases.
For a full description of all configuration parameters and their tuning guidance, see
MotionRetargeterCfg.
Step 5: Running the SOMA Example¶
Requires soma-retargeter to be installed. See the
README.
Single file:
python -m curobo.examples.getting_started.humanoid_retargeting \
--input /path/to/motion.bvh \
--output /path/to/output.csv
Batch (folder of BVH files):
python -m curobo.examples.getting_started.humanoid_retargeting \
--input /path/to/bvh_folder/ \
--output /path/to/csv_folder/
With visualization (opens a web viewer at http://localhost:8080):
python -m curobo.examples.getting_started.humanoid_retargeting \
--input motion.bvh --output motion.csv --visualize
The viewer provides play/pause, loop, speed, frame slider, target sphere visibility, and a motion dropdown (when multiple clips are loaded).
Additional flags:
--robot-config: cuRobo robot YAML config (default:unitree_g1_29dof_retarget.yml).--no-self-collision: disable self-collision checking (Level 1).--mpc: enable MPC mode (Level 3).--steps-per-target N: MPC steps per input frame (default: 4).--max-frames N: limit retargeting to the first N frames.--max-batch N: max clips to retarget in parallel (default: 100).
Additional Details¶
The virtual base joints (
base_link_x/y/z,base_link_xtheta/ytheta/ztheta) give the pelvis 6-DOF freedom. Their limits should be wide enough for the expected motion range.The SOMA example outputs joint data in
CSVAnimationBufferformat. The first 7 values per frame are the root transform[x, y, z, qx, qy, qz, qw](converted from the 6 virtual base DOFs viaPose.from_euler_xyz_intrinsic), followed by the 29 body joint angles reordered to SOMA CSV convention.