Github Source: https://github.com/or-tal-robotics/object_map

Algorithms

Bayesian object mapper (bom) is a package for semantic SLAM. This package consists of:

Objects detection and localization

Using Bayesian fusion of a semantic data (SSD\YOLO) and depth data (laser scan\depth camera). Each object is assign with identity in the form of a joint probability function of its traits (shape, class, etc.).

Objects update

Recognizing, associating and updating objects identity with new observations.

Example - experiment

Example - Gazebo simulation

Nodes

ssd_node

ssd_node takes in an RGB image and produce a list with potential objects, their corresponding class and bounding boxes. This node is forked from https://github.com/balancap/SSD-Tensorflow.

Subscribed Topics

camera/image_raw/ (sensor_msgs/Image)
  • RGB camera input stream.

Published Topics

im_info (object_detector_ssd_tf_ros/SSD_Outputs)
  • List of objects with their probability mass functions, their detection probability and bounding boxes.
ssd_image_output (sensor_msgs/Image)
  • An RGB image with the detected objects and their most probable class, mainly for debugging.

Object_Detection

Object_Detection fuses the semantic information stream from the ssd_node with the depth data stream (laser scan).

Subscribed Topics

/im_info (object_detector_ssd_tf_ros/SSD_Outputs)
  • List of objects.
/scan (sensor_msgs/LaserScan)
  • Laser scanner observations.
/odom (nav_msgs/Odometry)
  • Robots odometry data.
/slam_out_pose (geometry_msgs/PoseStamped)
  • Localization data.

Published Topics

/Theta_List (joint_object_localizer/OG_List)
  • List of objects identities and parameters.

Parameters

/Array/round (int array, default: [5,16])
  • Association between objects class and circles.
/Array/rectangle (int array, default: [2,14,18,20])
  • Association between objects class and rectangles.
/Array/elliptical (int array, default: [3,8,9,12,15,17])
  • Association between objects class and ellipticals.
/Array/object_list (int array, default: [2,3,5,8,9,12,14,15,16,17,18,20])
  • Association between objects and available likelihood fumctions.
/Cord_cor/Simulation/Correction (double, default: 0.15)
  • Camera field of view correction factor.

Object_Mapper

Object_Mapper keep tracks on the mapped objects. It associates new observations with the objects and choose whether to update a certain objects or to create new one.

Subscribed Topics

/Theta_List (joint_object_localizer/OG_List)
  • List of objects.

Published Topics

/object_mapped_values (object_mapping/Object_Map)
  • List of objects identities and parameters.

Parameters

/Array/rectangle (int array, default: [2,14,18,20])
  • Association between objects class and rectangles.
/Array/elliptical (int array, default: [3,8,9,12,15,17])
  • Association between objects class and ellipticals.

References

This work is summarized in a yet to be published paper - "Representing and updating object identities in semantic SLAM".

Wiki: bom (last edited 2020-02-23 16:47:38 by Or Tslil)