Size: 10986
Comment: Single SLAM Parameters
|
Size: 11015
Comment:
|
Deletions are marked like this. | Additions are marked like this. |
Line 2: | Line 2: |
= Documentation in progress = |
Only released in EOL distros:
Package Summary
Documented
The ohm_tsd_slam package provides a 2D SLAM approach for laser scanners.
- Maintainer: Philipp Koch <philipp.koch AT th-nuernberg DOT de>, Markus Kühn <markus.kuehn AT th-nuernberg DOT de>
- Author: Philipp Koch, Stefan May, Markus Kühn
- License: TODO
- Source: git https://github.com/autonohm/ohm_tsd_slam.git (branch: indigo-devel)
Contents
Documentation in progress
ROS Nodes
slam_node
Node for single robot SLAM with one laser scanner.Published Topics
map (nav_msgs/OccupancyGrid)- Map of the environment
- Absolute robot pose in the map frame
Parameters
cell_octave_factor (integer, default: 10)- Quadratic size of the map with a side length of 2^(cell_octave_factor) * cell_size
- Size of a cell in meters. It influences the absolute map size
- X-offset of the origin to the place the SLAM was initialized
- Y-offset of the origin to the place the SLAM was initialized
- Orientation offset of the origin to the place the SLAM was initialized (rotation around vertical z-axis)
- Minimal range of the raycaster. The raycaster is used to obtain virtual laser scans from the map
- Maximal range of the raycaster
- Something which helps against glass reflections.. To be done
- The time [s] that needs to pass before an update of the map is published again
- Node frequency of the SLAM. This has no influence on the map or pose frequency.
- Topic for pose updates
- Map coordinate system
- Robot or Laser coordintate system
- Number of cells used for the truncated signed distance function. See [add Publication] for further details
- Topic for map publisher
- Name of a service that gives back a map
- Width of the robot (y-axis)
- Height of the robot (x-axis)
- Not sure about the reason for this. It moves the robot box on the x-axis
- If this is set to true, a RANSAC based pre-registration is done. This enhances roboustness but the pose update rate is about 3-4 times slower than without it.
- Start value of a cascading point filter for the ICP iterations.
- End value of a cascading point filter for the ICP iterations.
- Number of ICP iterations for scan matching
- Maximal allowed translation between two matched scans
- Maximal allowed rotation between two matched scans
- Subsampling of huge laser scans if a pre-registration is done.
- Name of the node_control service to start stop and reset the SLAM
multi_slam_node
This node can build one map with multiple robots/laser scanners.Published Topics
/map (invalid message type for MsgLink(msg/type))- Map
- Pose of Robot number X. robotX might also replaced by a more distinctive namespace name.
Launch Files
Single Robot SLAM
<launch> <node pkg="tf" type="static_transform_publisher" name = "tf_laser" args = "-0.19 0 0.0 0 0 0 laser base_footprint 50"/> <node name = "slam_node" pkg = "ohm_tsd_slam" type = "slam_node" output = "screen"> <param name = "laser_topic" type = "string" value = "scan" /> <param name = "x_off_factor" type = "double" value = "0.5" /> <param name = "y_off_factor" type = "double" value = "0.5" /> <param name = "yaw_offset" type = "double" value = "0.0" /> <param name = "cell_octave_factor" type = "int" value = "13" /> <param name = "cellsize" type = "double" value = "0.015" /> <param name = "min_range" type = "double" value = "0.0" /> <param name = "max_range" type = "double" value = "30.0" /> <param name = "low_reflectivity_range" type = "double" value = "3.0" /> <param name = "occ_grid_time_interval" type = "double" value = "2.0" /> <param name = "loop_rate" type = "double" value = "40.0" /> <param name = "pose_topic" type = "string" value = "pose" /> <param name = "tf_base_frame" type = "string" value = "/map" /> <param name = "tf_child_frame" type = "string" value = "laser" /> <param name = "truncation_radius" type = "double" value = "2.0" /> <param name = "object_inflation_factor" type = "int" value = "0" /> <param name = "use_object_inflation" type = "bool" value = "false" /> <param name = "map_topic" type = "string" value = "/map" /> <param name = "get_map_topic" type = "string" value = "/map" /> <param name = "footprint_width" type = "double" value = "1.0" /> <param name = "footprint_height" type = "double" value = "1.0" /> <param name = "footprint_x_offset" type = "double" value = "-0.5" /> <param name = "use_icpsac" type = "bool" value = "false" /> <param name = "dist_filter_max" type = "double" value = "2.0" /> <param name = "dist_filter_min" type = "double" value = "0.1" /> <param name = "icp_iterations" type = "int" value = "25" /> <param name = "reg_trs_max" type = "double" value = "1.25" /> <param name = "reg_sin_rot_max" type = "double" value = "0.4" /> <param name = "ransac_reduce_factor" type = "int" value = "1"/> <param name = "node_control_topic" type = "string" value = node_control"/> </node> </launch>
Multi Robot SLAM
<launch> <node name = "multi_slam_node" pkg = "ohm_tsd_slam" type = "multi_slam_node" output = "screen"> <param name = "robot_nbr" type = "int" value = "2"/> <param name = "x_off_factor" type = "double" value = "0.5" /> <param name = "y_off_factor" type = "double" value = "0.5" /> <param name = "cell_octave_factor" type = "int" value = "13" /> <param name = "cellsize" type = "double" value = "0.015" /> <param name = "low_reflectivity_range" type = "double" value = "3.0" /> <param name = "occ_grid_time_interval" type = "double" value = "2.0" /> <param name = "truncation_radius" type = "double" value = "3.0" /> <param name = "object_inflation_factor" type = "int" value = "3"/> <param name = "use_object_inflation" type = "bool" value = "true" /> <param name = "reg_trs_max" type = "double" value = "0.5" /> <param name = "reg_sin_rot_max" type = "double" value = "0.5" /> <param name = "robot0/namespace" type = "string" value = "georg"/> <param name = "/georg/tf_child_frame" type = "string" value = "laser"/> <param name = "/georg/pose_topic" type = "string" value = "pose"/> <param name = "/georg/x_offset" type = "double" value = "1.0"/> <param name = "/georg/y_offset" type = "double" value = "0.0"/> <param name = "/georg/yaw_offset" type = "double" value = "0.0"/> <param name = "/georg/footprint_width" type = "double" value = "1.0"/> <param name = "/georg/footprint_height" type = "double" value = "1.0"/> <param name = "/georg/footprint_x_offset" type = "double" value = "-0.5"/> <param name = "/georg/low_reflectivity_range" type = "double" value = "3.0" /> <param name = "/georg/max_range" type = "double" value ="15.0" /> <param name = "/georg/min_range" type = "double" value ="0.01" /> <param name = "/georg/ransac_reduce_factor" type = "int" value = "1"/> <param name = "/georg/use_icpsac" type = "bool" value = "false" /> <param name = "/georg/icp_iterations" type = "int" value = "25" /> <param name = "/georg/dist_filter_max" type = "double" value = "2.0" /> <param name = "/georg/dist_filter_min" type = "double" value = "0.1" /> <param name = "/georg/node_control" type = "string" value = "node_control"/> <param name = "robot1/namespace" type = "string" value = "simon"/> <param name = "/simon/tf_child_frame" type = "string" value = "laser"/> <param name = "/simon/pose_topic" type = "string" value = "pose"/> <param name = "/simon/x_offset" type = "double" value = "1.8"/> <param name = "/simon/y_offset" type = "double" value = "0.0"/> <param name = "/simon/yaw_offset" type = "double" value = "0.0"/> <param name = "/simon/footprint_width" type = "double" value = "1.0"/> <param name = "/simon/footprint_height" type = "double" value = "1.0"/> <param name = "/simon/footprint_x_offset" type = "double" value = "-0.5"/> <param name = "/simon/low_reflectivity_range" type = "double" value = "3.0" /> <param name = "/simon/max_range" type = "double" value ="30.0" /> <param name = "/simon/min_range" type = "double" value ="0.01" /> <param name = "/simon/ransac_reduce_factor" type = "int" value = "4"/> <param name = "/simon/use_icpsac" type = "bool" value = "true" /> <param name = "/simon/icp_iterations" type = "int" value = "25" /> <param name = "/simon/dist_filter_max" type = "double" value = "0.2" /> <param name = "/simon/dist_filter_min" type = "double" value = "0.01" /> <param name = "/simon/node_control" type = "string" value = "node_control"/> </node> </launch>