Public Member Functions | Private Attributes
blort_ros::GLDetector Class Reference

#include <gldetector.h>

List of all members.

Public Member Functions

cv::Mat getDebugImage ()
cv::Mat getImage ()
 Get the rendered image for visualization.
 GLDetector (const sensor_msgs::CameraInfo &camera_info, const std::string &config_root)
void reconfigure (blort_ros::DetectorConfig config)
 Control the tracker using a ROS reconfigure_gui node.
bool recovery (const cv::Mat &image, blort_ros::RecoveryCall::Response &resp)
 Method to run and handle recovery state.
bool recoveryWithLast (blort_ros::RecoveryCall::Response &resp)
 Method to run on the previously stored image.
void setNNThreshold (double nn_threshold)
 Set the threshold of the inner nearest neighbor match.
void setRansacNPointsToMatch (unsigned int n)
 Set the threshold of the inner nearest neighbor match.
 ~GLDetector ()

Private Attributes

IplImage * image_
cv::Mat last_image
bool last_reset
std::string model_name
std::string pose_cal
int rec3dcounter
boost::shared_ptr
< blortRecognizer::Recognizer3D
recognizer
float recovery_conf_threshold
std::string sift_file

Detailed Description

Definition at line 55 of file gldetector.h.


Constructor & Destructor Documentation

GLDetector::GLDetector ( const sensor_msgs::CameraInfo &  camera_info,
const std::string &  config_root 
)

Definition at line 51 of file gldetector.cpp.

Definition at line 124 of file gldetector.cpp.


Member Function Documentation

Definition at line 117 of file gldetector.cpp.

cv::Mat GLDetector::getImage ( )

Get the rendered image for visualization.

Definition at line 110 of file gldetector.cpp.

void GLDetector::reconfigure ( blort_ros::DetectorConfig  config)

Control the tracker using a ROS reconfigure_gui node.

Parameters:
reconfigure_guimessagetype

Definition at line 105 of file gldetector.cpp.

bool GLDetector::recovery ( const cv::Mat &  image,
blort_ros::RecoveryCall::Response resp 
)

Method to run and handle recovery state.

Definition at line 69 of file gldetector.cpp.

Method to run on the previously stored image.

See also:
recovery

Definition at line 78 of file gldetector.cpp.

void blort_ros::GLDetector::setNNThreshold ( double  nn_threshold) [inline]

Set the threshold of the inner nearest neighbor match.

Definition at line 99 of file gldetector.h.

void blort_ros::GLDetector::setRansacNPointsToMatch ( unsigned int  n) [inline]

Set the threshold of the inner nearest neighbor match.

Definition at line 103 of file gldetector.h.


Member Data Documentation

IplImage* blort_ros::GLDetector::image_ [private]

Definition at line 73 of file gldetector.h.

Definition at line 74 of file gldetector.h.

Definition at line 77 of file gldetector.h.

std::string blort_ros::GLDetector::model_name [private]

Definition at line 69 of file gldetector.h.

std::string blort_ros::GLDetector::pose_cal [private]

Definition at line 70 of file gldetector.h.

Definition at line 60 of file gldetector.h.

Definition at line 66 of file gldetector.h.

Definition at line 63 of file gldetector.h.

std::string blort_ros::GLDetector::sift_file [private]

Definition at line 69 of file gldetector.h.


The documentation for this class was generated from the following files:


blort_ros
Author(s): Bence Magyar
autogenerated on Thu Jan 2 2014 11:39:13