$search

LatestMatchingTFMessage Class Reference

List of all members.

Public Member Functions

Keypoint extract_keypoints (cv::Mat &image, bool frames_only)
cv::Mat extract_roi (std::vector< int > inliers, cv::Mat query, cv::Mat &output_image)
cv::Mat extract_roi (cv::Mat &image, Keypoint &camera_keypoints, Rect rect)
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 (std::vector< int > inliers, cv::Mat query, cv::Mat &output_image)
void visualize (cv::Mat camera_image_in, Keypoint &camera_keypoints)

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_

Detailed Description

Definition at line 20 of file in_hand_object_modeling.cpp.


Constructor & Destructor Documentation

LatestMatchingTFMessage::LatestMatchingTFMessage ( ros::NodeHandle nh,
const std::string &  source_frame 
) [inline]

Definition at line 41 of file in_hand_object_modeling.cpp.


Member Function Documentation

Keypoint LatestMatchingTFMessage::extract_keypoints ( cv::Mat &  image,
bool  frames_only 
) [inline]

SIFT keypoints

Parameters:
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 ( 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

Parameters:
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.

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

Parameters:
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.

void LatestMatchingTFMessage::Imagecallback ( const sensor_msgs::ImageConstPtr image  )  [inline]

Image callback - main function of the program"

  • establishes the connection with the robot_mask service server.
  • converts the ros::image to cv::image
  • masks out robot hand
  • calls the functions in order to get rid of outlier features: Options are: "manual", "radius_search", "knn_search"
    Parameters:
    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.

Parameters:
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.

Parameters:
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]

TF callback

Parameters:
msg TF message

Definition at line 79 of file in_hand_object_modeling.cpp.

void LatestMatchingTFMessage::visualize ( std::vector< int >  inliers,
cv::Mat  query,
cv::Mat &  output_image 
) [inline]

Draws keypoints

Parameters:
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.

void LatestMatchingTFMessage::visualize ( cv::Mat  camera_image_in,
Keypoint &  camera_keypoints 
) [inline]

Draws keypoints

Parameters:
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.


Member Data Documentation

Definition at line 34 of file in_hand_object_modeling.cpp.

Definition at line 25 of file in_hand_object_modeling.cpp.

Definition at line 30 of file in_hand_object_modeling.cpp.

Definition at line 26 of file in_hand_object_modeling.cpp.

Definition at line 35 of file in_hand_object_modeling.cpp.

Definition at line 26 of file in_hand_object_modeling.cpp.

Definition at line 26 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 35 of file in_hand_object_modeling.cpp.

Definition at line 24 of file in_hand_object_modeling.cpp.

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.

Definition at line 35 of file in_hand_object_modeling.cpp.

Definition at line 39 of file in_hand_object_modeling.cpp.

Definition at line 37 of file in_hand_object_modeling.cpp.

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.

Definition at line 28 of file in_hand_object_modeling.cpp.

Definition at line 25 of file in_hand_object_modeling.cpp.

robot_mask::GetMask LatestMatchingTFMessage::srv

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.

Definition at line 33 of file in_hand_object_modeling.cpp.

Definition at line 28 of file in_hand_object_modeling.cpp.

Definition at line 26 of file in_hand_object_modeling.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


model_completion
Author(s): Monica Opris
autogenerated on Mon Dec 3 21:44:57 2012