slam_toolbox: ros__parameters: use_sim_time: true # ── Solver ────────────────────────────────────────────────────────────── solver_plugin: solver_plugins::CeresSolver ceres_linear_solver: SPARSE_NORMAL_CHOLESKY ceres_preconditioner: SCHUR_JACOBI ceres_trust_strategy: LEVENBERG_MARQUARDT ceres_dogleg_type: TRADITIONAL_DOGLEG ceres_loss_function: None # ── Frames ────────────────────────────────────────────────────────────── odom_frame: odom map_frame: map base_frame: base_footprint scan_topic: /scan # ── Mode ──────────────────────────────────────────────────────────────── # mapping — build a new map; publishes /map and /map_metadata # localization — localise in a previously-saved map (load with map_server) # lifelong — continuous mapping with loop closure; memory-intensive mode: mapping # ── Map parameters ────────────────────────────────────────────────────── resolution: 0.05 # metres per pixel — 5 cm is good for indoor navigation max_laser_range: 12.0 # m — matches RPLIDAR A1 spec; trim to actual room size map_update_interval: 5.0 # seconds between map publishes # ── Timing / TF ───────────────────────────────────────────────────────── transform_publish_period: 0.02 # seconds (50 Hz) — map → odom TF publish rate transform_timeout: 0.2 # seconds — how long to wait for a TF lookup tf_buffer_duration: 30.0 # seconds — TF history kept in memory throttle_scans: 1 # process every Nth scan (1 = all) minimum_time_interval: 0.5 # seconds — minimum gap between processed scans # ── Scan matching ──────────────────────────────────────────────────────── use_scan_matching: true use_scan_barycenter: true # How far the robot must move/turn before adding a new node to the graph minimum_travel_distance: 0.5 # m minimum_travel_heading: 0.5 # rad (~29°) # Scan buffer — larger = more context for loop closure but more memory scan_buffer_size: 10 scan_buffer_maximum_scan_distance: 10.0 # m # Matching quality thresholds link_match_minimum_response_fine: 0.1 distance_variance_penalty: 0.5 angle_variance_penalty: 1.0 # Angular search parameters fine_search_angle_offset: 0.00349 # rad (~0.2°) coarse_search_angle_offset: 0.349 # rad (~20°) coarse_angle_resolution: 0.0349 # rad (~2°) minimum_angle_penalty: 0.9 minimum_distance_penalty: 0.5 use_response_expansion: true debug_logging: false stack_size_to_use: 40000000 # bytes — increase if you see stack overflows