Skip to content

Commit

Permalink
testing some params -rough performance gain
Browse files Browse the repository at this point in the history
  • Loading branch information
b1n-ch1kn committed Jul 17, 2024
1 parent 6553956 commit 51bfcc5
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions src/navigation/nav_bringup/config/slam_toolbox_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ slam_toolbox_node:
enable_interactive_mode: false # Interactive mode will retain a cache of laser scans mapped to their ID for visualization in interactive mode
position_covariance_scale: 2.0 # This can be used to tune the influence of the pose position in a downstream localization filter
yaw_covariance_scale: 1.5 # Pose yaw
resolution: 0.05 # Resolution of the 2D occupancy map to generate
resolution: 0.1 # Resolution of the 2D occupancy map to generate
max_laser_range: 25.0 # Maximum laser range to use for 2D occupancy map rastering
minimum_time_interval: 0.1 # The minimum duration of time between scans to be processed in synchronous mode
transform_timeout: 0.5 # TF timeout for looking up transforms
Expand All @@ -38,10 +38,10 @@ slam_toolbox_node:
use_scan_matching: true # Whether to use scan matching to refine odometric pose
use_scan_barycenter: false # Whether to use the barycenter or scan pose

minimum_travel_distance: 0.05 # Minimum distance of travel before processing a new scan
minimum_travel_heading: 0.2 # Minimum changing in heading to justify an update
minimum_travel_distance: 0.1 # Minimum distance of travel before processing a new scan
minimum_travel_heading: 0.1 # Minimum changing in heading to justify an update

scan_buffer_size: 10 # The number of scans to buffer into a chain, also used as the number of scans in the circular buffer of localization mode
scan_buffer_size: 20 # The number of scans to buffer into a chain, also used as the number of scans in the circular buffer of localization mode
scan_buffer_maximum_scan_distance: 10.0 # Maximum distance of a scan from the pose before removing the scan from the buffer

link_match_minimum_response_fine: 0.1 # The threshold link matching algorithm response for fine resolution to pass
Expand All @@ -63,7 +63,7 @@ slam_toolbox_node:
loop_search_space_smear_deviation: 0.03 # A penalty to apply to a matched scan as it differs from the odometric pose

distance_variance_penalty: 0.5 # A penalty to apply to a matched scan as it differs from the odometric pose
angle_variance_penalty: 1.0 # A penalty to apply to a matched scan as it differs from the odometric pose
angle_variance_penalty: 0.6 # A penalty to apply to a matched scan as it differs from the odometric pose

fine_search_angle_offset: 0.00349 # Range of angles to test for fine scan matching
coarse_search_angle_offset: 0.349 # Range of angles to test for coarse scan matching
Expand Down

0 comments on commit 51bfcc5

Please sign in to comment.