Only released in EOL distros:  

Package Summary

Simple object recognition library for 2D images, with the additional functionality of projecting matched 2D objects to 3D pointclouds. A matching alogrithm is used underneath.

Use GitHub to report bugs or submit feature requests. [View active issues]

Overview

custom_landmark_2d is a simple object recognition library for 2D images, with the additional functionality of projecting matched 2D objects to 3D pointclouds. A matching alogrithm is used underneath.

Here is a screenshot of Rviz when running custom_landmark_2d on the PR2 robot:

Depth

(Note: you can easily re-produce sth like this by running the demo_main.cpp file provided in the package)

API

custom_landmark_2d::Matcher is the main API.

It finds all the matched objects (each represented as a 'frame' by custom_landmark_2d::Frame) in the given rgb image. Given an additional registered depth image, it can also project the matched objects into 3D pointclouds.

Usage Example:

   1 custom_landmark_2d::Matcher matcher;
   2 
   3 matcher.set_template(templ);
   4 matcher.set_cam_model(camera_info);
   5 
   6 // this is the threshold for ALL acceptable matching frames,
   7 // with value ranging from 0.0 to 1.0(perfect match). The default value is 0.68. 
   8 // this value is likely needed to be adjusted for optimal results on different objects.
   9 matcher.match_limit = 0.6;
  10 
  11 // we want to find out how many matched objects are in the rgb image:
  12 std::vector<custom_landmark_2d::Frame> lst;
  13 if (matcher.Match(rgb_image, &lst)) {
  14   // we get >=1 matched frames/objects
  15 }
  16 
  17 // we now want the pointcloud containing only the second matched object:
  18 custom_landmark_2d::Frame object_frame = lst[1];
  19 pcl::PointCloud<pcl::PointXYZRGB>::Ptr object_cloud;
  20 matcher.FrameToCloud(rgb_image, depth_image, object_frame, object_cloud);
  21 
  22 // we don't care about 2D points;
  23 // just directly give us all matched objects, each in a pointcloud:
  24 std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> object_clouds;
  25 if (matcher.Match(rgb_image, depth_image, &object_cloud)) {
  26   // we get >=1 matched objects
  27 }

Executables

demo_main.cpp

The demo_main.cpp is provided in the package to help examine and visualize the results. It listens to two sensor_msgs::Image topics and output an annotated version of the rgb scene to /image_out as well as a concatenated pointcloud containing all matched objects to /generated_cloud. Many extra useful info is printed through ROS_INFO.

You can run the demo in this way:

$ rosrun custom_landmark_2d demo template.jpg rgb:=/topic1 depth:=/topic2 cam_info:=/topic3

Note that matcher.match_limit is already set as a rosparam in demo_main.cpp, and you can easily tweak its value by typing in terminal:

$ rosparam set match_limit [new_value]

To make your life easier, two launch files, demo_pr2.launch and demo_fetch.launch are also included in the package, where topic remapping is coded up for you (you can check the exact remapping by looking into the files).

You can run them like this:

$ roslaunch custom_landmark_2d demo_pr2.launch template:=[absolute_path_of_template_file]

template_fetcher.cpp

The template_fetcher.cpp is provided in the package to help saving a template image to current folder from a sensor_msgs::Image topic. You most likely need to crop it manually afterward.

You can run the template_fetcher in this way:

$ rosrun custom_landmark_2d template_fetcher rgb:=/topic1

Wiki: custom_landmark_2d (last edited 2018-03-03 01:50:16 by MatthewLiu)