forked from SteveMacenski/slam_toolbox
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
adding config files and launch files for lifelong
- Loading branch information
1 parent
3181785
commit b47e9e8
Showing
2 changed files
with
92 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,85 @@ | ||
|
||
# link_match_minimum_response_fine: 0.4 | ||
# link_scan_maximum_distance: 20.0 | ||
# loop_search_maximum_distance: 50.0 | ||
# distance_variance_penalty: 1.8 | ||
# angle_variance_penalty: 0.20 | ||
# minimum_angle_penalty: 1.6 #0.9 | ||
|
||
# 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 | ||
|
||
# ROS Parameters | ||
odom_frame: odom | ||
map_frame: map | ||
base_frame: base_footprint | ||
mode: mapping #localization | ||
|
||
# lifelong params | ||
lifelong_search_use_tree: true | ||
lifelong_minimum_score: 0.1 | ||
lifelong_iou_match: 0.75 | ||
lifelong_node_removal_score: 0.1 | ||
lifelong_overlap_score_scale: 0.5 | ||
lifelong_constraint_multiplier: 0.05 | ||
lifelong_nearby_penalty: 0.001 | ||
|
||
# if you'd like to immediately start continuing a map at a given pose | ||
# or at the dock, but they are mutually exclusive, if pose is given | ||
# will use pose | ||
#map_file_name: test_steve | ||
#map_start_pose: [0.0, 0.0, 0.0] | ||
#map_start_at_dock: true | ||
|
||
debug_logging: false | ||
throttle_scans: 1 | ||
transform_publish_period: 0.02 #if 0 never publishes odometry | ||
map_update_interval: 5.0 | ||
resolution: 0.05 | ||
max_laser_range: 20.0 #for rastering images | ||
minimum_time_interval: 0.5 | ||
transform_timeout: 0.2 | ||
tf_buffer_duration: 10. | ||
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps | ||
|
||
# General Parameters | ||
use_scan_matching: true | ||
use_scan_barycenter: true | ||
minimum_travel_distance: 0.5 | ||
minimum_travel_heading: 0.5 | ||
scan_buffer_size: 10 | ||
scan_buffer_maximum_scan_distance: 10 | ||
link_match_minimum_response_fine: 0.1 | ||
link_scan_maximum_distance: 1.5 | ||
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,7 @@ | ||
<launch> | ||
|
||
<node pkg="slam_toolbox" type="lifelong_slam_toolbox_node" name="lifelong_slam_toolbox_node" output="screen"> | ||
<rosparam command="load" file="$(find slam_toolbox)/config/mapper_params_lifelong.yaml" /> | ||
</node> | ||
|
||
</launch> |