Autonomy Stack (Real Robot)
This project is a “racing-style” autonomy pipeline: generate feasible motion candidates fast, then apply optimization-based control to execute them safely and smoothly on hardware. I implemented both a general MPC tracker (for arbitrary trajectories) and an MPCC controller (for racing line following + progress maximization).
The key engineering decision: separate “what to do next” (trajectory choice) from “how to execute” (MPC/MPCC optimization), so each component stays debuggable and swappable.
Platform: RoboRacer F1TENTH (Ackermann steering).
Control published as AckermannDriveStamped
with steering angle and speed. Robot pose obtained via TF:
map → ego_racecar/base_link.
This is not simulation-only control. Constraints, timing, TF availability, and safety margins (distance-to-obstacle) directly affect whether the robot runs cleanly on track.
Dynamic Trajectory Generation (RK4 Rollouts + Distance Transform)
The trajectory generator samples steering commands \( \delta \) across the feasible range and forward-simulates the bicycle model for a fixed horizon \(N\) with timestep \(\Delta t\). Each rollout produces a candidate path \(\{(x_k,y_k,\theta_k)\}_{k=1}^N\) which is scored using obstacle clearance from a distance transform map and penalties for curvature and goal deviation.
Integration is done via RK4: \(x_{k+1}=x_k+\frac{\Delta t}{6}(k_1+2k_2+2k_3+k_4)\) (applied to all state components), which reduces numerical drift compared to Euler at higher speeds / longer horizons.
From an occupancy grid, free cells are binarized and passed through an Euclidean distance transform \(d(x,y)\), giving approximate clearance (in meters) for each map cell. Any rollout with \(\min_k d(x_k,y_k) < d_{\text{safe}}\) is rejected.
A simple, interpretable objective works well for fast online selection:
- Clearance term prefers trajectories farther from obstacles.
- Curvature term discourages aggressive yaw oscillations.
- Goal term pulls the rollout endpoint toward a target.
The best rollout is published as nav_msgs/Path on
/dynamic_trajectory, which becomes the MPC reference.
Nonlinear MPC Tracking (CasADi + IPOPT)
The MPC tracker consumes the reference path and solves a finite-horizon nonlinear optimization problem every control cycle. The state includes pose and speed: \(\mathbf{x}=[x, y, \psi, v]^T\). Controls are commanded speed and steering: \(\mathbf{u}=[v_c,\delta]^T\).
The model uses a small slip-angle approximation: \(\beta=\tan^{-1}\!\left(\frac{L_r}{L}\tan\delta\right)\).
Minimize tracking error + control effort with input bounds:
Implemented with CasADi symbolic variables and solved using IPOPT. The first control action \((v_0,\delta_0)\) is applied (receding horizon control).
Model Predictive Contouring Control (MPCC)
MPCC differs from standard tracking MPC by introducing a progress state \(\theta\) (arc-length along the centerline) and penalizing contouring and lag errors relative to the racing line. The optimizer simultaneously decides how to steer and how quickly to advance along the track.
Augmented state: \(\mathbf{x}=[x,y,\psi,v,\theta]^T\), with progress update: \(\theta_{k+1}=\theta_k+v_k\Delta t\).
Let the nearest centerline reference be \((x_{cl},y_{cl},\phi_{cl},s_{cl})\). With \(dx=x-x_{cl}\), \(dy=y-y_{cl}\):
Penalize contouring/lag errors and encourage progress by rewarding \(\theta\) toward \(s_{cl}\):
In practice: MPCC “doesn’t blindly chase waypoints”; it optimizes a race-style tradeoff between staying near the line and maximizing forward progress.
- Explicit progress makes the controller “want” to move forward, not just reduce error.
- Stable at speed because it avoids overreacting to noisy reference points.
- Racing line behavior: controls naturally balance corner cutting vs stability.
/racing_trajectory→ custom Trajectory msg (with arc-length \(s\))/mpcc_predicted_horizon→ MarkerArray (visual horizon points)/drive→ AckermannDriveStamped (applied control)
Key Equations (Quick Reference)
| Module | Equation | Purpose |
|---|---|---|
| Planner | \(\dot{\theta}=\frac{v}{L}\tan\delta\) | Rollout curvature / turning |
| Planner | \(\min_k d(x_k,y_k)\ge d_{\text{safe}}\) | Obstacle safety margin |
| MPC | \(\min \sum \|\mathbf{x}-\mathbf{x}^{ref}\|_Q^2+\|\mathbf{u}\|_R^2\) | Trajectory tracking |
| MPCC | \(\varepsilon_c=\sin\phi\,dx-\cos\phi\,dy\) | Contouring error |
| MPCC | \(\varepsilon_l=-\cos\phi\,dx-\sin\phi\,dy\) | Lag error |
| MPCC | \(\theta_{k+1}=\theta_k+v_k\Delta t\) | Progress along track |
This page uses KaTeX (already included in <head>). Use inline math with
\( ... \)
and block math with $$ ... $$. No additional LaTeX extensions are needed beyond KaTeX.