Skip to main content

Lab 05-03: Adaptive Control for Model Uncertainty

Objectivesโ€‹

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

  • Understand how model uncertainty affects control performance
  • Implement adaptive parameter estimation
  • Design a model-reference adaptive controller (MRAC)
  • Analyze convergence and stability of adaptive systems

Prerequisitesโ€‹

  • Completed Lab 05-02 (Computed Torque Control)
  • Understanding of Lyapunov stability concepts
  • Linear algebra proficiency

Materialsโ€‹

TypeNameTierNotes
softwareMuJoCo 3.0+requiredPhysics simulation
softwarePython 3.10+requiredProgramming environment
softwareNumPy, SciPy, MatplotlibrequiredComputation and visualization
simulation2dof-arm.xmlrequiredTwo-link planar arm model

Backgroundโ€‹

The Problem with Fixed Modelsโ€‹

Computed torque control requires accurate dynamics knowledge:

  • Link masses and inertias
  • Center of mass locations
  • Friction parameters

In practice, these parameters are uncertain or time-varying.

Adaptive Control Approachโ€‹

Instead of fixed parameters, we estimate them online and update the control law:

ฯ„=M^(q,ฮธ^)(qยจd+Kdeห™+Kpe)+C^(q,qห™,ฮธ^)qห™+g^(q,ฮธ^)\tau = \hat{M}(q, \hat{\theta})(\ddot{q}_d + K_d \dot{e} + K_p e) + \hat{C}(q, \dot{q}, \hat{\theta})\dot{q} + \hat{g}(q, \hat{\theta})

The parameter estimates ฮธ^\hat{\theta} are updated using an adaptation law derived from stability analysis.

Instructionsโ€‹

Step 1: Create Perturbed Modelโ€‹

First, create a scenario with model mismatch:

import mujoco
import numpy as np
import matplotlib.pyplot as plt

# Load nominal model
model = mujoco.MjModel.from_xml_path("textbook/assets/robot-models/mujoco/2dof-arm.xml")
data = mujoco.MjData(model)

# Store nominal parameters (for controller model)
nominal_masses = model.body_mass.copy()
print(f"Nominal masses: {nominal_masses}")

def get_dynamics_matrices(model, data):
"""Extract dynamics matrices from MuJoCo."""
nv = model.nv
M = np.zeros((nv, nv))
mujoco.mj_fullM(model, M, data.qM)
mujoco.mj_forward(model, data)
bias = data.qfrc_bias.copy()
return M, bias

def perturb_model(model, mass_scale_factor):
"""
Modify model masses to simulate uncertainty.

Note: This creates a mismatch between controller model and true plant.
"""
# Scale link masses
for i in range(model.nbody):
model.body_mass[i] *= mass_scale_factor

# Also scale inertias (roughly)
model.body_inertia[:] *= mass_scale_factor

# Create "true" plant with different parameters
perturb_model(model, mass_scale_factor=1.5) # 50% heavier than expected

print(f"Perturbed masses: {model.body_mass}")
print(f"Mass mismatch: {(model.body_mass[1] - nominal_masses[1])/nominal_masses[1]*100:.0f}%")

Expected: Model masses increased by 50%, creating significant mismatch.

Step 2: Observe Non-Adaptive CTC Performanceโ€‹

See how standard computed torque fails with model mismatch:

class StandardCTC:
"""Computed torque with fixed (incorrect) model."""

def __init__(self, nominal_model, kp, kd):
self.nominal_model = nominal_model
self.nominal_data = mujoco.MjData(nominal_model)
self.kp = np.atleast_1d(kp) * np.ones(nominal_model.nv)
self.kd = np.atleast_1d(kd) * np.ones(nominal_model.nv)
self.nv = nominal_model.nv

def compute(self, q, qd, q_desired, qd_desired, qdd_desired=None):
"""Compute control using nominal (incorrect) model."""
if qdd_desired is None:
qdd_desired = np.zeros(self.nv)

# Copy state to nominal model
self.nominal_data.qpos[:self.nv] = q
self.nominal_data.qvel[:self.nv] = qd

# Errors
e = q_desired - q
ed = qd_desired - qd

# Desired acceleration
qdd_cmd = qdd_desired + self.kd * ed + self.kp * e

# Get dynamics from NOMINAL model (incorrect!)
M_nom, bias_nom = get_dynamics_matrices(self.nominal_model, self.nominal_data)

# Computed torque
tau = M_nom @ qdd_cmd + bias_nom

return tau, {'error': e, 'qdd_cmd': qdd_cmd}

# Load a fresh nominal model for the controller (unperturbed)
nominal_model = mujoco.MjModel.from_xml_path("textbook/assets/robot-models/mujoco/2dof-arm.xml")

# Create controller with nominal model
standard_ctc = StandardCTC(nominal_model, kp=100, kd=20)

def run_control_test(model, data, controller, q_target, duration=5.0, label=""):
"""Run control test and return results."""
dt = model.opt.timestep
n_steps = int(duration / dt)
nv = model.nv

results = {
'time': np.zeros(n_steps),
'position': np.zeros((n_steps, nv)),
'error': np.zeros((n_steps, nv)),
'torque': np.zeros((n_steps, nv))
}

mujoco.mj_resetData(model, data)

for i in range(n_steps):
q = data.qpos[:nv].copy()
qd = data.qvel[:nv].copy()

tau, info = controller.compute(q, qd, q_target, np.zeros(nv))
data.ctrl[:nv] = tau

results['time'][i] = data.time
results['position'][i] = q
results['error'][i] = info['error']
results['torque'][i] = tau

mujoco.mj_step(model, data)

return results

# Test with model mismatch
target = np.array([np.radians(60), np.radians(-45)])
results_standard = run_control_test(model, data, standard_ctc, target, duration=5.0)

print(f"Standard CTC with model mismatch:")
print(f"Final error: {np.degrees(results_standard['error'][-1])} deg")
print(f"(Expected: significant error due to 50% mass mismatch)")

Expected: Noticeable steady-state error or oscillation due to model mismatch.

Step 3: Implement Adaptive Lawโ€‹

Design the parameter adaptation mechanism:

class AdaptiveParameters:
"""
Online parameter estimation using gradient descent.

Estimates the scaling factor for mass/inertia matrix.
"""

def __init__(self, nv, initial_scale=1.0, learning_rate=0.5):
"""
Initialize adaptive parameters.

Args:
nv: Number of velocity DOFs
initial_scale: Initial mass scale estimate
learning_rate: Adaptation gain (Gamma)
"""
self.nv = nv

# Parameter estimate (scalar for simplicity - scales entire M matrix)
self.mass_scale = initial_scale

# Learning rate
self.gamma = learning_rate

# Parameter bounds (for safety)
self.scale_min = 0.5
self.scale_max = 3.0

# History for analysis
self.history = []

def update(self, error, error_dot, regressor):
"""
Update parameter estimate using adaptation law.

Based on: ฮธฬ‡ = -ฮ“ * Y^T * s
where s is sliding variable (or error combination)

Args:
error: Position error
error_dot: Velocity error
regressor: Y matrix relating parameters to dynamics

Returns:
Updated mass scale estimate
"""
# Composite error (sliding variable)
lambda_s = 5.0 # Sliding surface slope
s = error_dot + lambda_s * error

# Gradient-based update
# For scalar mass scale, regressor is just the acceleration command magnitude
grad = np.dot(regressor, s)

# Update with projection
self.mass_scale -= self.gamma * grad * 0.001 # Small step
self.mass_scale = np.clip(self.mass_scale, self.scale_min, self.scale_max)

self.history.append(self.mass_scale)

return self.mass_scale

def get_estimate(self):
"""Get current parameter estimate."""
return self.mass_scale

Expected: Adaptive parameter class with update mechanism and bounds.

Step 4: Implement Adaptive Computed Torque Controllerโ€‹

Combine CTC with online adaptation:

class AdaptiveCTC:
"""
Adaptive Computed Torque Controller.

Updates mass estimate online to compensate for model uncertainty.
"""

def __init__(self, nominal_model, kp, kd, learning_rate=0.5):
"""
Initialize adaptive controller.

Args:
nominal_model: Nominal robot model
kp, kd: Control gains
learning_rate: Adaptation rate
"""
self.nominal_model = nominal_model
self.nominal_data = mujoco.MjData(nominal_model)
self.nv = nominal_model.nv

self.kp = np.atleast_1d(kp) * np.ones(self.nv)
self.kd = np.atleast_1d(kd) * np.ones(self.nv)

# Adaptive parameters
self.adaptive = AdaptiveParameters(self.nv, initial_scale=1.0,
learning_rate=learning_rate)

def compute(self, q, qd, q_desired, qd_desired, qdd_desired=None):
"""
Compute adaptive control torque.

Args:
q, qd: Current state
q_desired, qd_desired: Desired state
qdd_desired: Desired acceleration (feedforward)

Returns:
tau: Control torque
info: Debug information
"""
if qdd_desired is None:
qdd_desired = np.zeros(self.nv)

# Copy state to nominal model
self.nominal_data.qpos[:self.nv] = q
self.nominal_data.qvel[:self.nv] = qd

# Errors
e = q_desired - q
ed = qd_desired - qd

# Desired acceleration with feedback
qdd_cmd = qdd_desired + self.kd * ed + self.kp * e

# Get nominal dynamics
M_nom, bias_nom = get_dynamics_matrices(self.nominal_model, self.nominal_data)

# Scale mass matrix with adaptive estimate
scale = self.adaptive.get_estimate()
M_adapted = scale * M_nom

# Compute torque with adapted model
tau = M_adapted @ qdd_cmd + bias_nom

# Update adaptation law
# Regressor: how torque depends on mass scale (simplified)
regressor = M_nom @ qdd_cmd
self.adaptive.update(e, ed, regressor)

info = {
'error': e,
'error_dot': ed,
'qdd_cmd': qdd_cmd,
'mass_scale': scale
}

return tau, info

# Create adaptive controller
adaptive_ctc = AdaptiveCTC(nominal_model, kp=100, kd=20, learning_rate=0.3)

print("Adaptive CTC controller created")

Expected: AdaptiveCTC class created with adaptation mechanism.

Step 5: Test Adaptive Controllerโ€‹

Run and compare with standard CTC:

def run_adaptive_test(model, data, controller, q_target, duration=10.0):
"""Run adaptive control test with extended duration for adaptation."""
dt = model.opt.timestep
n_steps = int(duration / dt)
nv = model.nv

results = {
'time': np.zeros(n_steps),
'position': np.zeros((n_steps, nv)),
'error': np.zeros((n_steps, nv)),
'torque': np.zeros((n_steps, nv)),
'mass_scale': np.zeros(n_steps)
}

mujoco.mj_resetData(model, data)

for i in range(n_steps):
q = data.qpos[:nv].copy()
qd = data.qvel[:nv].copy()

tau, info = controller.compute(q, qd, q_target, np.zeros(nv))
data.ctrl[:nv] = tau

results['time'][i] = data.time
results['position'][i] = q
results['error'][i] = info['error']
results['torque'][i] = tau
results['mass_scale'][i] = info['mass_scale']

mujoco.mj_step(model, data)

return results

# Run adaptive controller (longer duration to allow adaptation)
results_adaptive = run_adaptive_test(model, data, adaptive_ctc, target, duration=10.0)

print(f"\nAdaptive CTC Results:")
print(f"Final error: {np.degrees(results_adaptive['error'][-1])} deg")
print(f"Final mass scale estimate: {results_adaptive['mass_scale'][-1]:.3f}")
print(f"True mass scale: 1.5 (50% heavier)")

Expected: Error should decrease over time as mass estimate converges toward 1.5.

Step 6: Analyze Adaptation Convergenceโ€‹

Visualize the learning process:

def plot_adaptive_comparison(results_standard, results_adaptive, true_scale=1.5):
"""Plot comparison of standard vs adaptive control."""
fig, axes = plt.subplots(3, 1, figsize=(12, 12))

# Error comparison
axes[0].plot(results_standard['time'], np.degrees(results_standard['error'][:, 0]),
'r-', linewidth=2, label='Standard CTC - Joint 0')
axes[0].plot(results_adaptive['time'], np.degrees(results_adaptive['error'][:, 0]),
'b-', linewidth=2, label='Adaptive CTC - Joint 0')
axes[0].set_ylabel('Error (deg)')
axes[0].set_title('Tracking Error Comparison (50% Mass Uncertainty)')
axes[0].legend()
axes[0].grid(True)

# Position tracking
axes[1].plot(results_adaptive['time'], np.degrees(results_adaptive['position'][:, 0]),
'b-', linewidth=2, label='Actual')
axes[1].axhline(y=np.degrees(target[0]), color='k', linestyle='--', label='Target')
axes[1].set_ylabel('Position (deg)')
axes[1].set_title('Joint 0 Position (Adaptive)')
axes[1].legend()
axes[1].grid(True)

# Parameter adaptation
axes[2].plot(results_adaptive['time'], results_adaptive['mass_scale'],
'g-', linewidth=2, label='Estimated')
axes[2].axhline(y=true_scale, color='r', linestyle='--', linewidth=2, label='True')
axes[2].axhline(y=1.0, color='k', linestyle=':', alpha=0.5, label='Nominal')
axes[2].set_xlabel('Time (s)')
axes[2].set_ylabel('Mass Scale Factor')
axes[2].set_title('Parameter Adaptation')
axes[2].legend()
axes[2].grid(True)

plt.tight_layout()
plt.savefig('adaptive_control_results.png', dpi=150)
plt.show()

# Extend standard results for fair comparison (need same length)
results_standard_long = run_control_test(model, data, standard_ctc, target, duration=10.0)

plot_adaptive_comparison(results_standard_long, results_adaptive, true_scale=1.5)

# Compute convergence metrics
final_error_std = np.linalg.norm(results_standard_long['error'][-100:].mean(axis=0))
final_error_adapt = np.linalg.norm(results_adaptive['error'][-100:].mean(axis=0))

print(f"\nConvergence Analysis:")
print(f"Standard CTC average final error: {np.degrees(final_error_std):.3f} deg")
print(f"Adaptive CTC average final error: {np.degrees(final_error_adapt):.3f} deg")
print(f"Improvement: {(final_error_std - final_error_adapt) / final_error_std * 100:.1f}%")

Expected: Adaptive controller shows decreasing error and mass estimate approaching 1.5.

Expected Outcomesโ€‹

After completing this lab, you should have:

  1. Code artifacts:

    • adaptive_controller.py: Adaptive CTC implementation
    • parameter_estimator.py: Online estimation class
  2. Visual outputs:

    • adaptive_control_results.png: Comparison showing adaptation benefits
  3. Understanding:

    • How model uncertainty degrades control
    • Online parameter estimation principles
    • Stability considerations in adaptive systems
    • Trade-offs between learning rate and stability

Rubricโ€‹

CriterionPointsDescription
Model Perturbation10Correctly creates model mismatch scenario
Standard CTC Test15Demonstrates degraded performance
Adaptive Law30Proper gradient-based parameter update
Adaptive Controller25Working integration of adaptation with CTC
Convergence Analysis20Clear visualization and metrics
Total100

Common Errorsโ€‹

Error: Parameters diverge or oscillate Solution: Reduce learning rate (gamma). Too fast adaptation causes instability.

Error: Adaptation too slow Solution: Increase learning rate or ensure regressor is properly scaled.

Error: Estimate converges to wrong value Solution: Check regressor computation. May need richer excitation (varied trajectories).

Extensionsโ€‹

For advanced students:

  1. Multi-parameter Estimation: Estimate separate scales for each link
  2. Robust Adaptive Control: Add sliding mode term for unmodeled dynamics
  3. Persistent Excitation: Analyze when parameters are identifiable
  4. Neural Network Adaptation: Replace linear adaptation with learned model
  • Theory: Module 05 theory.md, Section 5.6 (Adaptive Control)
  • Previous Labs: Lab 05-01 (PID), Lab 05-02 (CTC)
  • Application: See MIT Humanoid Lab case study for adaptive locomotion control