Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
pcl::CRHAlignment< PointT, nbins_ > Class Template Reference

CRHAlignment uses two Camera Roll Histograms (CRH) to find the roll rotation that aligns both views. See: More...

#include <crh_alignment.h>

List of all members.

Classes

struct  peaks_ordering
 Sorts peaks. More...

Public Member Functions

void align (pcl::PointCloud< pcl::Histogram< nbins_ > > &input_ftt, pcl::PointCloud< pcl::Histogram< nbins_ > > &target_ftt)
 Computes the transformation aligning model to input.
void computeRollAngle (pcl::PointCloud< pcl::Histogram< nbins_ > > &input_ftt, pcl::PointCloud< pcl::Histogram< nbins_ > > &target_ftt, std::vector< float > &peaks)
 Computes the roll angle that aligns input to modle.
 CRHAlignment ()
 Constructor.
void getTransforms (std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transforms)
 returns the computed transformations
void setInputAndTargetCentroids (Eigen::Vector3f &c1, Eigen::Vector3f &c2)
 sets model and input centroids
void setInputAndTargetView (PointTPtr &input_view, PointTPtr &target_view)
 sets model and input views

Private Types

typedef pcl::PointCloud
< PointT >::Ptr 
PointTPtr

Private Member Functions

void computeRollTransform (Eigen::Vector3f &centroidInput, Eigen::Vector3f &centroidResult, double roll_angle, Eigen::Affine3f &final_trans)
 computes the roll transformation
void computeTransformToZAxes (Eigen::Vector3f &centroid, Eigen::Affine3f &transform)
 computes the transformation to the z-axis

Private Attributes

float accept_threshold_
 Threshold for a peak to be accepted. If peak_i >= (max_peak * accept_threhsold_) => peak is accepted.
Eigen::Vector3f centroid_input_
 Centroid of the input_view_.
Eigen::Vector3f centroid_target_
 Centroid of the model_view_.
PointTPtr input_view_
 View of the input.
int max_peaks_
 Allowed maximum number of peaks.
float quantile_
 Quantile of peaks after sorting to be checked.
PointTPtr target_view_
 View of the model to be aligned to input_view_.
std::vector< Eigen::Matrix4f,
Eigen::aligned_allocator
< Eigen::Matrix4f > > 
transforms_
 transforms from model view to input view

Detailed Description

template<typename PointT, int nbins_>
class pcl::CRHAlignment< PointT, nbins_ >

CRHAlignment uses two Camera Roll Histograms (CRH) to find the roll rotation that aligns both views. See:

Author:
Aitor Aldoma

Definition at line 31 of file crh_alignment.h.


Member Typedef Documentation

template<typename PointT , int nbins_>
typedef pcl::PointCloud<PointT>::Ptr pcl::CRHAlignment< PointT, nbins_ >::PointTPtr [private]

Definition at line 45 of file crh_alignment.h.


Constructor & Destructor Documentation

template<typename PointT , int nbins_>
pcl::CRHAlignment< PointT, nbins_ >::CRHAlignment ( ) [inline]

Constructor.

Definition at line 107 of file crh_alignment.h.


Member Function Documentation

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::align ( pcl::PointCloud< pcl::Histogram< nbins_ > > &  input_ftt,
pcl::PointCloud< pcl::Histogram< nbins_ > > &  target_ftt 
) [inline]

Computes the transformation aligning model to input.

Parameters:
[in]input_fttCRH histogram of the input cloud
[in]target_fttCRH histogram of the target cloud

Definition at line 147 of file crh_alignment.h.

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::computeRollAngle ( pcl::PointCloud< pcl::Histogram< nbins_ > > &  input_ftt,
pcl::PointCloud< pcl::Histogram< nbins_ > > &  target_ftt,
std::vector< float > &  peaks 
) [inline]

Computes the roll angle that aligns input to modle.

Parameters:
[in]CRHhistogram of the input cloud
[in]CRHhistogram of the target cloud
[out]Vectorcontaining angles where the histograms correlate

Definition at line 185 of file crh_alignment.h.

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::computeRollTransform ( Eigen::Vector3f &  centroidInput,
Eigen::Vector3f &  centroidResult,
double  roll_angle,
Eigen::Affine3f &  final_trans 
) [inline, private]

computes the roll transformation

Parameters:
[in]centroidinput
[in]centroidview
[in]roll_angle
[out]rolltransformation

Definition at line 92 of file crh_alignment.h.

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::computeTransformToZAxes ( Eigen::Vector3f &  centroid,
Eigen::Affine3f &  transform 
) [inline, private]

computes the transformation to the z-axis

Parameters:
[in]centroid
[out]trasnformationto z-axis

Definition at line 71 of file crh_alignment.h.

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::getTransforms ( std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &  transforms) [inline]

returns the computed transformations

Parameters:
[out]transformations

Definition at line 116 of file crh_alignment.h.

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::setInputAndTargetCentroids ( Eigen::Vector3f &  c1,
Eigen::Vector3f &  c2 
) [inline]

sets model and input centroids

Parameters:
[in]c1model view centroid
[in]c2input view centroid

Definition at line 136 of file crh_alignment.h.

template<typename PointT , int nbins_>
void pcl::CRHAlignment< PointT, nbins_ >::setInputAndTargetView ( PointTPtr input_view,
PointTPtr target_view 
) [inline]

sets model and input views

Parameters:
[in]modelview
[in]input_view

Definition at line 125 of file crh_alignment.h.


Member Data Documentation

template<typename PointT , int nbins_>
float pcl::CRHAlignment< PointT, nbins_ >::accept_threshold_ [private]

Threshold for a peak to be accepted. If peak_i >= (max_peak * accept_threhsold_) => peak is accepted.

Definition at line 64 of file crh_alignment.h.

template<typename PointT , int nbins_>
Eigen::Vector3f pcl::CRHAlignment< PointT, nbins_ >::centroid_input_ [private]

Centroid of the input_view_.

Definition at line 54 of file crh_alignment.h.

template<typename PointT , int nbins_>
Eigen::Vector3f pcl::CRHAlignment< PointT, nbins_ >::centroid_target_ [private]

Centroid of the model_view_.

Definition at line 52 of file crh_alignment.h.

template<typename PointT , int nbins_>
PointTPtr pcl::CRHAlignment< PointT, nbins_ >::input_view_ [private]

View of the input.

Definition at line 50 of file crh_alignment.h.

template<typename PointT , int nbins_>
int pcl::CRHAlignment< PointT, nbins_ >::max_peaks_ [private]

Allowed maximum number of peaks.

Definition at line 58 of file crh_alignment.h.

template<typename PointT , int nbins_>
float pcl::CRHAlignment< PointT, nbins_ >::quantile_ [private]

Quantile of peaks after sorting to be checked.

Definition at line 60 of file crh_alignment.h.

template<typename PointT , int nbins_>
PointTPtr pcl::CRHAlignment< PointT, nbins_ >::target_view_ [private]

View of the model to be aligned to input_view_.

Definition at line 48 of file crh_alignment.h.

template<typename PointT , int nbins_>
std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > pcl::CRHAlignment< PointT, nbins_ >::transforms_ [private]

transforms from model view to input view

Definition at line 56 of file crh_alignment.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:39:32