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 (std::vector< std::string > &obj_ids, const cv::Mat &image, blort_msgs::RecoveryCall::Response &resp)
 Method to run and handle recovery state.
bool recoveryWithLast (std::vector< std::string > &obj_ids, blort_msgs::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::vector< blort::ObjectEntryobjects
int rec3dcounter
boost::shared_ptr
< blortRecognizer::Recognizer3D
recognizer
float recovery_conf_threshold
size_t sift_files_count
std::vector< size_t > sift_index

Detailed Description

Definition at line 57 of file gldetector.h.


Constructor & Destructor Documentation

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

Definition at line 52 of file gldetector.cpp.

Definition at line 162 of file gldetector.cpp.


Member Function Documentation

Definition at line 155 of file gldetector.cpp.

cv::Mat GLDetector::getImage ( )

Get the rendered image for visualization.

Definition at line 148 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 143 of file gldetector.cpp.

bool GLDetector::recovery ( std::vector< std::string > &  obj_ids,
const cv::Mat &  image,
blort_msgs::RecoveryCall::Response &  resp 
)

Method to run and handle recovery state.

Definition at line 80 of file gldetector.cpp.

bool GLDetector::recoveryWithLast ( std::vector< std::string > &  obj_ids,
blort_msgs::RecoveryCall::Response &  resp 
)

Method to run on the previously stored image.

See also:
recovery

Definition at line 89 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 102 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 106 of file gldetector.h.


Member Data Documentation

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

Definition at line 76 of file gldetector.h.

Definition at line 77 of file gldetector.h.

Definition at line 80 of file gldetector.h.

Definition at line 71 of file gldetector.h.

Definition at line 62 of file gldetector.h.

Definition at line 68 of file gldetector.h.

Definition at line 65 of file gldetector.h.

Definition at line 73 of file gldetector.h.

std::vector<size_t> blort_ros::GLDetector::sift_index [private]

Definition at line 72 of file gldetector.h.


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


blort_ros
Author(s): Bence Magyar
autogenerated on Wed Aug 26 2015 15:24:39