#include <gldetector.h>
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::ObjectEntry > | objects |
int | rec3dcounter |
boost::shared_ptr < blortRecognizer::Recognizer3D > | recognizer |
float | recovery_conf_threshold |
size_t | sift_files_count |
std::vector< size_t > | sift_index |
Definition at line 57 of file gldetector.h.
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.
cv::Mat GLDetector::getDebugImage | ( | ) |
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.
reconfigure_gui | messagetype |
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.
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.
IplImage* blort_ros::GLDetector::image_ [private] |
Definition at line 76 of file gldetector.h.
cv::Mat blort_ros::GLDetector::last_image [private] |
Definition at line 77 of file gldetector.h.
bool blort_ros::GLDetector::last_reset [private] |
Definition at line 80 of file gldetector.h.
std::vector<blort::ObjectEntry> blort_ros::GLDetector::objects [private] |
Definition at line 71 of file gldetector.h.
int blort_ros::GLDetector::rec3dcounter [private] |
Definition at line 62 of file gldetector.h.
boost::shared_ptr<blortRecognizer::Recognizer3D> blort_ros::GLDetector::recognizer [private] |
Definition at line 68 of file gldetector.h.
float blort_ros::GLDetector::recovery_conf_threshold [private] |
Definition at line 65 of file gldetector.h.
size_t blort_ros::GLDetector::sift_files_count [private] |
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.