Public Member Functions | |
| FlannMatching (ros::NodeHandle nh_) | |
| ~FlannMatching () | |
Protected Member Functions | |
| void | guiCB (const opencv_tut::valueMatrixConstPtr &msg) |
| void | homography (std::vector< cv::KeyPoint > aruco_, std::vector< cv::KeyPoint > feed_, std::vector< cv::DMatch > match, cv::Mat aruco_img, cv::Mat matches_mat) |
| void | imageCB (const sensor_msgs::ImageConstPtr &msg) |
| void | Matcher (cv::Mat in_feed, cv::Mat in_static, cv::Mat &out) |
Protected Attributes | |
| image_transport::ImageTransport | _imageTransport |
| float | dist_check |
| std::string | extractor_gui |
| std::string | feature_gui |
| ros::Subscriber | gui_sub |
| image_transport::Subscriber | image_sub |
| int | k |
| bool | knn |
| std::string | matcher_gui |
| std::string | path |
Definition at line 57 of file flann_matching.cpp.
Definition at line 81 of file flann_matching.cpp.
Definition at line 97 of file flann_matching.cpp.
| void FlannMatching::guiCB | ( | const opencv_tut::valueMatrixConstPtr & | msg | ) | [protected] |
Definition at line 102 of file flann_matching.cpp.
| void FlannMatching::homography | ( | std::vector< cv::KeyPoint > | aruco_, |
| std::vector< cv::KeyPoint > | feed_, | ||
| std::vector< cv::DMatch > | match, | ||
| cv::Mat | aruco_img, | ||
| cv::Mat | matches_mat | ||
| ) | [protected] |
Definition at line 193 of file flann_matching.cpp.
| void FlannMatching::imageCB | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [protected] |
Definition at line 124 of file flann_matching.cpp.
| void FlannMatching::Matcher | ( | cv::Mat | in_feed, |
| cv::Mat | in_static, | ||
| cv::Mat & | out | ||
| ) | [protected] |
Definition at line 152 of file flann_matching.cpp.
Definition at line 69 of file flann_matching.cpp.
float FlannMatching::dist_check [protected] |
Definition at line 76 of file flann_matching.cpp.
std::string FlannMatching::extractor_gui [protected] |
Definition at line 73 of file flann_matching.cpp.
std::string FlannMatching::feature_gui [protected] |
Definition at line 73 of file flann_matching.cpp.
ros::Subscriber FlannMatching::gui_sub [protected] |
Definition at line 71 of file flann_matching.cpp.
image_transport::Subscriber FlannMatching::image_sub [protected] |
Definition at line 70 of file flann_matching.cpp.
int FlannMatching::k [protected] |
Definition at line 75 of file flann_matching.cpp.
bool FlannMatching::knn [protected] |
Definition at line 74 of file flann_matching.cpp.
std::string FlannMatching::matcher_gui [protected] |
Definition at line 73 of file flann_matching.cpp.
std::string FlannMatching::path [protected] |
Definition at line 73 of file flann_matching.cpp.