Public Member Functions | Static Public Member Functions | Public Attributes
ObjectAspect Class Reference

#include <recognitionmodel.h>

List of all members.

Public Member Functions

int calculate (const cv::Mat &image, const PointCloud::Ptr &pointcloud)
void findCorrespondences (const ObjectAspect &other, std::vector< cv::Point2i > &ptpairs)
void fromFile (const std::string &filename)
double matchAspects (ObjectAspect &other, Eigen::Matrix4f &transform)
 ObjectAspect ()
void plotKeypoints (cv::Mat &image)

Static Public Member Functions

static double compareSURFDescriptors (const float *d1, const float *d2, double best, int length)
static int naiveNearestNeighbor (const float *vec, const std::vector< cv::KeyPoint > &model_keypoints, const float *model_descriptors, const std::map< int, int > &imageMap2D3D)

Public Attributes

std::vector< float > descriptors
 SURF descriptors.
cv::Mat image
 2D input image
std::vector< cv::KeyPoint > keypoints
 2D keypoints
PointCloud::Ptr keypoints3D
 3D keypoints
std::map< int, int > map2D3D
 maps 2D keypoints to 3D coordinates (indices from keypoints to indices from keypoints3D)
std::map< int, int > map2D3Dinv
 inverse to map2D3D
ObjectAspectmatch
PointCloud::Ptr points
 input pointcloud

Detailed Description

An object aspect corresponds to a single view of the model. It stores a set of SURF keypoints and descriptors along with 3D information for these. Recognition models consist of multiple aspects. When detecting an object, we go through all object aspects and try to find the best match.

Definition at line 57 of file recognitionmodel.h.


Constructor & Destructor Documentation

Definition at line 59 of file recognitionmodel.cpp.


Member Function Documentation

int ObjectAspect::calculate ( const cv::Mat &  image,
const PointCloud::Ptr &  pointcloud 
)

Calculates the SURF keypoints and descriptors for this aspect and determines their 3D coordinates.

Parameters:
image2D camera image
pointclouddense point cloud for extracting 3D coordinates

Definition at line 64 of file recognitionmodel.cpp.

double ObjectAspect::compareSURFDescriptors ( const float *  d1,
const float *  d2,
double  best,
int  length 
) [static]

Calculates the distance between 2 SURF descriptors.

Returns:
euclidean distance
Parameters:
d1first descriptor
d2second descriptor
bestlowest distance found until now
lengthlength of descriptors (has to be a multiple of 4)

Definition at line 277 of file recognitionmodel.cpp.

void ObjectAspect::findCorrespondences ( const ObjectAspect other,
std::vector< cv::Point2i > &  ptpairs 
)

Finds a set of correspondences between this and another object aspect and gives a list of correspondences.

Parameters:
otherthe other ObjectAspect to compare
ptpairsoutput parameter, where each cv::Point2i contains (index of this ObjectAspect's keypoint, index of other's keypoint)

Definition at line 293 of file recognitionmodel.cpp.

void ObjectAspect::fromFile ( const std::string &  filename)

Loads an ObjectAspect from a dense .pcd file.

Parameters:
filenamefilename to a dense .pcd

Definition at line 407 of file recognitionmodel.cpp.

double ObjectAspect::matchAspects ( ObjectAspect other,
Eigen::Matrix4f &  transform 
)

Tries to match 2 aspects and calculates the resulting transformation.

Returns:
1 for success, DBL_MAX for failure
Parameters:
otherthe ObjectAspect to compare with
outputparameter, gives the resulting transformation

Definition at line 115 of file recognitionmodel.cpp.

int ObjectAspect::naiveNearestNeighbor ( const float *  vec,
const std::vector< cv::KeyPoint > &  model_keypoints,
const float *  model_descriptors,
const std::map< int, int > &  imageMap2D3D 
) [static]

Finds the nearest neighbor of a given SURF descriptor.

Returns:
index of the nearest neighbor, or -1 if none is found
Parameters:
vecSURF descriptor
model_keypointskeypoints of the ObjectAspect
model_descriptorsdescriptors of the ObjectAspect
imageMap2D3Dmap from 2D points to 3D points

Definition at line 248 of file recognitionmodel.cpp.

void ObjectAspect::plotKeypoints ( cv::Mat &  image)

Definition at line 316 of file recognitionmodel.cpp.


Member Data Documentation

SURF descriptors.

Definition at line 113 of file recognitionmodel.h.

2D input image

Definition at line 122 of file recognitionmodel.h.

2D keypoints

Definition at line 111 of file recognitionmodel.h.

PointCloud::Ptr ObjectAspect::keypoints3D

3D keypoints

Definition at line 119 of file recognitionmodel.h.

std::map<int,int> ObjectAspect::map2D3D

maps 2D keypoints to 3D coordinates (indices from keypoints to indices from keypoints3D)

Definition at line 115 of file recognitionmodel.h.

std::map<int,int> ObjectAspect::map2D3Dinv

inverse to map2D3D

Definition at line 117 of file recognitionmodel.h.

Definition at line 125 of file recognitionmodel.h.

PointCloud::Ptr ObjectAspect::points

input pointcloud

Definition at line 124 of file recognitionmodel.h.


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


re_kinect_object_detector
Author(s): Andreas Koch
autogenerated on Sun Jan 5 2014 11:38:30