create_smplh
Module: GBC.utils.data_preparation.create_smplh
This module provides the core functionality for fitting SMPL+H (Skinned Multi-Person Linear model with Hands) body shape parameters to humanoid robot skeletons. The fitting process is essential for transferring human motion capture data to robot control, enabling human-robot motion imitation and behavior cloning.
π Dependenciesβ
This module requires the following Python packages:
torch
- PyTorch framework for optimizationnumpy
- Numerical computationsscipy
- Spatial transformations and scientific computinghuman_body_prior
- SMPL+H body model implementationbody_visualizer
- Mesh visualization toolstrimesh
- 3D mesh processingopen3d
- 3D data processing and visualizationopencv-python
- Computer vision operationsGBC.utils.base.base_fk
- Robot forward kinematics
ποΈ Core Classβ
π€ SMPLHFitterβ
Module Name: GBC.utils.data_preparation.create_smplh.SMPLHFitter
Definition:
class SMPLHFitter:
def __init__(self,
smplh_model_path: str,
dmpls_model_path: str,
urdf_path: str,
device: str = "cuda")
π₯ Input:
smplh_model_path
(str): Path to SMPL+H model file (.npz)dmpls_model_path
(str): Path to DMPL muscle model file (.npz)urdf_path
(str): Path to robot URDF description filedevice
(str): Computing device ("cuda" or "cpu"). Default: "cuda"
π§ Functionality: Main class for fitting SMPL+H human body model parameters to match humanoid robot skeleton geometry. This process creates a mapping between human body joints and robot links, enabling motion transfer from human demonstrations to robot execution.
π‘ Key Features:
- Automated body shape parameter optimization (beta coefficients)
- Muscle dynamics parameter fitting (DMPL coefficients)
- Scale factor optimization for size matching
- Multi-pose fitting support for improved accuracy
- 3D visualization tools for validation
π― Critical Configuration Parametersβ
πΊοΈ mapping_table - Joint Mapping Configurationβ
The following example shows the mapping for a Unitree robot:
β οΈ CRITICAL PARAMETER - Incorrect mapping will prevent training
Type: Dict[str, str]
Purpose: Maps SMPL+H joint names to corresponding robot link names
π§ Functionality: This is the most critical configuration parameter. It establishes the correspondence between SMPL+H body joints and robot links. Incorrect mapping will result in:
- Failed motion transfer
- Inconsistent joint positions
- Training failures in downstream tasks
π SMPL+H Available Joints:
smplh_body_names = [
'Pelvis', 'L_Hip', 'R_Hip', 'Torso', 'L_Knee', 'R_Knee',
'Spine', 'L_Ankle', 'R_Ankle', 'Chest', 'L_Toe', 'R_Toe',
'Neck', 'L_Thorax', 'R_Thorax', 'Head', 'L_Shoulder',
'R_Shoulder', 'L_Elbow', 'R_Elbow', 'L_Wrist', 'R_Wrist'
]
smplh_hand_names = ['L_Index1', 'L_Index2', 'L_Index3', 'L_Middle1',
'L_Middle2', 'L_Middle3', 'L_Pinky1', 'L_Pinky2',
'L_Pinky3', 'L_Ring1', 'L_Ring2', 'L_Ring3',
'L_Thumb1', 'L_Thumb2', 'L_Thumb3', 'R_Index1', 'R_Index2',
'R_Index3', 'R_Middle1', 'R_Middle2', 'R_Middle3', 'R_Pinky1',
'R_Pinky2', 'R_Pinky3', 'R_Ring1', 'R_Ring2',
'R_Ring3', 'R_Thumb1', 'R_Thumb2', 'R_Thumb3']
π‘ Mapping Strategy:
- Pelvis β Base Link: Root body connection
- Hip Joints β Hip Links: Leg attachment points
- Knee/Ankle β Corresponding Links: Leg chain continuity
- Shoulder/Elbow/Wrist β Arm Links: Arm chain mapping
- Optional Joints: Head, Toe, Torso (if robot has corresponding links)
π rotation_map - SMPLH Joint Alignmentβ
Type: Dict[str, List[float]]
Purpose: Rotates SMPLH joints to match robot's zero pose configuration
π§ Functionality: Adjusts SMPLH joint orientations to align with the robot's default pose. Each rotation is specified as Euler angles [x, y, z] in radians.
π‘ Common Rotations:
- Elbow Joints: Often need Ο/2 rotations to match robot arm orientations
- Shoulder Joints: May require adjustments for different arm rest positions
- Hip Joints: Alignment for different leg orientations
π t_pose_action - Robot T-Pose Configurationβ
Type: torch.Tensor
Purpose: Joint actions to move robot into T-pose for fitting
π§ Functionality: Defines the joint positions that place the robot in a T-pose (arms extended horizontally). This pose provides better correspondence with SMPL+H's default pose for fitting.
π‘ Typical T-Pose Actions:
- Shoulder Roll: Β±Ο/2 to extend arms horizontally
- Elbow: Ο/2 to straighten arms
- Other Joints: Usually remain at zero
βοΈ joint_weights - Fitting Priority Weightsβ
Type: torch.Tensor
Purpose: Relative importance weights for different joints during optimization
π§ Functionality: Determines the emphasis placed on matching each joint during the fitting process. Higher weights mean the optimizer prioritizes accuracy for those joints.
π‘ Weight Strategy:
- End Effectors (hands, feet): Higher weights (2.0-4.0) for precise positioning
- Major Joints (knees, elbows): Medium weights (1.5) for structural accuracy
- Base Joints (pelvis, shoulders): Standard weights (1.0) for general alignment
π§ Core Methodsβ
π― set_mapping_tableβ
Definition:
def set_mapping_table(self, mapping_table: Dict[str, str]) -> None
π₯ Input:
mapping_table
(Dict[str, str]): Joint name mapping from SMPLH to robot
π§ Functionality: Sets the critical joint mapping between SMPLH and robot. Must be called before fitting.
π¨ fitβ
Definition:
def fit(self,
max_iter: int = 1000,
lr: float = 0.01,
tol: float = 1e-6,
verbose: bool = False,
offset_map: Optional[Dict[str, torch.Tensor]] = None,
rotation_map: Optional[Dict[str, List[float]]] = None,
t_pose_action: Optional[torch.Tensor] = None,
additional_fitting_poses: Optional[List[Tuple[Dict[str, torch.Tensor], torch.Tensor]]] = None,
joint_weights: Optional[torch.Tensor] = None
) -> Dict[str, torch.Tensor]
π₯ Input:
max_iter
(int): Maximum optimization iterations. Default: 1000lr
(float): Learning rate for optimization. Default: 0.01tol
(float): Convergence tolerance. Default: 1e-6verbose
(bool): Print fitting progress. Default: Falseoffset_map
(Dict[str, torch.Tensor]): Position offsets for robot linksrotation_map
(Dict[str, List[float]]): SMPLH joint rotations for alignmentt_pose_action
(torch.Tensor): Robot joint actions for T-poseadditional_fitting_poses
(List): Extra poses for multi-pose fittingjoint_weights
(torch.Tensor): Importance weights for joints
π€ Output:
fit_result
(Dict[str, torch.Tensor]): Optimized parameters (beta, dmpls, scale)
π§ Functionality: Main optimization routine that fits SMPL+H body shape parameters to match robot skeleton geometry. Uses gradient-based optimization to minimize joint position differences.
ποΈ Visualization Methodsβ
visualize_open3d()β
Interactive 3D visualization of fitted SMPL+H model with robot joint positions
visualize_open3d_tpose()β
Visualization of T-pose alignment between SMPL+H and robot
visualize_fit_model()β
Rendered mesh visualization of the fitted body model
πΎ save_fit_result / load_fit_resultβ
Functionality: Save and load optimized fitting parameters for reuse across training sessions.
π‘ Complete Usage Exampleβ
Based on the Turin humanoid robot configuration:
import torch
import numpy as np
from GBC.utils.data_preparation.create_smplh import SMPLHFitter
# Initialize fitter
device = 'cuda'
fitter = SMPLHFitter(
smplh_model_path="/path/to/smplh/male/model.npz",
dmpls_model_path="/path/to/dmpls/male/model.npz",
urdf_path="/path/to/turin_humanoid.urdf",
device=device
)
# 1. CRITICAL: Set joint mapping (Turin robot example)
mapping_table = {
"Pelvis": "base_link",
"L_Hip": "l_hip_yaw_link",
"R_Hip": "r_hip_yaw_link",
"L_Knee": "l_knee_link",
"R_Knee": "r_knee_link",
"L_Ankle": "l_ankle_pitch_link",
"R_Ankle": "r_ankle_pitch_link",
"L_Shoulder": "l_arm_roll_link",
"R_Shoulder": "r_arm_roll_link",
"L_Elbow": "l_elbow_roll_link",
"R_Elbow": "r_elbow_roll_link",
"L_Wrist": "l_wrist_roll_link",
"R_Wrist": "r_wrist_roll_link",
}
# 2. Configure SMPLH joint rotations for alignment
rotation_map = {
"L_Shoulder": [0, 0, np.pi / 10], # Slight outward rotation
"R_Shoulder": [0, 0, -np.pi / 10], # Slight outward rotation
}
# 3. Set robot T-pose action
t_pose_action = torch.zeros(fitter.robot.num_dofs).to(device)
dof_names = fitter.robot.get_dof_names()
t_pose_action[dof_names.index("l_arm_roll")] = -np.pi / 10
t_pose_action[dof_names.index("r_arm_roll")] = np.pi / 10
# 4. Configure joint weights (critical for end effector accuracy)
joint_weights = torch.tensor([
1.0, # Pelvis - base reference
1.0, # L_Hip - structural
1.0, # R_Hip - structural
1.5, # L_Knee - important for leg kinematics
1.5, # R_Knee - important for leg kinematics
4.0, # L_Ankle - end effector, high precision needed
4.0, # R_Ankle - end effector, high precision needed
1.0, # L_Shoulder - structural
1.0, # R_Shoulder - structural
1.5, # L_Elbow - important for arm kinematics
1.5, # R_Elbow - important for arm kinematics
2.0, # L_Wrist - end effector, precision needed
2.0, # R_Wrist - end effector, precision needed
])
# 5. Execute fitting process
fitter.set_mapping_table(mapping_table)
fit_result = fitter.fit(
max_iter=30000,
verbose=True,
lr=0.01,
rotation_map=rotation_map,
t_pose_action=t_pose_action,
joint_weights=joint_weights
)
# 6. Save results for training
fitter.save_fit_result("fit_turin/best_fit_30000.pt")
# 7. Visualize results
fitter.visualize_open3d() # Interactive 3D view
fitter.visualize_open3d_tpose() # T-pose alignment check
β οΈ Critical Setup Guidelinesβ
π― Joint Mapping Verificationβ
ESSENTIAL STEP: Verify mapping correctness before training
- Visual Inspection: Use
visualize_open3d()
to check joint alignments - T-Pose Check: Verify T-pose correspondence with
visualize_open3d_tpose()
- Joint Order: Ensure consistent left/right naming conventions
- Missing Joints: Some SMPL+H joints may not have robot equivalents (skip them)
π Weight Tuning Strategyβ
End Effector Priority (Weights: 2.0-4.0):
- Hands (wrists) for manipulation tasks
- Feet (ankles) for locomotion stability
Structural Joints (Weights: 1.0-1.5):
- Hips, shoulders for overall posture
- Knees, elbows for kinematic chains
π Iterative Refinementβ
- Start Simple: Basic mapping with default weights
- Monitor Convergence: Target loss around 0.05 per pose
- Visual Validation: Check alignment quality
- Weight Adjustment: Increase weights for poorly aligned critical joints
- Multi-Pose Fitting: Add additional poses for complex robots
- Final Validation: Verify with actual motion transfer
π Convergence Monitoringβ
β οΈ Critical Performance Indicators:
- Optimal Loss: 0.05 Β± 0.03 per pose indicates successful fitting
- Configuration Issues: Loss > 0.1 suggests mapping or weight problems
- Excellent Fit: Loss < 0.02 indicates very precise alignment (usually not likely to happen)
π‘ Troubleshooting by Loss Values:
- Loss 0.15-0.5: Check joint mapping accuracy
- Loss 0.1-0.15: Adjust joint weights for critical joints
- Loss > 0.5: Verify URDF structure and SMPL+H joint correspondence
π¨ Common Issues and Solutionsβ
β Poor Joint Alignmentβ
Cause: Incorrect mapping or insufficient joint weights
Solution: Verify mapping table and increase weights for misaligned joints
β Scale Mismatchβ
Cause: Significant size difference between SMPL+H and robot
Solution: Check scale factor in fit results, consider robot-specific adjustments
β Convergence Issuesβ
Cause: Learning rate too high or conflicting constraints
Solution: Reduce learning rate, check joint weight balance
β οΈ Expected Convergence Values:
- Target Loss: ~0.05 per pose for proper fitting
- Acceptable Range: 0.02-0.08 depending on robot complexity
- Warning Signs: Loss > 0.1 indicates configuration problems
β Training Failuresβ
Cause: Incorrect joint mapping preventing motion transfer
Solution: Re-verify mapping table against robot URDF structure
π― Integration with Training Pipelineβ
The fitted SMPL+H parameters are essential for:
- Motion Retargeting: Converting human motion to robot joint commands
- Behavior Cloning: Training policies from human demonstrations
- Simulation Setup: Accurate human-robot correspondence in training environments
- Evaluation Metrics: Measuring motion similarity between human and robot
Proper SMPL+H fitting is the foundation for successful human-to-robot motion transfer in the GBC framework.