Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar > Class Template Reference

#include <pcl_registration_module.h>

List of all members.

Public Types

typedef pcl::Registration
< PointSource, PointTarget >
::PointCloudSource 
PointCloudSource
typedef pcl::Registration
< PointSource, PointTarget >
::PointCloudTarget 
PointCloudTarget
typedef PointCloudSource::ConstPtr PointSourceConstPtr
typedef PointCloudSource::Ptr PointSourcePtr
typedef PointCloudTarget::ConstPtr PointTargetConstPtr
typedef PointCloudTarget::Ptr PointTargetPtr
typedef pcl::Registration
< PointSource, PointTarget > 
tRegistration

Public Member Functions

 CPclRegistration ()
 Constructor.
EPclRegistrationMode getMode ()
 Get mode.
template<class tpRegistration >
tpRegistration * getRegistrationAlgorithmPtr ()
 Get registration algorithm pointer.
std::string getStrMode ()
 Get registration mode as a string.
Eigen::Matrix4f getTransform ()
 Get output transform.
void init (ros::NodeHandle &node_handle)
bool isRegistering ()
 Is registration used.
bool process (PointSourcePtr &source, PointTargetPtr &target, PointSourcePtr &output)
void resetParameters ()
 Reinitialize registration parameters.
void setMode (EPclRegistrationMode mode)
 Set used mode.

Static Public Attributes

static const std::string m_mode_names []

Protected Member Functions

bool inSensorCone (const cv::Point2d &uv)
EPclRegistrationMode modeFromString (const std::string &name)
void setRegistrationParameters ()
 Set common parameters.
void setSCAParameters ()
 Set SCA parameters.

Protected Attributes

pcl::IterativeClosestPoint
< PointSource, PointTarget > 
m_algIcp
 ICP algorithm.
pcl::IterativeClosestPointNonLinear
< PointSource, PointTarget > 
m_algIcpNl
 Nonlinear ICP.
pcl::SampleConsensusInitialAlignment
< PointSource, PointTarget,
pcl::FPFHSignature33 > 
m_algSCA
 Sample consensus alignment.
double m_maxCorrespondenceDistance
 Maximal correspondence distance.
int m_maxIterations
 Maximum of iterations.
EPclRegistrationMode m_mode
 Used mode.
double m_RANSACOutlierRejectionThreshold
 RANSAC outlier rejection threshodl.
tRegistrationm_registrationPtr
 Used registration.
int m_scaCorrespondenceRamdomness
 Number of neighbors to use when selecting a random feature correspondence.
double m_scaMinSampleDistance
 Minimum distances between samples.
int m_scaNumOfSamples
 Number of samples to use during each iteration.
double m_transformationEpsilon
 Transformation epsilon value.

Detailed Description

template<typename PointSource, typename PointTarget, typename Scalar = float>
class srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >

Definition at line 50 of file pcl_registration_module.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::Registration<PointSource, PointTarget>::PointCloudSource srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::PointCloudSource

Definition at line 54 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::Registration<PointSource, PointTarget>::PointCloudTarget srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::PointCloudTarget

Definition at line 58 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::ConstPtr srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::PointSourceConstPtr

Definition at line 56 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::Ptr srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::PointSourcePtr

Definition at line 55 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::ConstPtr srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::PointTargetConstPtr

Definition at line 60 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::Ptr srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::PointTargetPtr

Definition at line 59 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::Registration<PointSource, PointTarget> srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::tRegistration

Definition at line 53 of file pcl_registration_module.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::CPclRegistration ( ) [inline]

Constructor.

Definition at line 67 of file pcl_registration_module.h.


Member Function Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
EPclRegistrationMode srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::getMode ( ) [inline]

Get mode.

Definition at line 73 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
template<class tpRegistration >
tpRegistration* srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::getRegistrationAlgorithmPtr ( ) [inline]

Get registration algorithm pointer.

Definition at line 95 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::string srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::getStrMode ( ) [inline]

Get registration mode as a string.

Definition at line 105 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
Eigen::Matrix4f srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::getTransform ( ) [inline]

Get output transform.

Definition at line 79 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::init ( ros::NodeHandle node_handle)

Initialize parameters from the parameter server

Parameters:
node_handleNode handle
template<typename PointSource, typename PointTarget, typename Scalar = float>
bool srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::inSensorCone ( const cv::Point2d &  uv) [protected]
template<typename PointSource, typename PointTarget, typename Scalar = float>
bool srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::isRegistering ( ) [inline]

Is registration used.

Definition at line 76 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
EPclRegistrationMode srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::modeFromString ( const std::string &  name) [protected]

Convert string to the mode

Parameters:
nameMode name
template<typename PointSource, typename PointTarget, typename Scalar = float>
bool srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::process ( PointSourcePtr source,
PointTargetPtr target,
PointSourcePtr output 
)

Process data

Parameters:
sourceSource point cloud - this should be aligned to the target cloud
targetTarget point cloud - to this cloud should be source cloud aligned
outputOutput point cloud
template<typename PointSource, typename PointTarget, typename Scalar = float>
void srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::resetParameters ( )

Reinitialize registration parameters.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::setMode ( EPclRegistrationMode  mode)

Set used mode.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::setRegistrationParameters ( ) [protected]

Set common parameters.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::setSCAParameters ( ) [protected]

Set SCA parameters.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::IterativeClosestPoint< PointSource, PointTarget > srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_algIcp [protected]

ICP algorithm.

Definition at line 128 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::IterativeClosestPointNonLinear< PointSource, PointTarget > srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_algIcpNl [protected]

Nonlinear ICP.

Definition at line 131 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, pcl::FPFHSignature33 > srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_algSCA [protected]

Sample consensus alignment.

Definition at line 134 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_maxCorrespondenceDistance [protected]

Maximal correspondence distance.

Definition at line 149 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_maxIterations [protected]

Maximum of iterations.

Definition at line 143 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
EPclRegistrationMode srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_mode [protected]

Used mode.

Definition at line 125 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
const std::string srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_mode_names[] [static]

Definition at line 63 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_RANSACOutlierRejectionThreshold [protected]

RANSAC outlier rejection threshodl.

Definition at line 146 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
tRegistration* srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_registrationPtr [protected]

Used registration.

Definition at line 137 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_scaCorrespondenceRamdomness [protected]

Number of neighbors to use when selecting a random feature correspondence.

Definition at line 164 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_scaMinSampleDistance [protected]

Minimum distances between samples.

Definition at line 158 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_scaNumOfSamples [protected]

Number of samples to use during each iteration.

Definition at line 161 of file pcl_registration_module.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double srs_env_model::CPclRegistration< PointSource, PointTarget, Scalar >::m_transformationEpsilon [protected]

Transformation epsilon value.

Definition at line 152 of file pcl_registration_module.h.


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


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:50:51