Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
65 changes: 65 additions & 0 deletions config/slam_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
slam_toolbox:
ros__parameters:
# Plugin params
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 #HuberLoss

# ROS Parameters
odom_frame: odom
map_frame: map
base_frame: base_link
scan_topic: /scan
mode: mapping #localization

debug_logging: false
throttle_scans: 1
transform_publish_period: 0.04
map_update_interval: 1.0
resolution: 0.05
max_laser_range: 12.0 #for rastering images
minimum_time_interval: 0.05
transform_timeout: 0.1
tf_buffer_duration: 20.0
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
enable_interactive_mode: false

# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.2
minimum_travel_heading: 0.1
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 0.5
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 0.75
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45

# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1

# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03

# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0

fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true
1 change: 1 addition & 0 deletions turtlebot3c-gadget/gadget/gadget-amd64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ defaults:
simulation: "True"
navigation-config: "https://raw.githubusercontent.com/ubuntu-robotics/turtlebot3c-ubuntu-core/refs/heads/humble-virtual/config/nav2_params.yaml"
localization-config: "https://raw.githubusercontent.com/ubuntu-robotics/turtlebot3c-ubuntu-core/refs/heads/humble-virtual/config/localization_params.yaml"
slam-config: "https://raw.githubusercontent.com/ubuntu-robotics/turtlebot3c-ubuntu-core/refs/heads/humble-virtual/config/slam_params.yaml"

connections:
# robot-model-server <-> turtlebot3c-model
Expand Down
1 change: 1 addition & 0 deletions turtlebot3c-gadget/gadget/gadget-arm64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ defaults:
simulation: "True"
navigation-config: "https://raw.githubusercontent.com/ubuntu-robotics/turtlebot3c-ubuntu-core/refs/heads/humble-virtual/config/nav2_params.yaml"
localization-config: "https://raw.githubusercontent.com/ubuntu-robotics/turtlebot3c-ubuntu-core/refs/heads/humble-virtual/config/localization_params.yaml"
slam-config: "https://raw.githubusercontent.com/ubuntu-robotics/turtlebot3c-ubuntu-core/refs/heads/humble-virtual/config/slam_params.yaml"

connections:
# robot-model-server <-> turtlebot3c-model
Expand Down