The main API for 2D object recognition and projection to 3D pointclouds. More...
#include <matcher.h>
Public Member Functions | |
bool | FrameToCloud (const cv::Mat &rgb, const cv::Mat &depth, const Frame &f, pcl::PointCloud< pcl::PointXYZRGB >::Ptr object_cloud) |
Given a single pre-computed matched Frame, projects it into a pcl pointcloud. Currently only supports depth image type of CV_32FC1. | |
bool | Match (const cv::Mat &scene, std::vector< Frame > *lst) |
Performs matching and outputs each matched object as a Frame. | |
bool | Match (const cv::Mat &rgb, const cv::Mat &depth, std::vector< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > *object_clouds) |
Performs matching and outputs each matched object as a pcl pointcloud. Currently only supports depth image type of CV_32FC1. | |
Matcher () | |
The default constructors. | |
void | set_cam_model (const sensor_msgs::CameraInfoConstPtr &camera_info) |
Sets the camera model. | |
void | set_template (const cv::Mat &templ) |
Sets the template image (the object to be recognized) | |
Public Attributes | |
int | count_times |
#times of scaling in each direction | |
float | match_limit |
The threshold for ALL acceptable matching frames, with value ranging from 0.0 to 1.0(perfect match). | |
Private Member Functions | |
bool | around_frame (int x, int y, std::vector< Frame > *lst, Frame **p_ptr_ptr) |
bool | around_point (int x, int y, cv::Point &p) |
void | check_rgbd (const cv::Mat &rgb, const cv::Mat &depth) |
void | exact_match (const cv::Mat &scene, const cv::Mat &scaled_templ, std::vector< Frame > *lst) |
Private Attributes | |
image_geometry::PinholeCameraModel | cam_model_ |
int | match_method_ |
cv::Mat | templ_ |
int | x_dist_ |
int | y_dist_ |
The main API for 2D object recognition and projection to 3D pointclouds.
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.
custom_landmark_2d::Matcher matcher; matcher.set_template(templ); matcher.set_cam_model(camera_info); // this is the threshold for ALL acceptable matching frames, // with value ranging from 0.0 to 1.0(perfect match). The default value is 0.68. // this value is likely needed to be adjusted for optimal results on different objects. matcher.match_limit = 0.6; // we want to find out how many matched objects are in the rgb image: std::vector<custom_landmark_2d::Frame> lst; if (matcher.Match(rgb_image, &lst)) { // we get >=1 matched frames/objects } // we now want the pointcloud containing only the second matched object: custom_landmark_2d::Frame object_frame = lst[1]; pcl::PointCloud<pcl::PointXYZRGB>::Ptr object_cloud; matcher.FrameToCloud(rgb_image, depth_image, object_frame, object_cloud); // we don't care about 2D points; // just directly give us all matched objects, each in a pointcloud: std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> object_clouds; if (matcher.Match(rgb_image, depth_image, &object_cloud)) { // we get >=1 matched objects }
The default constructors.
Sets all public variables to their default values.
Definition at line 23 of file matcher.cpp.
bool custom_landmark_2d::Matcher::around_frame | ( | int | x, |
int | y, | ||
std::vector< Frame > * | lst, | ||
Frame ** | p_ptr_ptr | ||
) | [private] |
Definition at line 192 of file matcher.cpp.
bool custom_landmark_2d::Matcher::around_point | ( | int | x, |
int | y, | ||
cv::Point & | p | ||
) | [private] |
Definition at line 207 of file matcher.cpp.
void custom_landmark_2d::Matcher::check_rgbd | ( | const cv::Mat & | rgb, |
const cv::Mat & | depth | ||
) | [private] |
Definition at line 106 of file matcher.cpp.
void custom_landmark_2d::Matcher::exact_match | ( | const cv::Mat & | scene, |
const cv::Mat & | scaled_templ, | ||
std::vector< Frame > * | lst | ||
) | [private] |
Definition at line 153 of file matcher.cpp.
bool custom_landmark_2d::Matcher::FrameToCloud | ( | const cv::Mat & | rgb, |
const cv::Mat & | depth, | ||
const Frame & | f, | ||
pcl::PointCloud< pcl::PointXYZRGB >::Ptr | object_cloud | ||
) |
Given a single pre-computed matched Frame, projects it into a pcl pointcloud. Currently only supports depth image type of CV_32FC1.
Returns true if object_cloud is not empty. This method asserts that the rgb and depth image have the same dimension and the depth image is of type CV_32FC1.
[in] | rgb | The 2D rgb scene within which we found the input matched Frame f |
[in] | depth | The 2D registered depth image corresponds to the rgb scene (must have the same dimension as the rgb image) |
[in] | f | A single pre-computed matched Frame in the input rgb scene |
[out] | object_cloud | The pcl pointcloud of the matched object represented by the input Frame f |
Definition at line 62 of file matcher.cpp.
bool custom_landmark_2d::Matcher::Match | ( | const cv::Mat & | scene, |
std::vector< Frame > * | lst | ||
) |
Performs matching and outputs each matched object as a Frame.
Returns true if there is at least one matched object, and false otherwise.
[in] | scene | The 2D rgb scene within which to find matched objects |
[out] | lst | The vector that contains all frames of matched objects in the scene |
bool custom_landmark_2d::Matcher::Match | ( | const cv::Mat & | rgb, |
const cv::Mat & | depth, | ||
std::vector< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > * | object_clouds | ||
) |
Performs matching and outputs each matched object as a pcl pointcloud. Currently only supports depth image type of CV_32FC1.
Returns true if there is at least one matched object, and false otherwise. This method asserts that the rgb and depth image have the same dimension and the depth image is of type CV_32FC1.
[in] | rgb | The 2D rgb scene within which to find matched objects |
[in] | depth | The 2D registered depth image corresponds to the rgb scene (must have the same dimension as the rgb image) |
[out] | lst | The vector of matched objects in the rgb scene, each as a pcl pointcloud |
void custom_landmark_2d::Matcher::set_cam_model | ( | const sensor_msgs::CameraInfoConstPtr & | camera_info | ) |
Sets the camera model.
This is only needed for projection to 3D pointclouds.
Definition at line 31 of file matcher.cpp.
void custom_landmark_2d::Matcher::set_template | ( | const cv::Mat & | templ | ) |
Sets the template image (the object to be recognized)
Definition at line 27 of file matcher.cpp.
int custom_landmark_2d::Matcher::match_method_ [private] |
cv::Mat custom_landmark_2d::Matcher::templ_ [private] |
int custom_landmark_2d::Matcher::x_dist_ [private] |
int custom_landmark_2d::Matcher::y_dist_ [private] |