Classes | Public Member Functions | Protected Member Functions | Protected Attributes
ObjectDetectorMethod Class Reference

#include <ObjectDetectorMethod.h>

Inheritance diagram for ObjectDetectorMethod:
Inheritance graph
[legend]

List of all members.

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
VisualizationManagerm_visualizer
 debug dir

Detailed Description

Definition at line 46 of file ObjectDetectorMethod.h.


Constructor & Destructor Documentation

Visualization functions.

Creates the detection method with a visualization manager

Parameters:
vis

Definition at line 139 of file ObjectDetectorMethod.h.


Member Function Documentation

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

Parameters:
facemodel face
face_indicesindices of correspondences in face
scene_surfsetfeatures in the scene image
scene_indicesindices of correspondences in the scene
cameracamera 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

Parameters:
cToa transformation in vision orientaiton
rTosame 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

Parameters:
face
indicesindices of face points involved in
cTotransformation from camera to object
points3dreturning 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

Parameters:
face
cTotransformation from camera to object
points3dreturning 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

Parameters:
Ttransformation matrix
poseROS pose

Definition at line 155 of file ObjectDetectorMethod.cpp.

virtual bool ObjectDetectorMethod::debugMode ( ) const [inline, virtual]

Says whether the debug mode is on

Returns:
true iif 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

Parameters:
data
modelmodel to search for
detectionresults

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

Parameters:
face
indicesindices 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

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

Parameters:
face
indicesindices 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

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

Parameters:
facedetected face of the object
cTotransformation from camera to object
cameraintrinsic camera parameters
indicesindices of face points involved in cTo transformation estimate
points2dall 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

Parameters:
facedetected face of the object
cTotransformation from camera to object
cameraintrinsic camera parameters
points2dall 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

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

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

Visualizes an image

Parameters:
image

Definition at line 146 of file ObjectDetectorMethod.h.


Member Data Documentation

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.

debug dir

Definition at line 283 of file ObjectDetectorMethod.h.


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


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:15