This ROS node is used for building a map of the environment and computing the transform between the /map and /odom frames from laser scan messages (sensor_msgs/LaserScan) and the odometry data.
-
tf (tf/tfMessage):
Transforms necessary to relate frames for laser, base, and odometry. -
scan (sensor_msgs/LaserScan):
Laser scans to create the map from.
-
map_metadata (nav_msgs/MapMetaData):
Get the map data from this topic, which is latched, and updated periodically. -
map (nav_msgs/OccupancyGrid):
Get the map data from this topic, which is latched, and updated periodically -
~entropy (std_msgs/Float64):
Estimate of the entropy of the distribution over the robot's pose (a higher value indicates greater uncertainty). New in 1.1.0.
- dynamic_map (nav_msgs/GetMap):
Call this service to get the map data
-
<laser_sensor_frame> ⟶ base_link:
Usually a fixed value, broadcast periodically by a robot_state_publisher, or a tf static_transform_publisher. -
base_link ⟶ odom:
Usually provided by the odometry system (e.g., the driver for the mobile base)
- map → odom:
The current estimate of the robot's pose within the map frame
-
~inverted_laser(string, default: "false"__)***:
(REMOVED in 1.1.1; transform data is used instead) Is the laser right side up (scans are ordered CCW), or upside down (scans are ordered CW)? -
~throttle_scans (int, default: 1):
Process 1 out of every this many scans (set it to a higher number to skip more scans) -
~transform_publish_period (float, default: 0.05):
How long (in seconds) between transform publications. To disable broadcasting transforms, set to 0.
-
~base_frame (string, default: "base_link"):
The frame attached to the mobile base. -
~map_frame (string, default: "map"):
The frame attached to the map. -
~odom_frame (string, default: "odom"):
The frame attached to the odometry system.
-
~xmin (float, default: -100.0):
Initial map size (in metres) -
~ymin (float, default: -100.0):
Initial map size (in metres) -
~xmax (float, default: 100.0):
Initial map size (in metres) -
~ymax (float, default: 100.0):
Initial map size (in metres) -
~delta (float, default: 0.05):
Resolution of the map (in metres per occupancy grid block) -
~occ_thresh (float, default: 0.25):
Threshold on gmapping's occupancy values. Cells with greater occupancy are considered occupied (i.e., set to 100 in the resulting sensor_msgs/LaserScan). New in 1.1.0.
-
~kernelSize (int, default: 1):
The kernel in which to look for a correspondence -
~lstep (float, default: 0.05):
The optimization step in translation -
~astep (float, default: 0.05):
The optimization step in rotation -
~iterations (int, default: 5):
The number of iterations of the scanmatcher -
~sigma (float, default: 0.05):
The sigma used by the greedy endpoint matching -
~lsigma (float, default: 0.075):
The sigma of a beam used for likelihood computation -
~lskip (int, default: 0):
Number of beams to skip in each scan. Take only every (n+1)th laser ray for computing a match (0 = take all rays)
-
~maxUrange (float, default: 80.0):
The maximum usable range of the laser. A beam is cropped to this value. -
~maxRange (float):
The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free space n the map, set maxUrange < maximum range of the real sensor ≤ maxRange.
-
~llsamplerange (float, default: 0.01):
Translational sampling range for the likelihood -
~llsamplestep (float, default: 0.01):
Translational sampling step for the likelihood -
~lasamplerange (float, default: 0.005):
Angular sampling range for the likelihood -
~lasamplestep (float, default: 0.005):
Angular sampling step for the likelihood
Standard deviations of a Gaussian noise model
-
~srr (float, default: 0.1):
Odometry error in translation as a function of translation (ρ/ρ).
Linear noise component (x and y). -
~stt (float, default: 0.2):
Odometry error in rotation as a function of rotation (θ/θ)
Angular noise component (θ) -
~srt (float, default: 0.2):
Odometry error in translation as a function of rotation (ρ/θ)
Linear ⟶ Angular noise component -
~str (float, default: 0.1):
Odometry error in rotation as a function of translation (θ/ρ)
Angular ⟶ Linear noise component
-
~map_update_interval (float, default: 5.0):
How long (in seconds) between updates to the map. Lowering this number updates the occupancy grid more often, at the expense of greater computational load. -
~linearUpdate (float, default: 1.0):
Process a scan each time the robot translates this far -
~angularUpdate (float, default: 0.5):
Process a scan each time the robot rotates this far -
~temporalUpdate (float, default: -1.0):
Process a scan if the last scan processed is older than the update time in seconds. A value less than zero will turn time based updates off.
-
~particles (int, default: 30):
Number of particles in the filter -
~resampleThreshold (float, default: 0.5):
The Neff based resampling threshold -
~minimumScore (float, default: 0.0):
Minimum score for considering the outcome of the scan matching good. Can avoid jumping pose estimates in large open spaces when using laser scanners with limited range (e.g. 5m). Scores go up to 600+, try 50 for example when experiencing jumping estimate issues. -
~ogain (float, default: 3.0):
Gain to be used while evaluating the likelihood, for smoothing the resampling effects
-
~en_fmp (bool, default: false):
Enable Full Map Posterior calculations -
~decayModel (bool, default: false):
Use a beam decay map model. -
~alpha_0 (float, default: 1.0):
-
~beta_0 (float, default: 1.0):