Public Member Functions | |
| Keypoint | extract_keypoints (cv::Mat &image, bool frames_only) |
| cv::Mat | extract_roi (cv::Mat &image, Keypoint &camera_keypoints, Rect rect) |
| cv::Mat | extract_roi (std::vector< int > inliers, cv::Mat query, cv::Mat &output_image) |
| void | Imagecallback (const sensor_msgs::ImageConstPtr &image) |
| void | knnSearch (Mat &query, Mat &indices, Mat &dists, int knn) |
| LatestMatchingTFMessage (ros::NodeHandle &nh, const std::string &source_frame) | |
| void | radiusSearch (Mat &query, Mat &indices, Mat &dists, double radius) |
| void | TFcallback (const tf::tfMessageConstPtr &msg) |
| void | visualize (cv::Mat camera_image_in, Keypoint &camera_keypoints) |
| void | visualize (std::vector< int > inliers, cv::Mat query, cv::Mat &output_image) |
Public Attributes | |
| sensor_msgs::CvBridge | bridge_ |
| ros::ServiceClient | client |
| cv::Mat | final_image_ |
| cv::Mat | image_ |
| cv::Mat | image_roi2_ |
| cv::Mat | image_roi_ |
| std::string | image_topic_ |
| int | knn_ |
| tf::tfMessageConstPtr | last_matching_tf |
| cv::Mat | mask_ |
| int | min_nn_ |
| std::string | mode_ |
| cv::Mat | original_image_ |
| double | radius_ |
| Rect | rect_ |
| robot_mask::GetMask | srv |
| tf::tfMessageConstPtr | tf_state |
| std::string | tf_topic_ |
Private Attributes | |
| std::string | camera_frame_ |
| int | count_ |
| int | fovy_ |
| int | height_ |
| ros::Subscriber | image_sub_ |
| ros::NodeHandle | nh_ |
| bool | save_images_ |
| std::string | source_frame_ |
| ros::Subscriber | tf_sub_ |
| bool | valid_ |
| int | width_ |
Definition at line 20 of file in_hand_object_modeling.cpp.
| LatestMatchingTFMessage::LatestMatchingTFMessage | ( | ros::NodeHandle & | nh, |
| const std::string & | source_frame | ||
| ) | [inline] |
Definition at line 41 of file in_hand_object_modeling.cpp.
| Keypoint LatestMatchingTFMessage::extract_keypoints | ( | cv::Mat & | image, |
| bool | frames_only | ||
| ) | [inline] |
SIFT keypoints
| image | input image |
| frames_only | GetKeypointFrames when is true |
Definition at line 445 of file in_hand_object_modeling.cpp.
| cv::Mat LatestMatchingTFMessage::extract_roi | ( | cv::Mat & | image, |
| Keypoint & | camera_keypoints, | ||
| Rect | rect | ||
| ) | [inline] |
Manual ROI extraction Extracts a sub-image from another one given the top-left and bottom-right points
| image | input image |
| camera_keypoints | is a pointer to the vector containing the keypoints |
| rect | top-left and bottom-right points |
Definition at line 475 of file in_hand_object_modeling.cpp.
| cv::Mat LatestMatchingTFMessage::extract_roi | ( | std::vector< int > | inliers, |
| cv::Mat | query, | ||
| cv::Mat & | output_image | ||
| ) | [inline] |
Automatically extracts ROI Returns a sub-image defined by bounding box around the inlier features
| inliers | inlier features as found by either radiusSearch or knnSearch |
| query | matrix with all keypoints |
Definition at line 504 of file in_hand_object_modeling.cpp.
| void LatestMatchingTFMessage::Imagecallback | ( | const sensor_msgs::ImageConstPtr & | image | ) | [inline] |
Image callback - main function of the program"
| image | camera image |
Definition at line 104 of file in_hand_object_modeling.cpp.
| void LatestMatchingTFMessage::knnSearch | ( | Mat & | query, |
| Mat & | indices, | ||
| Mat & | dists, | ||
| int | knn | ||
| ) | [inline] |
Performs a K-nearest neighbor search for multiple query points.
| query | – The query points with the keypoints coordinates |
| indices | – Indices of the nearest neighbors found |
| dists | – Distances to the nearest neighbors found |
| knn | – Number of nearest neighbors to search for |
Definition at line 422 of file in_hand_object_modeling.cpp.
| void LatestMatchingTFMessage::radiusSearch | ( | Mat & | query, |
| Mat & | indices, | ||
| Mat & | dists, | ||
| double | radius | ||
| ) | [inline] |
Performs a radius nearest neighbor search for multiple query points.
| query | – The query points with the keypoints coordinates |
| indices | – Indices of the nearest neighbors found |
| dists | – Distances to the nearest neighbors found |
| radius | – The search radius in pixels |
Definition at line 390 of file in_hand_object_modeling.cpp.
| void LatestMatchingTFMessage::TFcallback | ( | const tf::tfMessageConstPtr & | msg | ) | [inline] |
| void LatestMatchingTFMessage::visualize | ( | cv::Mat | camera_image_in, |
| Keypoint & | camera_keypoints | ||
| ) | [inline] |
Draws keypoints
| camera_image_in | is the input image |
| camera_keypoints | a pointer to the vector containing the keypoints extracted |
Definition at line 533 of file in_hand_object_modeling.cpp.
| void LatestMatchingTFMessage::visualize | ( | std::vector< int > | inliers, |
| cv::Mat | query, | ||
| cv::Mat & | output_image | ||
| ) | [inline] |
Draws keypoints
| inliers | inlier features as found by either radiusSearch or knnSearch |
| query | matrix with all keypoints |
| output | image to draw on |
Definition at line 552 of file in_hand_object_modeling.cpp.
Definition at line 34 of file in_hand_object_modeling.cpp.
std::string LatestMatchingTFMessage::camera_frame_ [private] |
Definition at line 25 of file in_hand_object_modeling.cpp.
Definition at line 30 of file in_hand_object_modeling.cpp.
int LatestMatchingTFMessage::count_ [private] |
Definition at line 26 of file in_hand_object_modeling.cpp.
Definition at line 35 of file in_hand_object_modeling.cpp.
int LatestMatchingTFMessage::fovy_ [private] |
Definition at line 26 of file in_hand_object_modeling.cpp.
int LatestMatchingTFMessage::height_ [private] |
Definition at line 26 of file in_hand_object_modeling.cpp.
| cv::Mat LatestMatchingTFMessage::image_ |
Definition at line 35 of file in_hand_object_modeling.cpp.
Definition at line 35 of file in_hand_object_modeling.cpp.
Definition at line 35 of file in_hand_object_modeling.cpp.
Definition at line 24 of file in_hand_object_modeling.cpp.
| std::string LatestMatchingTFMessage::image_topic_ |
Definition at line 33 of file in_hand_object_modeling.cpp.
Definition at line 39 of file in_hand_object_modeling.cpp.
Definition at line 32 of file in_hand_object_modeling.cpp.
| cv::Mat LatestMatchingTFMessage::mask_ |
Definition at line 35 of file in_hand_object_modeling.cpp.
Definition at line 39 of file in_hand_object_modeling.cpp.
| std::string LatestMatchingTFMessage::mode_ |
Definition at line 37 of file in_hand_object_modeling.cpp.
ros::NodeHandle LatestMatchingTFMessage::nh_ [private] |
Definition at line 27 of file in_hand_object_modeling.cpp.
Definition at line 35 of file in_hand_object_modeling.cpp.
Definition at line 38 of file in_hand_object_modeling.cpp.
Definition at line 36 of file in_hand_object_modeling.cpp.
bool LatestMatchingTFMessage::save_images_ [private] |
Definition at line 28 of file in_hand_object_modeling.cpp.
std::string LatestMatchingTFMessage::source_frame_ [private] |
Definition at line 25 of file in_hand_object_modeling.cpp.
Definition at line 31 of file in_hand_object_modeling.cpp.
Definition at line 32 of file in_hand_object_modeling.cpp.
Definition at line 23 of file in_hand_object_modeling.cpp.
| std::string LatestMatchingTFMessage::tf_topic_ |
Definition at line 33 of file in_hand_object_modeling.cpp.
bool LatestMatchingTFMessage::valid_ [private] |
Definition at line 28 of file in_hand_object_modeling.cpp.
int LatestMatchingTFMessage::width_ [private] |
Definition at line 26 of file in_hand_object_modeling.cpp.