Skip to content

Commit

Permalink
Add more docs
Browse files Browse the repository at this point in the history
  • Loading branch information
tutunarsl committed Jun 29, 2024
1 parent faa1393 commit 9d91737
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 27 deletions.
11 changes: 6 additions & 5 deletions smb_slam/README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# SMB_SLAM
This package contains a bunch of commodity scripts for running (simultaneous) localization & mapping using [open3d_slam](https://github.com/ETHZ-RobotX/open3d_slam_advanced_rss_2024).
This package contains a bunch of commodity scripts for running (simultaneous) localization & mapping using [open3d_slam](https://github.com/ETHZ-RobotX/open3d_slam_advanced_rss_2024_public).

Follow instructions the instructions below to build ```smb_slam```.

Expand All @@ -21,7 +21,7 @@ Here are different modes of operation:

1. Running in Online SLAM Mode:

Make sure that `smb smb.launch` is running correctly. Now simply run the following command to start running online SLAM. You can save the map at any point by using rosservice or the map will automatically get saved upon closing the node. The `loop closure` is switched off by default for this operation and can be turned on using ```loop_closure:=true``` argument (Though we don't recommend it due to computational limits).
Make sure that `smb smb.launch` is running correctly. Now simply run the following command to start running online SLAM. You can save the map at any point by using rosservice or the map will automatically get saved upon closing the node. Advanced features such as `loop closure`, `space carving` and `submap-to-submap` registration are disabled by default as SMBs are computationally already loaded. Refer to the parameter file `/smb_slam/config/open3d_slam/param_robosense_rs16.lua` and the below table for parameter details.

```
roslaunch smb_slam online_slam.launch
Expand All @@ -45,16 +45,16 @@ For all the above cases, if you run in simulation, you can launch rviz by settin
> **Note**: The user is responsible to make sure that the specified topics are in the bag. The node will guide if there is something missing.

```
roslaunch smb_slam replay_SLAM.launch"
roslaunch smb_slam replay_SLAM.launch
```

### Map Saving

The map can be saved at any point by using rosservice from a new terminal. Run the following command from a new sourced terminal:
```
rosservice call /mapping_node/save_map
rosservice call /mapping/save_map
```
Alternatively there is an option for autosaving upon exit which can be switched on from the param files (`params.saving.save_at_mission_end = true`).
Alternatively there is an option for autosaving upon exit which can be switched on from the param files (`params.saving.save_map = true`).


## Important Parameters
Expand All @@ -70,6 +70,7 @@ Other than the parameters exposed to the ROS parameter server (the parameters us
| `params.submap.submap_size` | `double` | The submap size in meters, if increased each submap contains more data but computation increases.|
| `params.map_builder.map_voxel_size ` | `double` | The voxel size of the map, subsequently of the submap. Defines the resolution of the map that is used for localization purposes. |
| `params.mapper_localizer.scan_to_map_registration.icp.reference_cloud_seting_period` | `double` | The refence setting period in seconds. If you decrease (> 0.0s) the localization becomes more robust but computation increases. If rapid motions are done, the decrease in the period can help.|
| `params.mapper_localizer.scan_to_map_registration.scan_processing.voxel_size` | `double` | The voxel size used for the registration. This parameter should not be set smaller than the map voxel size, as it would be meaningless. If set smaller the localization resolution increases but also sensitivity to noise and computational limitations. |


> **Note**: There are multiple advanced parameters in Open3D, to not complicated simple operation these are not detailed here. Follow the naming of the variables to infer usage.
44 changes: 22 additions & 22 deletions smb_slam/config/open3d_slam/param_robosense_rs16.lua
Original file line number Diff line number Diff line change
Expand Up @@ -13,18 +13,18 @@ params.odometry.use_odometry_topic_instead_of_scan_to_scan = true --Uses Externa
params.odometry.use_IMU_for_attitude_initialization = false --Uses IMU msgs to initialize gravity aligned attitude.

--MAPPER_LOCALIZER
params.mapper_localizer.is_use_map_initialization = false
params.mapper_localizer.republish_the_preloaded_map = false
params.mapper_localizer.is_merge_scans_into_map = false
params.mapper_localizer.is_build_dense_map = false
params.mapper_localizer.is_use_map_initialization = false --If enabled, a map should be given by the params below.
params.mapper_localizer.republish_the_preloaded_map = false --if enabled, the pre-loaded map is re-published for viz. Costly.
params.mapper_localizer.is_merge_scans_into_map = false --if enabled, the provided map is extended with the scans we see.
params.mapper_localizer.is_build_dense_map = false --if enabled a dense map is built alongside the regular map. If you want this to be saved, enable submap saving.
params.mapper_localizer.is_attempt_loop_closures = false
params.mapper_localizer.is_print_timing_information = false
params.mapper_localizer.map_merge_delay_in_seconds = 10.0
params.mapper_localizer.is_print_timing_information = false --if enabled additional logs are printed
params.mapper_localizer.map_merge_delay_in_seconds = 10.0 --the delay in seconds before merging to the existing map.
params.mapper_localizer.is_refine_odometry_constraints_between_submaps = false

params.mapper_localizer.is_carving_enabled = false
params.mapper_localizer.scan_to_map_registration.scan_processing.voxel_size = 0.25
params.mapper_localizer.scan_to_map_registration.scan_processing.downsampling_ratio = 1.0
params.mapper_localizer.is_carving_enabled = false --Space carving, allows user to clear the dynamic obstables from the map if points are re-observed.
params.mapper_localizer.scan_to_map_registration.scan_processing.voxel_size = 0.25
params.mapper_localizer.scan_to_map_registration.scan_processing.downsampling_ratio = 1.0 -- 1.0: no down sampling, 0.1: 1 in every 10 points left.
params.mapper_localizer.scan_to_map_registration.scan_processing.scan_cropping.cropping_radius_max = 15.0 --meters
params.mapper_localizer.scan_to_map_registration.icp.max_correspondence_dist = 2.0 --NOT USED RIGHT NOW
params.mapper_localizer.scan_to_map_registration.icp.knn = 5 --Currently only used for surface normal estimation.
Expand All @@ -44,19 +44,19 @@ params.map_initializer.init_pose.yaw = 120.0

--SUBMAP
params.submap.submap_size = 15.0 --meters
params.submap.adjacency_based_revisiting_min_fitness = 0.5
params.submap.min_seconds_between_feature_computation = 10.0
params.submap.submaps_num_scan_overlap = 5 -- 200
params.submap.max_num_points = 250000
params.submap.adjacency_based_revisiting_min_fitness = 0.5 --How easy we want the system to switch submaps
params.submap.min_seconds_between_feature_computation = 10.0 --seconds, this is a feature of loop-closure
params.submap.submaps_num_scan_overlap = 5 -- 10 -15
params.submap.max_num_points = 250000 --We dont want our submaps to get too large in dense scenes where distance is a not a indicator of fullness. Hence, we create a submap also based on this upper point limit.

--MAP_BUILDER
params.map_builder.map_voxel_size = 0.25
params.map_builder.map_voxel_size = 0.25 --the map voxel size 25cm
params.map_builder.scan_cropping.cropping_radius_max = 40.0
params.map_builder.scan_cropping.cropping_radius_min = 2.0
params.map_builder.space_carving.carve_space_every_n_scans = 10
params.map_builder.space_carving.max_raytracing_length = 20
params.map_builder.space_carving.truncation_distance = 0.3
params.map_builder.space_carving.voxel_size = 0.2
params.map_builder.space_carving.carve_space_every_n_scans = 10 --feature of space carving
params.map_builder.space_carving.max_raytracing_length = 20 --feature of space carving
params.map_builder.space_carving.truncation_distance = 0.3 --feature of space carving
params.map_builder.space_carving.voxel_size = 0.2 --feature of space carving

--DENSE_MAP_BUILDER
params.dense_map_builder.map_voxel_size = 0.05
Expand All @@ -69,8 +69,8 @@ params.place_recognition.ransac_min_corresondence_set_size = 40
params.place_recognition.max_icp_correspondence_distance = 1.0
params.place_recognition.min_icp_refinement_fitness = 0.7
params.place_recognition.dump_aligned_place_recognitions_to_file = false
params.place_recognition.min_submaps_between_loop_closures = 2
params.place_recognition.loop_closure_search_radius = 20.0 --This considers a looot of submaps. With the current setup.
params.place_recognition.min_submaps_between_loop_closures = 2 --If you make this 0, you start doing submap-to-submap registration as well. Loop-closure feature has to be enabled for this to take action.
params.place_recognition.loop_closure_search_radius = 20.0 -- The range of search for loop-closures, technically it has to be bigger than the submap size.
params.place_recognition.consistency_check.max_drift_roll = 30.0 --deg
params.place_recognition.consistency_check.max_drift_pitch = 30.0 --deg
params.place_recognition.consistency_check.max_drift_yaw = 30.0 --deg
Expand All @@ -79,12 +79,12 @@ params.place_recognition.consistency_check.max_drift_y = 80.0 --m
params.place_recognition.consistency_check.max_drift_z = 40.0 --m

--MOTION_COMPENSATION
params.motion_compensation.is_undistort_scan = false
params.motion_compensation.is_undistort_scan = false --Needs point timestamp field to exist. Not well-tested for summer school.
params.motion_compensation.num_poses_vel_estimation = 3

--SAVING
params.saving.save_map = true
params.saving.save_submaps = false
params.saving.save_submaps = false --If enabled, the submaps are separately saved.


return params

0 comments on commit 9d91737

Please sign in to comment.