Public Types | Public Member Functions | Protected Attributes
pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar > Class Template Reference

Base warp point class. More...

#include <warp_point_rigid.h>

Inheritance diagram for pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const WarpPointRigid
< PointSourceT, PointTargetT,
Scalar > > 
ConstPtr
typedef Eigen::Matrix< Scalar, 4, 4 > Matrix4
typedef boost::shared_ptr
< WarpPointRigid< PointSourceT,
PointTargetT, Scalar > > 
Ptr
typedef Eigen::Matrix< Scalar, 4, 1 > Vector4
typedef Eigen::Matrix< Scalar,
Eigen::Dynamic, 1 > 
VectorX

Public Member Functions

int getDimension () const
 Get the number of dimensions.
const Matrix4getTransform () const
 Get the Transform used.
virtual void setParam (const VectorX &p)=0
 Set warp parameters. Pure virtual.
void warpPoint (const PointSourceT &pnt_in, PointSourceT &pnt_out) const
 Warp a point given a transformation matrix.
void warpPoint (const PointSourceT &pnt_in, Vector4 &pnt_out) const
 Warp a point given a transformation matrix.
 WarpPointRigid (int nr_dim)
 Constructor.
virtual ~WarpPointRigid ()
 Destructor.

Protected Attributes

int nr_dim_
Matrix4 transform_matrix_

Detailed Description

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
class pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >

Base warp point class.

Note:
The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float.
Author:
Radu B. Rusu

Definition at line 57 of file warp_point_rigid.h.


Member Typedef Documentation

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
typedef boost::shared_ptr<const WarpPointRigid<PointSourceT, PointTargetT, Scalar> > pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::ConstPtr
template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
typedef Eigen::Matrix<Scalar, 4, 4> pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::Matrix4
template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
typedef boost::shared_ptr<WarpPointRigid<PointSourceT, PointTargetT, Scalar> > pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::Ptr
template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
typedef Eigen::Matrix<Scalar, 4, 1> pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::Vector4

Definition at line 62 of file warp_point_rigid.h.

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::VectorX

Constructor & Destructor Documentation

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::WarpPointRigid ( int  nr_dim) [inline]

Constructor.

Parameters:
[in]nr_dimthe number of dimensions

Definition at line 70 of file warp_point_rigid.h.

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
virtual pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::~WarpPointRigid ( ) [inline, virtual]

Destructor.

Definition at line 78 of file warp_point_rigid.h.


Member Function Documentation

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
int pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::getDimension ( ) const [inline]

Get the number of dimensions.

Definition at line 117 of file warp_point_rigid.h.

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
const Matrix4& pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::getTransform ( ) const [inline]

Get the Transform used.

Definition at line 121 of file warp_point_rigid.h.

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
virtual void pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::setParam ( const VectorX p) [pure virtual]
template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
void pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::warpPoint ( const PointSourceT &  pnt_in,
PointSourceT &  pnt_out 
) const [inline]

Warp a point given a transformation matrix.

Parameters:
[in]pnt_inthe point to warp (transform)
[out]pnt_outthe warped (transformed) point

Definition at line 91 of file warp_point_rigid.h.

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
void pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::warpPoint ( const PointSourceT &  pnt_in,
Vector4 pnt_out 
) const [inline]

Warp a point given a transformation matrix.

Parameters:
[in]pnt_inthe point to warp (transform)
[out]pnt_outthe warped (transformed) point

Definition at line 107 of file warp_point_rigid.h.


Member Data Documentation

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
int pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::nr_dim_ [protected]

Definition at line 127 of file warp_point_rigid.h.

template<typename PointSourceT, typename PointTargetT, typename Scalar = float>
Matrix4 pcl::registration::WarpPointRigid< PointSourceT, PointTargetT, Scalar >::transform_matrix_ [protected]

Definition at line 128 of file warp_point_rigid.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:46:56