tabletop_object_detector::IterativeTranslationFitter Class Reference

Does an ICP-like fitting only in the X and Y translation DOFs. More...

#include <iterative_distance_fitter.h>

Inheritance diagram for tabletop_object_detector::IterativeTranslationFitter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

template<class PointCloudType >
ModelFitInfo fitPointCloud (const PointCloudType &cloud)
 Main fitting function.
 IterativeTranslationFitter ()
 Stub, just calls super's constructor.
 ~IterativeTranslationFitter ()
 Empty stub.

Private Member Functions

template<class PointCloudType >
geometry_msgs::Point32 centerOfSupport (const PointCloudType &cloud)
 Helper function for fitting.
template<class PointCloudType >
double getFitScoreAndGradient (const PointCloudType &cloud, const geometry_msgs::Point32 &location, geometry_msgs::Point32 &vector, double &maxDist)
 Inner loop when doing translation fitting.

Detailed Description

Does an ICP-like fitting only in the X and Y translation DOFs.

Definition at line 46 of file iterative_distance_fitter.h.


Constructor & Destructor Documentation

tabletop_object_detector::IterativeTranslationFitter::IterativeTranslationFitter (  )  [inline]

Stub, just calls super's constructor.

Definition at line 58 of file iterative_distance_fitter.h.

tabletop_object_detector::IterativeTranslationFitter::~IterativeTranslationFitter (  )  [inline]

Empty stub.

Definition at line 60 of file iterative_distance_fitter.h.


Member Function Documentation

template<class PointCloudType >
geometry_msgs::Point32 tabletop_object_detector::IterativeTranslationFitter::centerOfSupport ( const PointCloudType &  cloud  )  [inline, private]

Helper function for fitting.

Computes the point at the bottom of the point cloud vertical to the center of gravity. This is the point where the table supports the object.

Definition at line 77 of file iterative_distance_fitter.h.

template<class PointCloudType >
ModelFitInfo tabletop_object_detector::IterativeTranslationFitter::fitPointCloud ( const PointCloudType &  cloud  )  [inline]

Main fitting function.

Iterates over the inner loop of getFitScoreAndGradient, then moves in the direction of the computed gradient. Does this until the score stops decreasing.

The fit is initialized to the centroid of the cloud along x and y, and 0 along z. This assumes that the meshes are all such that the origin is at the bottom, with the z axis pointing up. It also assumes the points have been translated to a coordinate frame where z=0 is the table plane.

For the same reason. there is no iteration done along z at all.

Definition at line 171 of file iterative_distance_fitter.h.

template<class PointCloudType >
double tabletop_object_detector::IterativeTranslationFitter::getFitScoreAndGradient ( const PointCloudType &  cloud,
const geometry_msgs::Point32 &  location,
geometry_msgs::Point32 &  vector,
double &  maxDist 
) [inline, private]

Inner loop when doing translation fitting.

Definition at line 97 of file iterative_distance_fitter.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator


tabletop_object_detector
Author(s): Marius Muja and Matei Ciocarlie
autogenerated on Fri Jan 11 09:34:40 2013