Regulated Pure Pursuit: The nav2 Default Controller — 3 Regulation Mechanisms Deep Dive
Curvature, proximity, and preemptive collision regulation — 85% path error reduction over vanilla Pure Pursuit
TL;DR
RPP (Regulated Pure Pursuit) is a mobile robot path tracking controller published by Steve Macenski et al. (Samsung Research) in 2023 (arXiv:2305.20026). It extends Adaptive Pure Pursuit with three safety-critical regulation mechanisms: (1) Curvature-based velocity regulation — auto-decelerate before sharp turns, (2) Obstacle proximity regulation — slow down near obstacles, (3) Preemptive arc collision detection — project forward trajectory to detect collisions before they happen. Integrated as the default controller in ROS 2 nav2. On a PAL Tiago real robot, RPP reduces path tracking error by 85% compared to vanilla Pure Pursuit (0.19m → 0.03m) with no meaningful increase in travel time.
Background: What's Wrong with Pure Pursuit
Pure Pursuit is a classic path tracking algorithm proposed by Craig Coulter in 1992. The idea is elegantly simple:
Find the point on the path that is exactly `lookahead distance` ahead of the robot.
Compute the circular arc from the robot's current pose to that carrot point.
Drive that arc.
Steering angle = arctan(2L·sin(α) / ld)
L = robot wheelbase
α = angle between heading and carrot point
ld = lookahead distance
Simple and computationally cheap — but falls apart in real deployments:
| Problem | Situation | Outcome |
| No velocity awareness | High speed + sharp turn | Path deviation, sliding |
| Blind corners | Hallway intersection | Pedestrian collision |
| No obstacle proximity | Passing near people | Too-fast close approach |
| No collision detection | Sudden obstacle on path | Runs straight into it |
Adaptive Pure Pursuit (APP) improved one thing: lookahead distance scales with velocity (ld = v · lt), so faster speeds look farther ahead. But it still doesn't regulate velocity itself — the robot blasts through corners at full speed with just a longer lookahead.
RPP adds three regulation layers on top of APP to address the remaining problems.
Core Algorithm: Regulated Pure Pursuit
1. Adaptive Lookahead (inherited from APP)
Lookahead distance:
ld = v · lt (velocity-proportional dynamic lookahead)
v : current linear velocity
lt : lookahead time gain (default 1.5s)
Clamped to: [ld_min, ld_max] = [0.3m, 0.9m]
At high speed, the robot looks far ahead. At low speed, it tracks closely. Both high-speed straight lines and low-speed tight turns are handled naturally.
2. Curvature-Based Velocity Regulation
When path curvature (κ) exceeds a threshold, linear velocity is automatically reduced:
κ = 2 · sin(α) / ld (geometric curvature from Pure Pursuit geometry)
Curvature regulation:
if κ > T_κ:
v_regulated = v_max · (1 / (κ · regulated_linear_scaling_min_radius))
regulated_linear_scaling_min_radius default: 0.9m
What this means in practice: At hallway intersections or tight U-turns, the robot automatically slows by 30–50% before entering the curve. "Blind corners" — where the space beyond the turn is not yet visible — are no longer approached at full speed.
Experimental result: RPP achieves 33% greater stopping distance at the same corner compared to APP.
3. Obstacle Proximity Velocity Regulation
Reads costmap obstacle cost to reduce velocity near obstacles:
if d_obstacle ≤ d_prox:
v' = v · α · (d_obstacle / d_prox)
d_prox : regulation start distance (default 0.6m)
α : cost_scaling_gain (default 1.0)
Since it uses the costmap, it handles both static obstacles (walls, shelves) and dynamic obstacles (people) through the same mechanism.
Experimental result: In confined corridor experiments, 14% less path tracking error than APP; robot maintains safer distance from obstacles.
4. Preemptive Arc Collision Detection
Old approach: check space ahead up to lookahead distance (spatial projection).
RPP approach: project forward in time — simulate the circular arc the robot would travel for T seconds at current velocity; if any point on that arc is occupied, stop:
Simulated arc:
for t in [0, T_max]: (T_max default 1.0s)
x(t) = x₀ + ∫v·cos(θ) dt
y(t) = y₀ + ∫v·sin(θ) dt
if costmap[x(t), y(t)] > collision_threshold:
STOP
Why this is better: Spatial projection is fixed regardless of speed. Temporal projection extends farther at higher speeds — safety margin automatically scales with velocity.
Full Control Loop
[Every control cycle]
1. Find lookahead carrot point on path
ld = clamp(v · lt, ld_min, ld_max)
2. Set base velocity
v = v_max
3. Apply curvature regulation
κ = curvature(carrot_point)
if κ > T_κ: v = min(v, v_curvature_regulated)
4. Apply proximity regulation
d_obs = nearest_obstacle_distance()
if d_obs < d_prox: v = min(v, v_proximity_regulated)
5. Preemptive collision check
if arc_collision_check(v): v = 0 (STOP)
6. Compute steering
ω = v · κ ← uses REGULATED v, not v_max
7. Publish velocity command: (v, ω)
Step 6 is the key difference from APP: APP computes steering at max velocity, then decelerates separately. RPP computes steering using the already-regulated velocity → velocity and steering are consistent, preventing undershoot on regulated velocity commands.
nav2 Parameter Reference
Shipped as nav2_regulated_pure_pursuit_controller in ROS 2 nav2:
RegulatedPurePursuitController:
# Lookahead
use_velocity_scaled_lookahead_dist: true
min_lookahead_dist: 0.3
max_lookahead_dist: 0.9
lookahead_time: 1.5
# Curvature regulation
use_regulated_linear_velocity_scaling: true
regulated_linear_scaling_min_radius: 0.9
# Proximity regulation
use_cost_regulated_linear_velocity_scaling: true
cost_scaling_dist: 0.6
cost_scaling_gain: 1.0
# Collision detection
use_collision_detection: true
max_allowed_time_to_collision_up_to_carrot: 1.0
# Velocity limits
desired_linear_vel: 0.5
min_approach_linear_velocity: 0.05
Experimental Results
Platforms
- Simulation: Turtlebot 3 + Gazebo (ideal conditions, ground truth available)
- Real robot: PAL Robotics Tiago (industrial service robot, indoor environment)
Experiment 1: Path Tracking Accuracy
| Controller | Mean Path Error |
| PP (Pure Pursuit) | 0.19m |
| APP (Adaptive PP) | 0.09m |
| RPP (Regulated PP) | 0.03m |
85% error reduction vs. PP. 67% improvement vs. APP.
Experiment 2: Blind Corner Safety
Same corner scenario:
- RPP: 33% greater stopping distance (more collision buffer)
- Completion time nearly identical to APP — safety gain without speed penalty
Experiment 3: Confined Corridor
- RPP: 14% less path tracking error than APP
- Velocity heatmap visualization: deceleration only at corners; maximum speed maintained on straight segments
Experiment 4: Full System (Campus Building)
Real-world navigation through a campus building:
- Completion time: PP/APP/RPP all 85–95s (similar)
- Path deviation: RPP lowest at 0.043m mean
- Conclusion: safety and accuracy improvement with no meaningful travel time cost
Key Experiments
The Safety-Speed Trade-off Myth
RPP's central claim: "You don't have to go slow to be safe — you only slow down at the right moments."
Experimental data:
- Total travel time: PP ≈ APP ≈ RPP (85–95s)
- Path error: RPP 85% lower than PP
- Corner safety margin: RPP 33% larger
Simultaneous improvement in safety and accuracy without the assumed speed trade-off.
minimum_radius Parameter Sensitivity
Varying regulated_linear_scaling_min_radius from 0.5m to 1.5m:
- Small value: aggressive deceleration, very safe but slow
- Large value: minimal deceleration, fast but corner overshoot increases
- Default 0.9m is the empirical sweet spot
Limitations — A Field Engineer's Perspective
Algorithmic limitations:
No vehicle dynamics model: Common to all Pure Pursuit variants. For Ackermann-steered robots, minimum turning radius is a hard physical constraint not addressed geometrically — the path must be "feasibly drivable."
Path shortcutting persists: Sharp curves still get slightly cut compared to the planned path. Reduced vs. PP/APP, but not eliminated.
Costmap dependency: Proximity regulation quality is only as good as costmap quality. Sensor noise → inaccurate costmap → unnecessary deceleration or missed deceleration events.
Pure reactive, local controller: Responds to the path ahead. Complex global re-planning is delegated to the global planner layer.
Field engineering perspective:
Immediate nav2 availability: Available out of the box as
nav2_regulated_pure_pursuit_controller. Tune three parameters (min_radius, d_prox, lookahead_time) and most environments work well.DWB vs RPP: DWB (Dynamic Window Approach) is more flexible with dynamic obstacles but heavier and harder to configure. RPP is lighter and more predictable → right choice for indoor static environments and service robots.
Quadruped robots (Unitree Go2 etc.): RPP is the natural starting point when deploying nav2 on legged robots. Empirically, increase
min_lookahead_distslightly to compensate for foot-slip and gait irregularity.Start conservative: In field deployment, start with
desired_linear_vel: 0.2–0.3 m/s, verify stability, then increase. Tuneregulated_linear_scaling_min_radiusto match environment complexity.
The Lineage — Where RPP Sits
| Algorithm / Paper | Relationship |
| Pure Pursuit (Coulter 1992) | Foundation — simple geometric lookahead tracking |
| Adaptive Pure Pursuit (APP) | Velocity-proportional lookahead distance |
| DWB (Dynamic Window Approach) | nav2 alternative — dynamic constraints, heavier |
| TEB (Timed Elastic Band) | Full path optimization with time parametrization and vehicle dynamics |
| RPP (Macenski et al. 2023) | Curvature + proximity + collision regulation — nav2 default |
| nav2 MPPIController | Sample-based optimization; handles complex constraints |
| nav2 GracefulController | Nonholonomic constraints; natural deceleration curves |
RPP's position in the ecosystem: computational efficiency + intuitive parameter tuning makes it the de facto standard controller for nav2 production deployments.
Summary — Key Takeaways
Pure Pursuit + 3 regulations = practical safe controller — curvature regulation (corner deceleration), proximity regulation (obstacle deceleration), preemptive collision detection (arc projection). Each independently togglable, modular design.
Velocity-steering consistency is the key improvement — APP computes steering at max velocity then decelerates separately, causing undershoot. RPP computes steering at regulated velocity → actual trajectory matches intended path.
85% path error reduction vs. PP (0.19m → 0.03m) — safety improvement doesn't translate to travel time increase. Deceleration only at the right moments.
nav2 production-ready, 92% unit test coverage — plug-and-play without custom implementation. YAML parameter tuning is sufficient for most deployments.
Local reactive controller limitations are acknowledged, not papered over — vehicle dynamics, high-speed shortcutting, global re-planning: solved by other layers (global planner, MPPI). RPP doesn't try to do everything — that's its strength.
📚 Paper: arXiv:2305.20026
🤖 nav2 source: GitHub nav2_regulated_pure_pursuit_controller
📖 nav2 docs: Regulated Pure Pursuit — Nav2 Docs
Next post: GR00T — NVIDIA's humanoid foundation policy