Package Summary

BoWP-Map is a RGB image based topological mapping algorithm.

* Author : Nishant Kejriwal

* Email id: kejriwalnishant1990@gmail.com

* License : BSD

* Bug/ feature tracker: https://gitlab.com/nishant1990/bowpmap_ros/issues

* Source: git https://gitlab.com/nishant1990/bowpmap_ros.git (branch: master)

Overview

Tutorials

  1. How to run BoWP-Map on your robot!

    This tutorial shows how to configure bowpmap_ros with any camera sensor(default: Kinect) on turtlebot2.

  2. Hand Held Mapping with any RGB camera sensor.

    This tutorial shows how to use bowpmap_ros with any camera sensor(default: Kinect).

Demos

Appearance-based loop closure detection-only

This video is a result of BoWP-Map on New College Dataset.

Real Time implementation of BoWP-Map

Nodes

bowpmap_ros

It is a wrapper of the BoWP-Map Core library for topological mapping . The graph of the map is incrementally built and the output is shown using ros topics where loop closure information is published.

Subscribed Topics

rgb/image (sensor_msgs/Image)
  • Kinect RGB Images or Any monocular camera image for topological mapping. This topic is mapped to RGB image topic of either kinect or any web camera(By default, it is set to kinect rgb image topic).
odom (nav_msgs/Odometry)
  • Odometry data is used to visualise the map built using bowpMap algorithm. Visualisation is not a part of the algorithm. You can download the bowpMap code with visualisation from here : https://gitlab.com/nishant1990/bowpmap_ros.git (branch: prasun).

Published Topics

loopClosure (std_msgs/Bool)
  • BoWP-Map based loop closure detection.
loopClosureImage (sensors_msgs/Image)
  • Loop Closure Image and Query Image combined together.

Parameters

~matching_threshold (double, default: 15)
  • Matching Threshold for geometrical verification. It is varied with environment.
~distance (double, default: 0.8)
  • Nearest neighbor distance ratio. Generally this ratio is fixed and should not be varied. However to get more matching features in the K-D tree, you can increase the distance threshold.
~hessian (int, default: 100)
  • Hessian threshold, This threshold varies the number of descriptor per image. If threshold is lowered, number of keypoint detected are increased and vice-versa.
~noOfDescriptors (int, default: 1000)
  • Number of descriptors which you want to keep in each image.
~candidates (int, default: 1)
  • Number of candidates for geometrical verification step using RANSAC.
~loopProbability (double, default: 0.1)
  • Minimum probability for each loop closure candidate.

Wiki: bowpMap (last edited 2015-11-30 11:05:51 by Prasun Pallav)