Skip to main content

Lab 08-03: Dynamic Locomotion and Running

Objectivesโ€‹

By the end of this lab, you will be able to:

  • Implement Spring-Loaded Inverted Pendulum (SLIP) model for running
  • Design flight phase controllers for aerial locomotion
  • Generate and track running gaits with touchdown control
  • Analyze energy efficiency of different locomotion modes

Prerequisitesโ€‹

  • Completed Labs 08-01 and 08-02
  • Understanding of hybrid dynamical systems
  • Familiarity with energy-based control concepts

Materialsโ€‹

TypeNameTierNotes
softwareMuJoCo 3.0+requiredPhysics simulation
softwarePython 3.10+requiredProgramming environment
softwareNumPy, SciPyrequiredODE integration, optimization
simulationslip-runner.xmlrequiredSLIP model for running

Backgroundโ€‹

Running vs. Walkingโ€‹

Walking: Always at least one foot on ground (no flight phase) Running: Includes flight phase where no feet touch ground

Spring-Loaded Inverted Pendulum (SLIP)โ€‹

The SLIP model captures essential running dynamics:

  • Point mass at hip
  • Massless spring leg
  • Two phases: stance and flight

Stance dynamics: mxยจ=โˆ’k(rโˆ’r0)xโˆ’xfrm\ddot{x} = -k(r - r_0)\frac{x - x_f}{r} mzยจ=โˆ’k(rโˆ’r0)zrโˆ’mgm\ddot{z} = -k(r - r_0)\frac{z}{r} - mg

Where r=(xโˆ’xf)2+z2r = \sqrt{(x-x_f)^2 + z^2} is leg length.

Raibert Hopping Controllerโ€‹

Decomposed control:

  1. Vertical hopping: Control apex height
  2. Forward speed: Control touchdown angle
  3. Body attitude: Separate from legs

Instructionsโ€‹

Step 1: Implement SLIP Modelโ€‹

Create the SLIP dynamics model:

import numpy as np
from scipy.integrate import solve_ivp
import matplotlib.pyplot as plt

class SLIPModel:
"""Spring-Loaded Inverted Pendulum model for running."""

def __init__(self, mass=80, leg_length=1.0, stiffness=15000, gravity=9.81):
"""
Initialize SLIP model.

Args:
mass: Body mass (kg)
leg_length: Rest leg length (m)
stiffness: Leg spring stiffness (N/m)
gravity: Gravitational acceleration (m/s^2)
"""
self.m = mass
self.r0 = leg_length
self.k = stiffness
self.g = gravity

# State: [x, z, xdot, zdot]
# Phase: 'flight' or 'stance'
self.phase = 'flight'
self.foot_x = 0 # Foot position during stance

def flight_dynamics(self, t, state):
"""
Flight phase dynamics: ballistic motion.

state = [x, z, xdot, zdot]
"""
x, z, xdot, zdot = state
return [xdot, zdot, 0, -self.g]

def stance_dynamics(self, t, state):
"""
Stance phase dynamics: spring leg.

state = [x, z, xdot, zdot]
"""
x, z, xdot, zdot = state

# Leg vector
dx = x - self.foot_x
r = np.sqrt(dx**2 + z**2)

# Spring force (compression only)
```python
```python
if r < self.r0:
            F_spring = self.k * (self.r0 - r)
else:
F_spring = 0

# Force components
Fx = F_spring * dx / r
Fz = F_spring * z / r

# Accelerations
xddot = Fx / self.m
zddot = Fz / self.m - self.g

return [xdot, zdot, xddot, zddot]

def touchdown_event(self, t, state):
"""Detect touchdown (z = r0 * cos(angle))."""
x, z, xdot, zdot = state
# Assuming touchdown at angle theta from vertical
# For now, trigger at z = 0.95 * r0 (slightly compressed)
return z - 0.95 * self.r0

def liftoff_event(self, t, state):
"""Detect liftoff (spring unloaded)."""
x, z, xdot, zdot = state
dx = x - self.foot_x
r = np.sqrt(dx**2 + z**2)
return r - self.r0 # Positive when leg fully extended

def simulate_step(self, state0, touchdown_angle, max_time=2.0):
"""
Simulate one running step.

Args:
state0: Initial state [x, z, xdot, zdot]
touchdown_angle: Leg angle at touchdown (rad from vertical)
max_time: Maximum simulation time

Returns:
t: Time array
states: State array
events: Dictionary of event times
"""
t_all = [0]
states_all = [state0]
events = {}

state = state0.copy()
t_current = 0

# Phase 1: Flight until touchdown
```python
```python
if self.phase == 'flight':
            touchdown_event = lambda t, s: s[1] - self.r0 * np.cos(touchdown_angle)
touchdown_event.terminal = True
touchdown_event.direction = -1

sol = solve_ivp(
self.flight_dynamics,
[t_current, t_current + max_time],
state,
events=touchdown_event,
dense_output=True,
max_step=0.01
)

```python
```python
if sol.t_events[0].size > 0:
                t_td = sol.t_events[0][0]
events['touchdown'] = t_td

# Record trajectory
t_all.extend(sol.t[1:])
states_all.extend(sol.y[:, 1:].T.tolist())

# Update state and foot position
state = sol.y_events[0][0]
self.foot_x = state[0] - self.r0 * np.sin(touchdown_angle)
self.phase = 'stance'
t_current = t_td
else:
# No touchdown
t_all.extend(sol.t[1:])
states_all.extend(sol.y[:, 1:].T.tolist())
return np.array(t_all), np.array(states_all), events

# Phase 2: Stance until liftoff
```python
```python
if self.phase == 'stance':
            liftoff_event = lambda t, s: np.sqrt((s[0]-self.foot_x)**2 + s[1]**2) - self.r0
liftoff_event.terminal = True
liftoff_event.direction = 1

sol = solve_ivp(
self.stance_dynamics,
[t_current, t_current + max_time - (t_current if t_current > 0 else 0)],
state,
events=liftoff_event,
dense_output=True,
max_step=0.001 # Smaller for stance accuracy
)

```python
```python
if sol.t_events[0].size > 0:
                t_lo = sol.t_events[0][0]
events['liftoff'] = t_lo

t_all.extend(sol.t[1:])
states_all.extend(sol.y[:, 1:].T.tolist())

state = sol.y_events[0][0]
self.phase = 'flight'
else:
t_all.extend(sol.t[1:])
states_all.extend(sol.y[:, 1:].T.tolist())

return np.array(t_all), np.array(states_all), events

# Create SLIP model
slip = SLIPModel(mass=80, leg_length=1.0, stiffness=20000)

# Initial state for running
x0 = 0.0
z0 = 1.2 # Start above ground
xdot0 = 3.0 # Forward velocity
zdot0 = 0.0 # No initial vertical velocity

state0 = [x0, z0, xdot0, zdot0]
touchdown_angle = 0.3 # About 17 degrees forward

# Simulate one step
slip.phase = 'flight'
t, states, events = slip.simulate_step(state0, touchdown_angle)

print(f"Step simulation: {len(t)} points")
print(f"Events: {events}")
print(f"Final state: {states[-1]}")

Expected: SLIP step simulated with touchdown and liftoff events detected.

Step 2: Design Raibert Controllerโ€‹

Implement the classic Raibert hopping controller:

class RaibertController:
"""Raibert-style controller for SLIP running."""

def __init__(self, slip_model, desired_speed=3.0, desired_height=1.1):
"""
Initialize controller.

Args:
slip_model: SLIP model instance
desired_speed: Target forward velocity (m/s)
desired_height: Target apex height (m)
"""
self.slip = slip_model
self.v_des = desired_speed
self.z_apex_des = desired_height

# Gains
self.kv = 0.1 # Forward velocity gain
self.kp_height = 1000 # Height control (energy injection)

# State memory
self.last_stance_energy = 0
self.stride_time = 0.3 # Estimated stride time

def compute_touchdown_angle(self, state):
"""
Compute touchdown angle for speed control.

Raibert's neutral point + velocity correction.

Args:
state: Current [x, z, xdot, zdot]

Returns:
theta: Touchdown angle (rad from vertical)
"""
x, z, xdot, zdot = state

# Neutral point: leg should land at position where
# COM will be directly above foot at mid-stance
# theta_neutral = arcsin(v * T_stance / 2 / r0)
T_stance_est = 0.15 # Estimated stance duration
theta_neutral = np.arcsin(np.clip(xdot * T_stance_est / 2 / self.slip.r0, -1, 1))

# Velocity correction
v_error = xdot - self.v_des
theta_correction = self.kv * v_error

theta = theta_neutral + theta_correction

# Limit angle
theta = np.clip(theta, -0.5, 0.5)

return theta

def compute_energy_injection(self, state):
"""
Compute energy to inject during stance for height control.

Args:
state: Current state

Returns:
energy: Energy to add (J)
"""
x, z, xdot, zdot = state

# Current total energy
KE = 0.5 * self.slip.m * (xdot**2 + zdot**2)
PE = self.slip.m * self.slip.g * z
E_current = KE + PE

# Desired energy at apex (all potential)
E_desired = self.slip.m * self.slip.g * self.z_apex_des + \
0.5 * self.slip.m * self.v_des**2

# Energy to inject
delta_E = E_desired - E_current

return delta_E

def run_simulation(self, n_steps=10, initial_state=None):
"""
Run multiple steps with control.

Args:
n_steps: Number of steps
initial_state: Initial [x, z, xdot, zdot]

Returns:
full_trajectory: Complete trajectory data
"""
if initial_state is None:
initial_state = [0, 1.3, self.v_des, 0]

trajectory = {
'time': [],
'x': [],
'z': [],
'xdot': [],
'zdot': [],
'phase': [],
'touchdown_angle': [],
'apex_height': []
}

state = initial_state.copy()
t_offset = 0

for step in range(n_steps):
# Compute control
theta = self.compute_touchdown_angle(state)

# Simulate step
self.slip.phase = 'flight' if state[1] > 1.05 * self.slip.r0 else 'stance'
t, states, events = self.slip.simulate_step(state, theta)

# Record
for i in range(len(t)):
trajectory['time'].append(t[i] + t_offset)
trajectory['x'].append(states[i, 0])
trajectory['z'].append(states[i, 1])
trajectory['xdot'].append(states[i, 2])
trajectory['zdot'].append(states[i, 3])
trajectory['phase'].append(step)

trajectory['touchdown_angle'].append(theta)

# Find apex (max z)
apex_idx = np.argmax(states[:, 1])
trajectory['apex_height'].append(states[apex_idx, 1])

# Update for next step
state = states[-1].tolist()
t_offset += t[-1]

print(f"Step {step}: apex={states[apex_idx, 1]:.3f}m, "
f"v={states[-1, 2]:.2f}m/s, theta={np.rad2deg(theta):.1f}ยฐ")

return trajectory

# Create controller
controller = RaibertController(slip, desired_speed=3.0, desired_height=1.15)

# Run simulation
trajectory = controller.run_simulation(n_steps=8)

print(f"\nSimulation complete")
print(f"Total distance: {trajectory['x'][-1]:.2f} m")
print(f"Average speed: {np.mean(trajectory['xdot']):.2f} m/s")
print(f"Apex heights: {trajectory['apex_height']}")

Expected: Multiple running steps with speed and height regulation.

Step 3: Implement Flight Phase Controlโ€‹

Add control during flight for attitude:

class FlightPhaseController:
"""Controller for flight phase: attitude and leg positioning."""

def __init__(self, slip_model):
self.slip = slip_model

# Attitude control (if robot has rotational DOF)
self.kp_pitch = 50
self.kd_pitch = 10

# Leg retraction for clearance
self.retract_ratio = 0.9 # Retract to 90% of leg length

def compute_leg_angle_trajectory(self, current_angle, target_angle, flight_time, dt=0.01):
"""
Generate smooth leg swing trajectory.

Args:
current_angle: Current leg angle (rad)
target_angle: Target touchdown angle (rad)
flight_time: Available flight time (s)
dt: Time step

Returns:
t: Time array
angles: Leg angle trajectory
"""
t = np.arange(0, flight_time, dt)
n = len(t)

# Use smooth 5th order polynomial
s = t / flight_time
h = 10*s**3 - 15*s**4 + 6*s**5

angles = current_angle + h * (target_angle - current_angle)

return t, angles

def compute_leg_retraction_trajectory(self, flight_time, dt=0.01):
"""
Generate leg length trajectory: retract then extend.

Returns:
t: Time array
lengths: Leg length trajectory
"""
t = np.arange(0, flight_time, dt)

# Retract in first half, extend in second
lengths = np.zeros_like(t)
for i, ti in enumerate(t):
s = ti / flight_time
```python
```python
if s < 0.5:
                # Retract
lengths[i] = self.slip.r0 * (1 - (1-self.retract_ratio) * 2*s)
else:
# Extend
lengths[i] = self.slip.r0 * (self.retract_ratio + (1-self.retract_ratio) * 2*(s-0.5))

return t, lengths

# Test flight control
flight_ctrl = FlightPhaseController(slip)

# Leg swing from -0.2 to 0.3 rad over 0.2s flight
t_leg, angles = flight_ctrl.compute_leg_angle_trajectory(-0.2, 0.3, 0.2)
t_ret, lengths = flight_ctrl.compute_leg_retraction_trajectory(0.2)

print(f"Flight phase control trajectories generated")
print(f"Leg angle: {angles[0]:.2f} to {angles[-1]:.2f} rad")
print(f"Leg length: {lengths[0]:.2f} to {lengths[-1]:.2f} m (min: {min(lengths):.2f})")

Expected: Smooth leg swing and retraction trajectories for flight phase.

Step 4: Energy Analysisโ€‹

Analyze energy exchange during running:

class EnergyAnalyzer:
"""Analyze energy exchange in running."""

def __init__(self, slip_model):
self.slip = slip_model

def compute_energies(self, trajectory):
"""
Compute energy components over trajectory.

Returns:
energies: Dict with KE, PE, spring, total
"""
n = len(trajectory['time'])

energies = {
'kinetic': np.zeros(n),
'potential': np.zeros(n),
'total': np.zeros(n)
}

for i in range(n):
x = trajectory['x'][i]
z = trajectory['z'][i]
xdot = trajectory['xdot'][i]
zdot = trajectory['zdot'][i]

# Kinetic energy
KE = 0.5 * self.slip.m * (xdot**2 + zdot**2)
energies['kinetic'][i] = KE

# Potential energy
PE = self.slip.m * self.slip.g * z
energies['potential'][i] = PE

# Total mechanical energy
energies['total'][i] = KE + PE

return energies

def compute_cost_of_transport(self, trajectory, energies):
"""
Compute Cost of Transport (CoT).

CoT = Energy used / (weight * distance)

For passive SLIP, this measures energy dissipation.
"""
# Distance traveled
distance = trajectory['x'][-1] - trajectory['x'][0]

# Energy change (ideally zero for conservative SLIP)
E_initial = energies['total'][0]
E_final = energies['total'][-1]
E_lost = E_initial - E_final

# Weight
weight = self.slip.m * self.slip.g

# CoT
```python
```python
if distance > 0:
            cot = abs(E_lost) / (weight * distance)
else:
cot = float('inf')

return {
'distance': distance,
'energy_lost': E_lost,
'cot': cot,
'cot_dim': cot # Dimensionless
}

# Analyze running trajectory
analyzer = EnergyAnalyzer(slip)
energies = analyzer.compute_energies(trajectory)
cot = analyzer.compute_cost_of_transport(trajectory, energies)

print(f"\nEnergy Analysis:")
print(f" Initial KE: {energies['kinetic'][0]:.1f} J")
print(f" Initial PE: {energies['potential'][0]:.1f} J")
print(f" Initial Total: {energies['total'][0]:.1f} J")
print(f" Final Total: {energies['total'][-1]:.1f} J")
print(f" Energy lost: {cot['energy_lost']:.1f} J")
print(f"\nCost of Transport:")
print(f" Distance: {cot['distance']:.2f} m")
print(f" CoT: {cot['cot']:.4f}")

Expected: Energy analysis showing kinetic-potential exchange during running.

Step 5: Compare Walking vs Runningโ€‹

Analyze tradeoffs between gaits:

def compare_gaits(distance=20):
"""
Compare walking and running gaits.

Args:
distance: Distance to cover (m)

Returns:
comparison: Dictionary of metrics
"""
comparison = {}

# Walking parameters (from Lab 08-02 theory)
walking = {
'speed': 1.2, # m/s
'step_length': 0.6, # m
'step_frequency': 2.0, # Hz
'cot': 0.3, # Typical human walking CoT
'time': distance / 1.2
}

# Running parameters
running = {
'speed': 3.0, # m/s
'step_length': 1.2, # m
'step_frequency': 2.5, # Hz
'cot': 0.5, # Typical running CoT (higher due to vertical oscillation)
'time': distance / 3.0
}

# Mechanical work
walking['work'] = walking['cot'] * 80 * 9.81 * distance
running['work'] = running['cot'] * 80 * 9.81 * distance

# Power
walking['power'] = walking['work'] / walking['time']
running['power'] = running['work'] / running['time']

print(f"\nGait Comparison for {distance}m:")
print(f"{'Metric':<20} {'Walking':<15} {'Running':<15}")
print("-" * 50)
print(f"{'Speed (m/s)':<20} {walking['speed']:<15.1f} {running['speed']:<15.1f}")
print(f"{'Time (s)':<20} {walking['time']:<15.1f} {running['time']:<15.1f}")
print(f"{'Step length (m)':<20} {walking['step_length']:<15.2f} {running['step_length']:<15.2f}")
print(f"{'Step freq (Hz)':<20} {walking['step_frequency']:<15.1f} {running['step_frequency']:<15.1f}")
print(f"{'CoT':<20} {walking['cot']:<15.2f} {running['cot']:<15.2f}")
print(f"{'Work (J)':<20} {walking['work']:<15.0f} {running['work']:<15.0f}")
print(f"{'Power (W)':<20} {walking['power']:<15.0f} {running['power']:<15.0f}")

return walking, running

walking_data, running_data = compare_gaits(distance=100)

# Froude number analysis
def compute_froude_number(speed, leg_length=1.0, g=9.81):
"""
Compute Froude number: Fr = v^2 / (g * L)

Fr < 0.5: Walking preferred
Fr > 0.5: Running preferred
"""
return speed**2 / (g * leg_length)

print(f"\nFroude Number Analysis:")
print(f" Walking (1.2 m/s): Fr = {compute_froude_number(1.2):.2f}")
print(f" Running (3.0 m/s): Fr = {compute_froude_number(3.0):.2f}")
print(f" Transition point: Fr โ‰ˆ 0.5 โ†’ v โ‰ˆ {np.sqrt(0.5 * 9.81 * 1.0):.1f} m/s")

Expected: Walking vs running comparison showing speed/energy tradeoffs.

Step 6: MuJoCo Running Simulationโ€‹

Implement running in full physics simulation:

def run_mujoco_simulation():
"""
Execute running in MuJoCo simulation.

This requires a proper running robot model.
"""
# Load model
try:
model = mujoco.MjModel.from_xml_path(
"textbook/assets/robot-models/mujoco/slip-runner.xml"
)
data = mujoco.MjData(model)
except:
print("Note: slip-runner.xml not found. Using SLIP model analysis only.")
return None

# Initialize
mujoco.mj_resetData(model, data)

# Set initial velocity
data.qvel[0] = 3.0 # Forward velocity

# Simulation parameters
dt = model.opt.timestep
duration = 5.0
steps = int(duration / dt)

history = {
'time': [],
'x': [],
'z': [],
'xdot': [],
'zdot': []
}

for i in range(steps):
# Step simulation
mujoco.mj_step(model, data)

# Record
history['time'].append(i * dt)
history['x'].append(data.qpos[0])
history['z'].append(data.qpos[2])
history['xdot'].append(data.qvel[0])
history['zdot'].append(data.qvel[2])

return history

mujoco_history = run_mujoco_simulation()
if mujoco_history:
print(f"MuJoCo simulation complete: {len(mujoco_history['time'])} steps")

Expected: Either MuJoCo simulation runs or graceful fallback to SLIP model.

Expected Outcomesโ€‹

After completing this lab, you should have:

  1. Code artifacts:

    • slip_model.py: SLIP dynamics implementation
    • raibert_controller.py: Running controller
    • flight_controller.py: Flight phase control
    • energy_analysis.py: Efficiency metrics
    • gait_comparison.py: Walking vs running analysis
  2. Understanding:

    • SLIP model as running approximation
    • Raibert control decomposition
    • Energy storage and return in running
    • Walk-run transition principles
  3. Experimental results:

    • Running trajectory over multiple steps
    • Energy exchange during running
    • Gait comparison metrics

Rubricโ€‹

CriterionPointsDescription
SLIP Implementation20Correct stance/flight dynamics
Raibert Controller25Speed and height regulation
Flight Control15Leg swing and retraction
Energy Analysis20CoT and efficiency metrics
Gait Comparison20Walk vs run tradeoff analysis
Total100

Common Errorsโ€‹

Error: SLIP simulation crashes or goes unstable Solution: Check event detection, use smaller time steps during stance.

Error: Speed doesn't converge to desired Solution: Tune touchdown angle gain, check Froude number regime.

Error: Robot falls after few steps Solution: Check energy balance, adjust stiffness for height.

Extensionsโ€‹

For advanced students:

  1. 3D Running: Extend to lateral balance and turning
  2. Rough Terrain: Add terrain height perturbations
  3. Learned Running: Train RL policy for robust running
  4. Quadruped: Extend to 4-leg running gaits (trot, gallop)
  • Theory: Module 08 theory.md, Section 8.3 (Dynamic Locomotion)
  • Previous Lab: Lab 08-02 (Walking Gait)
  • Research: Boston Dynamics running, Agility Robotics Digit
  • Biology: Biomechanics of running, SLIP in nature