🔀 Convert AMASS Actions
This section describes how to convert the entire AMASS dataset into robot-feasible, learnable data for imitation learning. This process combines the SMPL+H fitting and PoseFormer training from previous sections to create a comprehensive dataset ready for reinforcement learning environments.
📚 Overview
The AMASS Action Converter transforms human motion capture data into robot-compatible action sequences with comprehensive post-processing and data augmentation. After completing this section, you'll have a dataset ready for imitation learning training.
Key Features:
- Physically Feasible Actions: All outputs respect robot joint limits and kinematics
- Data Augmentation: Longest cycle detection and sequence extension
- Signal Processing: Hampel filtering, low-pass filtering, and quaternion continuity
- Contact Detection: Foot contact sequences and height correction
- Multi-modal Data: Linear/angular velocities, gravity orientation, IMU parameters
- Quality Control: NaN detection and anomaly filtering
For detailed implementation details, see AMASS Action Converter API.
🔧 Prerequisites Verification
Before starting the conversion process, verify that all required components are properly configured:
✅ Model Verification Checklist
-
SMPL+H Fitting Results
# Verify fitted parameters exist and are loadable
python -c "
import torch
fits = torch.load('/path/to/smpl_fits/smpl_fits_all.pt')
print(f'✅ SMPL+H fits loaded: {len(fits)} sequences')
" -
PoseFormer Model
# Check trained model accessibility
python -c "
import torch
model = torch.load('/path/to/trained_poseformer.pt')
print('✅ PoseFormer model loaded successfully')
" -
Robot Configuration
# Verify URDF and joint mapping
python -c "
from GBC.utils.base.base_fk import RobotKinematics
fk = RobotKinematics('/path/to/robot.urdf')
print(f'✅ Robot DOF: {len(fk.get_dof_names())}')
print(f'✅ Joint names: {fk.get_dof_names()}')
" -
Flipper Configuration (Optional)
# Test symmetry flipper if using mirrored data
python -c "
from GBC.utils.data_preparation.robot_flip_left_right import YourFlipperModule
flipper = YourFlipperModule()
print('✅ Flipper module loaded successfully')
"
⚙️ Basic Configuration Setup
📋 Required Imports and Dependencies
from GBC.utils.data_preparation.amass_action_converter import AMASSActionConverter, AMASSActionConverterCfg
from GBC.utils.data_preparation.robot_flip_left_right import YourFlipperModule
from GBC.utils.base.base_fk import RobotKinematics
from GBC.utils.base.assets import DATA_PATHS
import torch
🔧 Joint Mapping Configuration
Define the robot-specific joint mapping consistent with previous sections:
# Define robot-specific joint mapping (same as SMPL+H fitting)
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",
}
🎯 Converter Configuration
Initialize the conversion configuration with all required paths:
# Initialize configuration
cfg = AMASSActionConverterCfg(
urdf_path="/path/to/robot.urdf",
pose_transformer_path="/path/to/trained_poseformer.pt",
export_path="/output/converted_actions",
mapping_table=mapping_table,
smplh_model_path=DATA_PATHS["SMPLH_MODEL_PATH"],
dmpls_model_path=DATA_PATHS["DMPLS_MODEL_PATH"],
smpl_fits_dir="/path/to/smpl_fits/smpl_fits_all.pt",
dataset_path=DATA_PATHS["AMASS_PATH"],
device="cuda:0"
)
📂 Dataset Subset Selection
Configure which AMASS datasets to include in the conversion:
# Specify dataset subset using regex patterns
cfg.specialize_dir = [
"ACCAD/*", # Academic capture data
"CMU/*", # Carnegie Mellon University motions
"BMLmovi/*", # Biology of Motion Lab data
"KIT/*", # Karlsruhe Institute of Technology
"MPI_HDM05/*", # Max Planck Institute data
"TotalCapture/*", # Total Capture dataset
# Add or remove datasets based on your needs
]
# Alternative: Process all datasets
# cfg.specialize_dir = None # Process entire AMASS dataset
🤖 Initialize Converter
Create the converter instance with your configuration:
# Initialize converter
converter = AMASSActionConverter.from_cfg(cfg)
🔄 Flipper Configuration (Optional)
Set up bilateral symmetry support for data augmentation:
🔧 Flipper Setup
# Initialize flipper for bilateral symmetry
flipper = YourFlipperModule()
fk = RobotKinematics(cfg.urdf_path)
flipper.prepare_flip_joint_ids(fk.get_dof_names())
# Attach flipper to converter
converter.set_flipper(flipper)
👣 Foot Configuration
Configure foot contact parameters for accurate ground interaction:
# Define foot link names (must match URDF)
foot_names = ["l_ankle_pitch_link", "r_ankle_pitch_link"]
# Set foot ground offset (distance from ankle to ground contact point)
foot_ground_offset = 0.05 # 5cm ground clearance
# Important: This offset MUST be accurate for proper root translation
# and foot contact detection
The foot_ground_offset
must be precisely measured from your robot's URDF. This parameter is used for root translation correction and foot contact detection. Inaccurate values will result in floating or underground robot poses.
🚀 Conversion Execution
🎯 Start Conversion Process
Execute the comprehensive conversion with all post-processing steps:
# Execute conversion with comprehensive processing
converter.convert(
foot_names=foot_names,
foot_ground_offset=foot_ground_offset,
add_flipped_data=True, # Generate bilateral mirrored data
floor_contact_offset_map={
"l_ankle_pitch_link": torch.Tensor([0, 0, -foot_ground_offset]),
"r_ankle_pitch_link": torch.Tensor([0, 0, -foot_ground_offset]),
},
min_subseq_ratio=0.3, # Require cycle to be at least 30% of sequence
nan_check=True, # Enable NaN detection and filtering
verbose=True # Show detailed progress information
)
📊 Conversion Parameters
Key Configuration Options:
add_flipped_data
: Doubles dataset size with bilateral symmetrymin_subseq_ratio
: Quality threshold for cycle detection (0.3 = 30%)nan_check
: Enables comprehensive NaN detection and removalfloor_contact_offset_map
: Precise foot contact point configuration
🔧 Comprehensive Processing Pipeline
The converter performs extensive post-processing to ensure data quality and robot compatibility:
🔄 Data Augmentation
Longest Cycle Detection and Extension:
- Identifies repetitive motion patterns within sequences
- Extends motions through intelligent cycle repetition
- Ensures sufficient sample diversity for imitation learning
- Quality threshold prevents low-quality cycle detection
📈 Signal Processing
Multi-Stage Filtering Pipeline:
- Hampel Filtering: Removes statistical outliers and spikes
- Low-Pass Filtering: Smooths trajectories for feasible execution
- Quaternion Continuity Repair: Fixes discontinuities in AMASS rotation data
- Joint Limit Enforcement: Ensures all actions respect robot constraints
🌐 Multi-Modal Data Generation
Kinematic State Computation:
- Linear Velocities: World frame and body frame velocities
- Angular Velocities: World frame and body frame angular rates
- Gravity Orientation: IMU-compatible gravity vector
- Joint Velocities: Computed from smoothed position trajectories
👣 Contact Detection and Height Correction
Advanced Foot Contact Processing:
- Foot contact sequence detection based on velocity thresholds
- Height filtering using contact information to prevent ground penetration
- Root translation correction for consistent ground plane alignment
- Contact-aware smoothing to maintain physical plausibility
🔧 Dataset Quality Assurance
Comprehensive Error Handling:
- NaN detection and sequence removal
- Joint limit violation detection
- Kinematic feasibility verification
- Motion continuity validation
The AMASS dataset contains some compressed data that may be less accurate than original motion capture. The converter provides optional support for downloading and using original datasets to correct inaccuracies when available.
📦 Output Format
🎯 GBC Standard Format
The converter exports data in GBC standard pickle format optimized for imitation learning. Remember the dict names here and they will be used later to load by our manager.
### 📂 Directory Structure
```bash
/output/converted_actions/
├── ACCAD/
│ ├── Female1General_c3d/
│ │ ├── A1- Stand_poses.pkl
│ │ ├── A2- Walk_poses.pkl
│ │ └── ...
│ └── ...
├── CMU/
│ ├── 01/
│ │ ├── 01_01_poses.pkl
│ │ ├── 01_02_poses.pkl
│ │ └── ...
│ └── ...
└── processing_log.json
🔧 Integration with Imitation Learning
📋 Dataset Configuration
Configure which converted datasets to use for imitation learning in your assets.py
:
# In your project's assets.py configuration
converted_actions_path: str = "/output/converted_actions"
ref_data_path: list[str] = [
"ACCAD/Female1General_c3d/*.pkl", # Walking motions
"CMU/01/*.pkl", # General human motions
"BMLmovi/Subject_*/*.pkl", # Diverse motion library
"KIT/*/walking_*.pkl", # Walking-specific motions
# Add regex patterns for your specific needs
] # simple directory names like "CMU" can also do.
# Alternative: Use all converted data
# IMITATION_DATASETS = ["*"] # All converted sequences
📊 Validation and Quality Control
✅ Conversion Success Verification
Verify the conversion completed successfully:
# Check conversion results
import os
import pickle
from glob import glob
output_dir = "/output/converted_actions"
pkl_files = glob(f"{output_dir}/**/*.pkl", recursive=True)
print(f"✅ Total converted sequences: {len(pkl_files)}")
# Sample data verification
sample_file = pkl_files[0]
with open(sample_file, 'rb') as f:
data = pickle.load(f)
print(f"✅ Sample sequence shape: {data['actions'].shape}")
print(f"✅ Sample metadata: {data['metadata']['source_file']}")
📈 Statistical Analysis
Analyze dataset statistics for quality assessment:
# Dataset statistics analysis
def analyze_dataset_statistics(output_dir):
"""Analyze converted dataset statistics"""
durations = []
action_ranges = []
contact_ratios = []
for pkl_file in glob(f"{output_dir}/**/*.pkl", recursive=True):
with open(pkl_file, 'rb') as f:
data = pickle.load(f)
durations.append(data['metadata']['duration'])
action_ranges.append(data['actions'].std(dim=0).mean().item())
contact_ratios.append(data['observations']['foot_contacts'].float().mean().item())
print(f"📊 Dataset Statistics:")
print(f" Average duration: {np.mean(durations):.2f}s")
print(f" Action variability: {np.mean(action_ranges):.3f}")
print(f" Contact ratio: {np.mean(contact_ratios):.3f}")
analyze_dataset_statistics(output_dir)
🎯 Success Confirmation
✅ Completion Checklist
- Data Conversion: All specified AMASS sequences successfully converted
- Quality Control: No NaN values or invalid sequences detected
- File Structure: GBC standard format pkl files generated
- Processing Log: Conversion log with statistics available
- Integration Ready: Dataset configured for imitation learning
🚀 Next Steps
Congratulations! You now have a comprehensive, robot-feasible dataset ready for imitation learning. The converted data includes:
- Multi-Modal Observations: Joint states, velocities, gravity, contacts
- Robot-Compatible Actions: Physically feasible joint commands
- Data Augmentation: Extended sequences with bilateral symmetry
- Quality Assurance: Filtered and validated motion sequences
This dataset serves as the foundation for training robust imitation learning policies, enabling your robot to learn complex human-like behaviors with high fidelity and physical plausibility.
With your converted dataset ready, you can now proceed to configure your imitation learning environment and begin policy training. The GBC framework provides comprehensive tools for reinforcement learning training using this processed data.