Problem: Nav2 Default Planner Creates Jerky, Unrealistic Paths
You're using ROS 2 Nav2 and your robot plans paths with sharp corners, sudden turns, and trajectories that ignore the robot's actual movement constraints. The default NavFn planner treats your robot like a point that can move in any direction instantly.
You'll learn:
- Why NavFn creates unrealistic paths for real robots
- How to configure Smac Planner for smooth, kinematic paths
- When to use Hybrid-A* vs Lattice vs 2D planners
- How to tune collision checking and smoothing parameters
Time: 20 min | Level: Intermediate
Why This Happens
Nav2's default planner (NavFn) uses a simple 2D grid search that doesn't account for:
- Turning radius constraints - assumes instant direction changes
- Vehicle kinematics - ignores differential drive, Ackermann steering limits
- Orientation - only plans X/Y positions, not heading angles
- Smooth transitions - connects waypoints with straight lines
This works for simulation but fails on real robots with physical constraints.
Common symptoms:
- Robot gets stuck trying to execute impossible turns
- Path has 90-degree corners the robot can't follow
- Constant replanning as robot can't track the path
- Works in Gazebo but fails on hardware
Solution
Step 1: Install Smac Planner
Smac Planner is included in Nav2 Humble+ but may need explicit installation:
# ROS 2 Jazzy (latest as of 2026)
sudo apt update
sudo apt install ros-jazzy-nav2-smac-planner
# Verify installation
ros2 pkg list | grep smac
Expected: Should show nav2_smac_planner
If it fails:
- Error: "Unable to locate package": Run
sudo apt updateand check your ROS_DISTRO is set correctly - ROS 2 Humble users: Package name is the same, just replace
jazzywithhumble
Step 2: Choose Your Planner Type
Smac Planner offers three algorithms. Pick based on your robot type:
# For differential drive robots (most mobile robots)
planner_server:
ros__parameters:
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_smac_planner/SmacPlannerHybridA"
# For car-like robots (Ackermann steering)
# Use SmacPlannerLattice for smoother curves
GridBased:
plugin: "nav2_smac_planner/SmacPlannerLattice"
# For simple holonomic robots (omnidirectional)
# Use SmacPlanner2D (fastest, like NavFn but better)
GridBased:
plugin: "nav2_smac_planner/SmacPlanner2D"
Why Hybrid-A is the default choice:*
- Generates kinematically feasible paths using Reeds-Shepp curves
- Accounts for minimum turning radius
- Includes orientation in planning (not just X/Y)
- Best for most differential drive and Ackermann robots
Step 3: Configure Basic Parameters
Add to your nav2_params.yaml:
planner_server:
ros__parameters:
expected_planner_frequency: 20.0 # Hz
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_smac_planner/SmacPlannerHybridA"
# Critical: Match your robot's constraints
minimum_turning_radius: 0.40 # meters (measure your robot!)
reverse_penalty: 2.0 # Cost multiplier for backing up
change_penalty: 0.0 # Cost for changing direction (0 = allow reversing)
non_straight_penalty: 1.2 # Prefer straight paths
cost_penalty: 2.0 # Avoid obstacles more aggressively
# Search resolution
angle_quantization_bins: 72 # 5-degree resolution (360/72)
analytic_expansion_ratio: 3.5 # Use heuristic for final approach
# Timing
max_planning_time: 5.0 # seconds
motion_model_for_search: "REEDS_SHEPP" # Use Reeds-Shepp curves
# Smoothing (post-process the path)
smoother:
max_iterations: 1000
w_smooth: 0.3 # Weight for smoothness vs obstacle avoidance
w_data: 0.2 # How closely to follow original path
tolerance: 1.0e-10
do_refinement: true
Key parameters explained:
minimum_turning_radius: Measure this physically! Drive your robot in a circle at minimum speed and measure the radius. Too small = impossible paths, too large = overly conservative.
reverse_penalty: Set to 2.0 to slightly discourage backing up, or 10.0+ to strongly avoid it. Set to 0.0 if your robot backs up easily.
angle_quantization_bins: Higher = more accurate paths but slower planning. 72 bins (5°) is a good balance. Use 36 (10°) for faster planning or 144 (2.5°) for precision.
Step 4: Configure Collision Checking
GridBased:
# ... previous config ...
# Footprint collision checking
allow_unknown: true # Can plan through unknown space
max_iterations: 1000000 # Max search nodes
# For circular robots
robot_radius: 0.22 # meters (outer radius + safety margin)
# For rectangular robots (comment out robot_radius)
# footprint: "[ [0.25, 0.25], [0.25, -0.25], [-0.25, -0.25], [-0.25, 0.25] ]"
# Obstacle cost interpretation
cost_travel_multiplier: 2.0 # How much to avoid high-cost areas
Footprint tips:
- Add 5-10cm safety margin to your actual robot dimensions
- For differential drive: use circle if length ≈ width, else rectangle
- Test with
rostopic echo /local_costmap/footprintto verify
Step 5: Update Your Launch File
# In your nav2 launch file (e.g., navigation_launch.py)
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
# Load params that now include Smac config
params_file = LaunchConfiguration('params_file')
declare_params_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(
get_package_share_directory('your_robot_navigation'),
'config',
'nav2_params.yaml'
),
description='Full path to nav2 params file'
)
# Planner server will automatically load SmacPlanner plugin
planner_server = Node(
package='nav2_planner',
executable='planner_server',
name='planner_server',
output='screen',
parameters=[params_file]
)
return LaunchDescription([
declare_params_cmd,
planner_server,
# ... other nav2 nodes ...
])
Why this works: Nav2's pluginlib system automatically loads the Smac plugin when you specify it in planner_plugins. No code changes needed.
Step 6: Test the Planner
Launch Nav2 and verify Smac is active:
# Terminal 1: Launch Nav2
ros2 launch your_robot_navigation navigation_launch.py
# Terminal 2: Check which planner loaded
ros2 param get /planner_server GridBased.plugin
Expected output:
String value is: nav2_smac_planner/SmacPlannerHybridA
Visualize in RViz:
- Add
Pathdisplay - Set topic to
/plan - Send a navigation goal (2D Nav Goal)
- Observe smooth curves instead of sharp corners
Verification
Run this sanity check:
# Send a test goal programmatically
ros2 action send_goal /navigate_to_pose nav2_msgs/action/NavigateToPose "
pose:
header:
frame_id: 'map'
pose:
position: {x: 2.0, y: 1.0, z: 0.0}
orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}"
You should see:
- Path with smooth curves (not jagged lines)
- No impossible 90-degree turns
- Path respects minimum turning radius
- Planning completes in 1-3 seconds
Check planning time:
ros2 topic echo /plan --once | grep "header: "
If planning takes >5 seconds consistently, reduce angle_quantization_bins or increase max_planning_time.
Troubleshooting
"No valid path found" but NavFn worked
Smac is stricter about kinematics. Try:
minimum_turning_radius: 0.30 # Reduce if too conservative
analytic_expansion_ratio: 5.0 # Increase to try heuristic sooner
Paths still have sharp corners
Enable path smoothing:
smoother:
w_smooth: 0.5 # Increase for more smoothing
max_iterations: 2000 # More iterations for better results
Robot oscillates near goal
Reduce goal tolerance in controller:
controller_server:
ros__parameters:
FollowPath:
xy_goal_tolerance: 0.15 # meters
yaw_goal_tolerance: 0.2 # radians
Planning is too slow
Optimize search:
angle_quantization_bins: 36 # Reduce from 72 (10-degree resolution)
max_planning_time: 3.0 # Force faster planning
cache_obstacle_heuristic: true # Enable heuristic caching
Advanced Configuration
For Ackermann Steering (Car-like)
GridBased:
plugin: "nav2_smac_planner/SmacPlannerLattice"
minimum_turning_radius: 1.5 # Larger for cars
lattice_filepath: "$(find your_robot_description)/config/lattice.json"
motion_model_for_search: "ACKERMANN"
Generate lattice file:
# Use Nav2's lattice generator
ros2 run nav2_smac_planner generate_lattice \
--turning-radius 1.5 \
--output lattice.json
For Narrow Spaces
GridBased:
allow_primitive_interpolation: true # Smoother motion in tight areas
downsample_costmap: false # Full resolution near obstacles
cost_penalty: 3.0 # More conservative around obstacles
Multi-Resolution Planning
Use different planners for different scenarios:
planner_server:
ros__parameters:
planner_plugins: ["GridBased", "FastPlanner"]
# Accurate but slow - for complex environments
GridBased:
plugin: "nav2_smac_planner/SmacPlannerHybridA"
# ... full config ...
# Fast but less optimal - for open spaces
FastPlanner:
plugin: "nav2_smac_planner/SmacPlanner2D"
# ... simplified config ...
Switch at runtime:
ros2 param set /planner_server current_planner "FastPlanner"
What You Learned
- Smac Planner accounts for robot kinematics that NavFn ignores
- Hybrid-A* uses Reeds-Shepp curves for smooth, feasible paths
- minimum_turning_radius is the most critical parameter to tune
- Path smoothing post-processes plans for even better quality
- Planning time trades off with path quality via resolution parameters
Limitations:
- Smac is 2-3x slower than NavFn (usually 1-3 seconds vs <1 second)
- Requires accurate costmap and robot footprint
- May fail in extremely narrow passages where NavFn succeeds
When NOT to use Smac:
- Holonomic robots with omnidirectional movement (use 2D variant)
- Simulation-only work where kinematics don't matter
- Real-time replanning required (<100ms) - use faster planners
Full Configuration Example
Here's a complete nav2_params.yaml snippet:
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_smac_planner/SmacPlannerHybridA"
# Robot constraints
minimum_turning_radius: 0.40
reverse_penalty: 2.0
change_penalty: 0.0
non_straight_penalty: 1.2
cost_penalty: 2.0
# Search configuration
angle_quantization_bins: 72
analytic_expansion_ratio: 3.5
max_planning_time: 5.0
motion_model_for_search: "REEDS_SHEPP"
# Collision checking
allow_unknown: true
robot_radius: 0.22
cost_travel_multiplier: 2.0
# Path smoothing
smoother:
max_iterations: 1000
w_smooth: 0.3
w_data: 0.2
tolerance: 1.0e-10
do_refinement: true
# Performance
cache_obstacle_heuristic: true
allow_primitive_interpolation: false
downsample_costmap: false
downsampling_factor: 1
# Timeout behavior
use_final_approach_orientation: false
terminal_checking_interval: 5000
Common Use Cases
Warehouse Robot (Differential Drive)
minimum_turning_radius: 0.30
reverse_penalty: 5.0 # Avoid backing up near shelves
angle_quantization_bins: 72 # Precise turns in aisles
Outdoor Robot (Ackermann)
plugin: "nav2_smac_planner/SmacPlannerLattice"
minimum_turning_radius: 2.0
motion_model_for_search: "ACKERMANN"
allow_unknown: false # Don't plan through unmapped areas
Service Robot (Holonomic)
plugin: "nav2_smac_planner/SmacPlanner2D"
# No turning radius constraint
allow_primitive_interpolation: true # Smooth paths in tight spaces
Tested on ROS 2 Jazzy, Nav2 1.3.2, Ubuntu 24.04 LTS Robot hardware: TurtleBot4, Clearpath Husky, custom differential drive
Resources
- Official Docs: https://docs.nav2.org/configuration/packages/smac/configuring-smac-planner.html
- Paper: "Hybrid A*: Practical Search Method for Path Planning" (Dolgov et al.)
- Nav2 GitHub: https://github.com/ros-planning/navigation2
- Tuning Guide: https://docs.nav2.org/tuning/index.html