slam_gmapping

gmapping

This package contains a ROS wrapper for OpenSlam's Gmapping. The gmapping package provides laser-based SLAM (Simultaneous Localization and Mapping), as a ROS node called slam_gmapping. Using slam_gmapping, you can create a 2-D occupancy grid map (like a building floorplan) from laser and pose data collected by a mobile robot.

slam_gmapping is a wrapper around the GMapping SLAM library. It reads laser scans and odometry and computes a map. This map can be written to a file using e.g.

"rosrun map_server map_saver static_map:=dynamic_map"


ROS topics

Subscribes to (name/type):

Publishes to (name/type):

  • "/tf"/tf/tfMessage: position relative to the map

services

  • "~dynamic_map" : returns the map

ROS parameters

Reads the following parameters from the parameter server

Parameters used by our GMapping wrapper:

  • "~throttle_scans": [int] throw away every nth laser scan
  • "~base_frame": [string] the tf frame_id to use for the robot base pose
  • "~map_frame": [string] the tf frame_id where the robot pose on the map is published
  • "~odom_frame": [string] the tf frame_id from which odometry is read
  • "~map_update_interval": [double] time in seconds between two recalculations of the map

Parameters used by GMapping itself:

Laser Parameters:

  • "~/maxRange" [double] maximum range of the laser scans. Rays beyond this range get discarded completely. (default: maximum laser range minus 1 cm, as received in the the first LaserScan message)
  • "~/maxUrange" [double] maximum range of the laser scanner that is used for map building (default: same as maxRange)
  • "~/sigma" [double] standard deviation for the scan matching process (cell)
  • "~/kernelSize" [int] search window for the scan matching process
  • "~/lstep" [double] initial search step for scan matching (linear)
  • "~/astep" [double] initial search step for scan matching (angular)
  • "~/iterations" [int] number of refinement steps in the scan matching. The final "precision" for the match is lstep*2^(-iterations) or astep*2^(-iterations), respectively.
  • "~/lsigma" [double] standard deviation for the scan matching process (single laser beam)
  • "~/ogain" [double] gain for smoothing the likelihood
  • "~/lskip" [int] take only every (n+1)th laser ray for computing a match (0 = take all rays)
  • "~/minimumScore" [double] minimum score for considering the outcome of the scanmatching good. Can avoid 'jumping' pose estimates in large open spaces when using laser scanners with limited range (e.g. 5m). (0 = default. Scores go up to 600+, try 50 for example when experiencing 'jumping' estimate issues)

Motion Model Parameters (all standard deviations of a gaussian noise model)

  • "~/srr" [double] linear noise component (x and y)
  • "~/stt" [double] angular noise component (theta)
  • "~/srt" [double] linear -> angular noise component
  • "~/str" [double] angular -> linear noise component

Others:

  • "~/linearUpdate" [double] the robot only processes new measurements if the robot has moved at least this many meters
  • "~/angularUpdate" [double] the robot only processes new measurements if the robot has turned at least this many rads
  • "~/resampleThreshold" [double] threshold at which the particles get resampled. Higher means more frequent resampling.
  • "~/particles" [int] (fixed) number of particles. Each particle represents a possible trajectory that the robot has traveled

Likelihood sampling (used in scan matching)

  • "~/llsamplerange" [double] linear range
  • "~/lasamplerange" [double] linear step size
  • "~/llsamplestep" [double] linear range
  • "~/lasamplestep" [double] angular step size

Initial map dimensions and resolution:

  • "~/xmin" [double] minimum x position in the map [m]
  • "~/ymin" [double] minimum y position in the map [m]
  • "~/xmax" [double] maximum x position in the map [m]
  • "~/ymax" [double] maximum y position in the map [m]
  • "~/delta" [double] size of one pixel [m]


gmapping
Author(s): Brian Gerkey
autogenerated on Wed Mar 2 2022 01:03:13