Lab 01-02: Exploring the Humanoid Model
Objectives​
- Understand the hierarchical structure of robot bodies
- Identify and visualize individual joints and their ranges
- Map actuators to their corresponding joints
- Examine the sensor configuration
Materials​
| Type | Name | Version | Tier |
|---|---|---|---|
| software | Python | 3.10+ | required |
| software | MuJoCo | 3.0+ | required |
| software | Matplotlib | 3.5+ | recommended |
Instructions​
Step 1: Load and Examine the Body Hierarchy​
import mujoco
import numpy as np
# Load model
model = mujoco.MjModel.from_xml_path(
mujoco.util.get_resource_path("humanoid/humanoid.xml")
)
data = mujoco.MjData(model)
# Print body hierarchy
def print_body_tree(model, body_id=0, indent=0):
"""Recursively print the body tree."""
name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_BODY, body_id)
mass = model.body_mass[body_id]
print(" " * indent + f"├─ {name} (mass: {mass:.2f} kg)")
# Find children
for i in range(model.nbody):
```python
```python
if model.body_parentid[i] == body_id and i != body_id:
print_body_tree(model, i, indent + 1)
print("Body Hierarchy:")
print_body_tree(model)
Expected Output: A tree structure showing torso at root with limbs branching off. Verification: You should see ~14 bodies including torso, pelvis, thighs, shins, feet, upper arms, forearms, and hands.
Step 2: Explore Joint Properties​
# List all joints with their properties
print("\n" + "="*60)
print("JOINT PROPERTIES")
print("="*60)
for i in range(model.njnt):
name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, i)
jnt_type = model.jnt_type[i]
type_names = {0: "FREE", 1: "BALL", 2: "SLIDE", 3: "HINGE"}
# Get joint limits
limited = model.jnt_limited[i]
if limited:
range_low = model.jnt_range[i, 0]
range_high = model.jnt_range[i, 1]
range_str = f"[{np.degrees(range_low):.1f}°, {np.degrees(range_high):.1f}°]"
else:
range_str = "unlimited"
# Get associated body
body_id = model.jnt_bodyid[i]
body_name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_BODY, body_id)
print(f"{name:20} | Type: {type_names.get(jnt_type, '?'):6} | "
f"Range: {range_str:25} | Body: {body_name}")
Verification: You should see joints like abdomen_y, right_hip_x, left_knee, etc.
Understanding Check: Note which joints are HINGE (1-DOF) vs BALL (3-DOF).
Step 3: Visualize Joint Ranges​
import matplotlib.pyplot as plt
# Collect hinge joint data for visualization
hinge_joints = []
for i in range(model.njnt):
```python
```python
if model.jnt_type[i] == 3: # HINGE
name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, i)
if model.jnt_limited[i]:
low = np.degrees(model.jnt_range[i, 0])
high = np.degrees(model.jnt_range[i, 1])
hinge_joints.append((name, low, high))
# Create range visualization
fig, ax = plt.subplots(figsize=(10, 8))
y_positions = range(len(hinge_joints))
for i, (name, low, high) in enumerate(hinge_joints):
ax.barh(i, high - low, left=low, height=0.6, color='steelblue', alpha=0.7)
ax.plot([0, 0], [-0.5, len(hinge_joints) - 0.5], 'k--', linewidth=0.5)
ax.set_yticks(y_positions)
ax.set_yticklabels([j[0] for j in hinge_joints])
ax.set_xlabel('Joint Angle (degrees)')
ax.set_title('Humanoid Joint Ranges')
ax.grid(axis='x', alpha=0.3)
plt.tight_layout()
plt.savefig('joint_ranges.png', dpi=150)
plt.show()
Expected: A horizontal bar chart showing the range of motion for each joint. Note: Most leg joints have limited ranges (~±90°) while some have wider ranges.
Step 4: Map Actuators to Joints​
print("\n" + "="*60)
print("ACTUATOR MAPPING")
print("="*60)
for i in range(model.nu):
act_name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_ACTUATOR, i)
# Get actuator properties
gear = model.actuator_gear[i, 0]
ctrl_range = model.actuator_ctrlrange[i]
# Find associated joint (transmission target)
trnid = model.actuator_trnid[i, 0]
trn_type = model.actuator_trntype[i]
```python
```python
if trn_type == 0: # Joint transmission
jnt_name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, trnid)
else:
jnt_name = "complex"
print(f"{act_name:20} → {jnt_name:20} | "
f"Gear: {gear:6.1f} | Range: [{ctrl_range[0]:.1f}, {ctrl_range[1]:.1f}]")
Verification: Each actuator should map to a specific joint. Understanding: Gear ratio affects the torque-speed tradeoff.
Step 5: Test Actuator Response​
# Reset simulation
mujoco.mj_resetData(model, data)
# Find a specific actuator to test
act_name = "right_hip_y"
act_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_ACTUATOR, act_name)
# Apply a constant torque and observe
data.ctrl[act_id] = 50.0 # Apply torque
# Record joint response
times = []
positions = []
for _ in range(500):
mujoco.mj_step(model, data)
times.append(data.time)
# Get position of associated joint
jnt_id = model.actuator_trnid[act_id, 0]
qpos_adr = model.jnt_qposadr[jnt_id]
positions.append(data.qpos[qpos_adr])
# Plot response
plt.figure(figsize=(10, 4))
plt.plot(times, np.degrees(positions))
plt.xlabel('Time (s)')
plt.ylabel('Joint Angle (degrees)')
plt.title(f'Response of {act_name} to Constant Torque')
plt.grid(True, alpha=0.3)
plt.savefig('actuator_response.png', dpi=150)
plt.show()
Expected: The joint angle should change over time in response to the applied torque. Analysis: Note how quickly the joint responds and any oscillations.
Expected Outcomes​
- Complete understanding of the humanoid body structure
- Visualization of joint ranges saved as
joint_ranges.png - Understanding of actuator-joint mapping
- Actuator response plot saved as
actuator_response.png
Rubric​
| Criterion | Points | Description |
|---|---|---|
| Body Hierarchy | 20 | Correctly prints and explains the body tree |
| Joint Analysis | 25 | Identifies all joints with correct properties |
| Visualization | 20 | Creates clear joint range visualization |
| Actuator Mapping | 20 | Correctly maps all actuators to joints |
| Response Analysis | 15 | Analyzes and explains actuator response |
Total: 100 points
Extensions​
- Compare Models: Load the
antorcheetahmodel and compare structures - Custom Visualization: Create a 3D visualization of the body hierarchy
- Symmetry Analysis: Verify left-right symmetry in joint properties