• Diff for "ohm_tsd_slam"
Differences between revisions 19 and 20
Revision 19 as of 2015-06-01 08:17:38
Size: 10986
Editor: MarkusKuehn
Comment: Single SLAM Parameters
Revision 20 as of 2015-06-01 08:23:04
Size: 11015
Editor: MarkusKuehn
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

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)

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
pose (geometry_msgs/PoseStamped)
  • 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
cell_size (double, default: 0.025)
  • Size of a cell in meters. It influences the absolute map size
x_off_factor (double, default: 0.5)
  • X-offset of the origin to the place the SLAM was initialized
y_off_factor (double, default: 0.5)
  • Y-offset of the origin to the place the SLAM was initialized
yaw_off (double, default: 0.5)
  • Orientation offset of the origin to the place the SLAM was initialized (rotation around vertical z-axis)
min_range (double, default: 0.001)
  • Minimal range of the raycaster. The raycaster is used to obtain virtual laser scans from the map
max_range (double, default: 30.0)
  • Maximal range of the raycaster
low_reflectivity_range (double, default: 2.0)
  • Something which helps against glass reflections.. To be done
occ_grid_time_interval (double, default: 2.0)
  • The time [s] that needs to pass before an update of the map is published again
loop_rate (double, default: 40.0)
  • Node frequency of the SLAM. This has no influence on the map or pose frequency.
pose_topic (string, default: pose)
  • Topic for pose updates
tf_base_frame (string, default: /map)
  • Map coordinate system
tf_child_frame (string, default: /laser)
  • Robot or Laser coordintate system
truncation_radius (double, default: 3.0)
  • Number of cells used for the truncated signed distance function. See [add Publication] for further details
map_topic (string)
  • Topic for map publisher
get_map_topic (string)
  • Name of a service that gives back a map
footprint_width (double, default: 0.0)
  • Width of the robot (y-axis)
footprint_height (double, default: 0.0)
  • Height of the robot (x-axis)
footprint_x_offset (double, default: 0.28)
  • Not sure about the reason for this. It moves the robot box on the x-axis
use_icpsac (bool, default: false)
  • 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.
dist_filter_max (double, default: 2.0)
  • Start value of a cascading point filter for the ICP iterations.
dist_filter_min (double, default: 0.1)
  • End value of a cascading point filter for the ICP iterations.
icp_iterations (int, default: 25)
  • Number of ICP iterations for scan matching
reg_trs_max (double, default: 0.25)
  • Maximal allowed translation between two matched scans
reg_sin_rot_max (double, default: 0.17)
  • Maximal allowed rotation between two matched scans
ransac_reduce_factor (double, default: 1.0)
  • Subsampling of huge laser scans if a pre-registration is done.
node_control_topic (double, default: node_control)
  • 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
/robotX/pose (geometry_msgs/PoseStamped)
  • 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>

Wiki: ohm_tsd_slam (last edited 2015-11-30 17:21:10 by MarkusKuehn)