Github Source: https://github.com/ortslil64/dynamic_map_matcher_ros

Algorithms

dynamic_map_matcher is a package for cooperative robots SLAM. It is based on a regularized particle filter and the technical details will be published once our paper "Dynamic map matching using particle filtering" is published.

The main contribution of this package is its capability to work with any SLAM algorithm that produces an occupancy grid based map. The provided demo uses two hector_slam mappers.

Example

Nodes

map_matcher_node

map_matcher_node takes in two occupancy grid based map and outputs a global matched map. On startup, map_matcher_node initializes its particle filter according to the parameters provided.

Subscribed Topics

origin_map (nav_msgs/OccupancyGrid)
  • Map of the first robot to be matched with the target map.
target_map (nav_msgs/OccupancyGrid)
  • Target map to be matched.

Published Topics

global_map (nav_msgs/OccupancyGrid)
  • The estimated global map.

/sequential_map_matcher/origin_map (string, default: origin_map)

  • Topic name for the origin map.
/sequential_map_matcher/target_map (string, default: target_map)
  • Topic name for the target map.
/sequential_map_matcher/n_particles (int, default: 500)
  • Number of particles to use, has an effect on the computation time.
/sequential_map_matcher/n_observation (int, default: 500)
  • Number of observation to use from the maps, has an effect on the computation time.
/sequential_map_matcher/n_history (int, default: 5)
  • Convolution history, how many time steps to affect weighting the particles. A good value is 5-10.
/sequential_map_matcher/n_theta (int, default: 50)
  • Initialization count for the transformation angle.
/sequential_map_matcher/n_x (int, default: 20)
  • Initialization count for the transition on the x axis.
/sequential_map_matcher/n_y (int, default: 20)
  • Initialization count for the transition on the y axis.
/sequential_map_matcher/R_var (double, default: 0.1)
  • Weighting coefficient for the particle filter likelihood function.

References

This work is summarized in a yet to be published paper - "Dynamic map matching using particle filtering".

Wiki: dynamic_map_matcher (last edited 2020-02-23 11:35:48 by Or Tslil)