slam_params.yaml 2.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980
  1. # Copyright (c) Contributors to the Open 3D Engine Project.
  2. # For complete copyright and license terms please see the LICENSE at the root of this distribution.
  3. #
  4. # SPDX-License-Identifier: Apache-2.0 OR MIT
  5. #
  6. #
  7. slam_toolbox:
  8. ros__parameters:
  9. # Plugin params
  10. solver_plugin: solver_plugins::CeresSolver
  11. ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
  12. ceres_preconditioner: SCHUR_JACOBI
  13. ceres_trust_strategy: LEVENBERG_MARQUARDT
  14. ceres_dogleg_type: TRADITIONAL_DOGLEG
  15. ceres_loss_function: None
  16. # ROS Parameters
  17. odom_frame: odom
  18. map_frame: map
  19. base_frame: base_link
  20. scan_topic: /scan
  21. mode: mapping #localization
  22. # if you'd like to immediately start continuing a map at a given pose
  23. # or at the dock, but they are mutually exclusive, if pose is given
  24. # will use pose
  25. #map_file_name: test_steve
  26. # map_start_pose: [0.0, 0.0, 0.0]
  27. #map_start_at_dock: true
  28. debug_logging: false
  29. throttle_scans: 1
  30. transform_publish_period: 0.02 #if 0 never publishes odometry
  31. map_update_interval: 5.0
  32. resolution: 0.05
  33. max_laser_range: 20.0 #for rastering images
  34. minimum_time_interval: 0.5
  35. transform_timeout: 0.2
  36. tf_buffer_duration: 30.
  37. stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
  38. enable_interactive_mode: true
  39. # General Parameters
  40. use_scan_matching: true
  41. use_scan_barycenter: true
  42. minimum_travel_distance: 0.5
  43. minimum_travel_heading: 0.5
  44. scan_buffer_size: 10
  45. scan_buffer_maximum_scan_distance: 10.0
  46. link_match_minimum_response_fine: 0.1
  47. link_scan_maximum_distance: 1.5
  48. loop_search_maximum_distance: 3.0
  49. do_loop_closing: true
  50. loop_match_minimum_chain_size: 10
  51. loop_match_maximum_variance_coarse: 3.0
  52. loop_match_minimum_response_coarse: 0.35
  53. loop_match_minimum_response_fine: 0.45
  54. # Correlation Parameters - Correlation Parameters
  55. correlation_search_space_dimension: 0.5
  56. correlation_search_space_resolution: 0.01
  57. correlation_search_space_smear_deviation: 0.1
  58. # Correlation Parameters - Loop Closure Parameters
  59. loop_search_space_dimension: 8.0
  60. loop_search_space_resolution: 0.05
  61. loop_search_space_smear_deviation: 0.03
  62. # Scan Matcher Parameters
  63. distance_variance_penalty: 0.5
  64. angle_variance_penalty: 1.0
  65. fine_search_angle_offset: 0.00349
  66. coarse_search_angle_offset: 0.349
  67. coarse_angle_resolution: 0.0349
  68. minimum_angle_penalty: 0.9
  69. minimum_distance_penalty: 0.5
  70. use_response_expansion: true