#include <ObjectDetectorMethod.h>

Classes | |
| class | DetectionData |
Public Member Functions | |
| virtual bool | debugMode () const |
| virtual void | detect (ObjectDetectorMethod::DetectionData &data, ObjectModel &model, re_msgs::DetectedObject &detection)=0 |
| virtual void | setDebugMode (bool onoff, const std::string &dir) |
| virtual void | setVisualizationManager (VisualizationManager *vis) |
| virtual bool | visualizationMode () const |
Protected Member Functions | |
| void | calculatePose (const ObjectModel::Face &face, const std::vector< int > &face_indices, const DVision::SurfSet &scene_surfset, const std::vector< int > &scene_indices, const CameraBridge &camera, cv::Mat &cTo) const |
| Functions for several algorithms. | |
| void | changeOrientation (const cv::Mat &cTo, cv::Mat &rTo) const |
| void | convert3DPoints (const ObjectModel::Face &face, const std::vector< int > &indices, const cv::Mat &cTo, std::vector< geometry_msgs::Point > &points3d) const |
| void | convert3DPoints (const ObjectModel::Face &face, const cv::Mat &cTo, std::vector< geometry_msgs::Point > &points3d) const |
| void | convertPose (const cv::Mat &T, geometry_msgs::Pose &pose) const |
| void | get3DModelPoints (const ObjectModel::Face &face, const std::vector< int > &indices, std::vector< geometry_msgs::Point > &points3d) const |
| void | get3DModelPoints (const ObjectModel::Face &face, std::vector< geometry_msgs::Point > &points3d) const |
| void | getPointsOctave (const ObjectModel::Face &face, const std::vector< int > &indices, std::vector< int > &octave) const |
| void | getPointsOctave (const ObjectModel::Face &face, std::vector< int > &octave) const |
| ObjectDetectorMethod (VisualizationManager *vis=NULL) | |
| Visualization functions. | |
| void | project2DPoints (const ObjectModel::Face &face, const cv::Mat &cTo, const CameraBridge &camera, const std::vector< int > &indices, std::vector< re_msgs::Pixel > &points2d) const |
| void | project2DPoints (const ObjectModel::Face &face, const cv::Mat &cTo, const CameraBridge &camera, std::vector< re_msgs::Pixel > &points2d) const |
| void | visualize (const cv::Mat &image, const std::string &text="", bool hold=false) |
Protected Attributes | |
| bool | m_debug |
| std::string | m_debug_dir |
| debug mode | |
| VisualizationManager * | m_visualizer |
| debug dir | |
Definition at line 46 of file ObjectDetectorMethod.h.
| ObjectDetectorMethod::ObjectDetectorMethod | ( | VisualizationManager * | vis = NULL | ) | [inline, protected] |
Visualization functions.
Creates the detection method with a visualization manager
| vis |
Definition at line 139 of file ObjectDetectorMethod.h.
| void ObjectDetectorMethod::calculatePose | ( | const ObjectModel::Face & | face, |
| const std::vector< int > & | face_indices, | ||
| const DVision::SurfSet & | scene_surfset, | ||
| const std::vector< int > & | scene_indices, | ||
| const CameraBridge & | camera, | ||
| cv::Mat & | cTo | ||
| ) | const [protected] |
Functions for several algorithms.
Calculates the 3D pose of the model face in the image. Assumes that the keypoints come from a rectified image
| face | model face |
| face_indices | indices of correspondences in face |
| scene_surfset | features in the scene image |
| scene_indices | indices of correspondences in the scene |
| camera | camera intrinsic parameters |
| cTo | (out) returned 4x4 matrix transformation from camera to object |
Definition at line 52 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::changeOrientation | ( | const cv::Mat & | cTo, |
| cv::Mat & | rTo | ||
| ) | const [protected] |
Changes the orientation of a transformation from the vision reference system to the robotics reference system. In vision: x right, y down, z forward In robotics: x forward, y left, z up
| cTo | a transformation in vision orientaiton |
| rTo | same transformation in robotics orientation |
Definition at line 452 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::convert3DPoints | ( | const ObjectModel::Face & | face, |
| const std::vector< int > & | indices, | ||
| const cv::Mat & | cTo, | ||
| std::vector< geometry_msgs::Point > & | points3d | ||
| ) | const [protected] |
Converts 3D points of a face into the camera reference
| face | |
| indices | indices of face points involved in |
| cTo | transformation from camera to object |
| points3d | returning points3d in the camera reference |
Definition at line 235 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::convert3DPoints | ( | const ObjectModel::Face & | face, |
| const cv::Mat & | cTo, | ||
| std::vector< geometry_msgs::Point > & | points3d | ||
| ) | const [protected] |
Converts all the 3D points of a face into the camera reference
| face | |
| cTo | transformation from camera to object |
| points3d | returning pointsd in the camera reference |
Definition at line 268 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::convertPose | ( | const cv::Mat & | T, |
| geometry_msgs::Pose & | pose | ||
| ) | const [protected] |
Converts a 4x4 transformation matrix into a ROS pose data structure
| T | transformation matrix |
| pose | ROS pose |
Definition at line 155 of file ObjectDetectorMethod.cpp.
| virtual bool ObjectDetectorMethod::debugMode | ( | ) | const [inline, virtual] |
Says whether the debug mode is on
Definition at line 116 of file ObjectDetectorMethod.h.
| virtual void ObjectDetectorMethod::detect | ( | ObjectDetectorMethod::DetectionData & | data, |
| ObjectModel & | model, | ||
| re_msgs::DetectedObject & | detection | ||
| ) | [pure virtual] |
Tries to detect in the given data the given model. Results are stored in detection
| data | |
| model | model to search for |
| detection | results |
Implemented in Surf3DDetector, and SurfPlanarDetector.
| void ObjectDetectorMethod::get3DModelPoints | ( | const ObjectModel::Face & | face, |
| const std::vector< int > & | indices, | ||
| std::vector< geometry_msgs::Point > & | points3d | ||
| ) | const [protected] |
Copies all the model 3d points from the given face
| face | |
| indices | indices of face points involved in cTo transformation estimate |
| points3d,: | points in the object reference |
Definition at line 319 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::get3DModelPoints | ( | const ObjectModel::Face & | face, |
| std::vector< geometry_msgs::Point > & | points3d | ||
| ) | const [protected] |
Copies all the model 3d points from the given face
| face | |
| points3d,: | points in the object reference |
Definition at line 301 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::getPointsOctave | ( | const ObjectModel::Face & | face, |
| const std::vector< int > & | indices, | ||
| std::vector< int > & | octave | ||
| ) | const [protected] |
Returns the octave of all 3d points from the given face
| face | |
| indices | indices of face points involved in cTo transformation estimate |
| octave,: | scale-space octave in which the feature has been found |
Definition at line 337 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::getPointsOctave | ( | const ObjectModel::Face & | face, |
| std::vector< int > & | octave | ||
| ) | const [protected] |
Returns the octave of all 3d points from the given face
| face | |
| octave,: | scale-space octave in which the feature has been found |
Definition at line 352 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::project2DPoints | ( | const ObjectModel::Face & | face, |
| const cv::Mat & | cTo, | ||
| const CameraBridge & | camera, | ||
| const std::vector< int > & | indices, | ||
| std::vector< re_msgs::Pixel > & | points2d | ||
| ) | const [protected] |
Projects the 3D points involved in cTo transformation of the face into the image given the pose of the object and the parameters of the camera Note: this function does not check if the 2d points are within the bounds of the image Note: that is done in ObjectDetectorProvider::rectifyDetections
| face | detected face of the object |
| cTo | transformation from camera to object |
| camera | intrinsic camera parameters |
| indices | indices of face points involved in cTo transformation estimate |
| points2d | all the 3d points of the face projected into the camera |
Definition at line 408 of file ObjectDetectorMethod.cpp.
| void ObjectDetectorMethod::project2DPoints | ( | const ObjectModel::Face & | face, |
| const cv::Mat & | cTo, | ||
| const CameraBridge & | camera, | ||
| std::vector< re_msgs::Pixel > & | points2d | ||
| ) | const [protected] |
Projects all the 3D points of the face into the image given the pose of the object and the parameters of the camera Note: this function does not check if the 2d points are within the bounds of the image Note: that is done in ObjectDetectorProvider::rectifyDetections
| face | detected face of the object |
| cTo | transformation from camera to object |
| camera | intrinsic camera parameters |
| points2d | all the 3d points of the face projected into the camera |
Definition at line 365 of file ObjectDetectorMethod.cpp.
| virtual void ObjectDetectorMethod::setDebugMode | ( | bool | onoff, |
| const std::string & | dir | ||
| ) | [inline, virtual] |
Sets a flag to say if debug information should be generated
| onoff | debug mode iif true |
Definition at line 106 of file ObjectDetectorMethod.h.
| virtual void ObjectDetectorMethod::setVisualizationManager | ( | VisualizationManager * | vis | ) | [inline, virtual] |
Sets a visualization manager for this method
| vis |
Definition at line 122 of file ObjectDetectorMethod.h.
| virtual bool ObjectDetectorMethod::visualizationMode | ( | ) | const [inline, virtual] |
Returns whether visualization must be done
Definition at line 130 of file ObjectDetectorMethod.h.
| void ObjectDetectorMethod::visualize | ( | const cv::Mat & | image, |
| const std::string & | text = "", |
||
| bool | hold = false |
||
| ) | [inline, protected] |
bool ObjectDetectorMethod::m_debug [protected] |
Definition at line 280 of file ObjectDetectorMethod.h.
std::string ObjectDetectorMethod::m_debug_dir [protected] |
debug mode
Definition at line 281 of file ObjectDetectorMethod.h.
VisualizationManager* ObjectDetectorMethod::m_visualizer [protected] |
debug dir
Definition at line 283 of file ObjectDetectorMethod.h.