Public Member Functions | Protected Member Functions | Protected Attributes
cob_3d_registration::GeneralRegistration< Point > Class Template Reference

#include <general_registration.h>

Inheritance diagram for cob_3d_registration::GeneralRegistration< Point >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool compute ()
 GeneralRegistration ()
virtual boost::shared_ptr
< pcl::PointCloud< Point > > 
getMap ()
 map is not necessarily implemented
virtual boost::shared_ptr
< const pcl::PointCloud< Point > > 
getMarkers ()
 debug function for marker visualization
virtual bool getSceneChanged () const
virtual Eigen::Matrix4f getTransformation () const
 get transformation
virtual void setInputCloud (const boost::shared_ptr< const pcl::PointCloud< Point > > &cloud)
 sets preprocessed input cloud
virtual void setInputDepthImage (const boost::shared_ptr< const cv::Mat > &img)
 set disparity image
virtual void setInputImage (const boost::shared_ptr< const cv::Mat > &img)
 set color image
virtual void setInputOginalCloud (const boost::shared_ptr< const pcl::PointCloud< Point > > &cloud)
 sets orginal input cloud
virtual void setMoved (const bool b)
virtual void setOdometry (const Eigen::Matrix4f &odometry)
 change transformation matrix (for example if odometry results are known)
virtual void setTransformation (const Eigen::Matrix4f &mat)
virtual ~GeneralRegistration ()

Protected Member Functions

virtual bool compute_corrospondences ()=0
virtual bool compute_features ()=0
virtual bool compute_transformation ()=0

Protected Attributes

boost::shared_ptr< const
pcl::PointCloud< Point > > 
input_
boost::shared_ptr< const cv::Mat > input_depth_image_
boost::shared_ptr< const cv::Mat > input_image_
boost::shared_ptr< const
pcl::PointCloud< Point > > 
input_org_
bool moved_
bool scene_changed_
Eigen::Matrix4f transformation_

Detailed Description

template<typename Point>
class cob_3d_registration::GeneralRegistration< Point >

a general abstract class for registration purpose of 3d pointclouds as input it's espected to provide ...

Definition at line 86 of file general_registration.h.


Constructor & Destructor Documentation

template<typename Point >
cob_3d_registration::GeneralRegistration< Point >::GeneralRegistration ( ) [inline]

Definition at line 89 of file general_registration.h.

template<typename Point >
virtual cob_3d_registration::GeneralRegistration< Point >::~GeneralRegistration ( ) [inline, virtual]

Definition at line 92 of file general_registration.h.


Member Function Documentation

template<typename Point >
virtual bool cob_3d_registration::GeneralRegistration< Point >::compute ( ) [inline, virtual]

compute transformation

Returns:
true for success

Reimplemented in cob_3d_registration::Registration_Infobased< Point >.

Definition at line 127 of file general_registration.h.

template<typename Point >
virtual bool cob_3d_registration::GeneralRegistration< Point >::compute_corrospondences ( ) [protected, pure virtual]
template<typename Point >
virtual bool cob_3d_registration::GeneralRegistration< Point >::compute_features ( ) [protected, pure virtual]
template<typename Point >
virtual bool cob_3d_registration::GeneralRegistration< Point >::compute_transformation ( ) [protected, pure virtual]
template<typename Point >
virtual boost::shared_ptr<pcl::PointCloud<Point> > cob_3d_registration::GeneralRegistration< Point >::getMap ( ) [inline, virtual]
template<typename Point >
virtual boost::shared_ptr<const pcl::PointCloud<Point> > cob_3d_registration::GeneralRegistration< Point >::getMarkers ( ) [inline, virtual]
template<typename Point >
virtual bool cob_3d_registration::GeneralRegistration< Point >::getSceneChanged ( ) const [inline, virtual]

Definition at line 141 of file general_registration.h.

template<typename Point >
virtual Eigen::Matrix4f cob_3d_registration::GeneralRegistration< Point >::getTransformation ( ) const [inline, virtual]

get transformation

Definition at line 138 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setInputCloud ( const boost::shared_ptr< const pcl::PointCloud< Point > > &  cloud) [inline, virtual]

sets preprocessed input cloud

Definition at line 100 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setInputDepthImage ( const boost::shared_ptr< const cv::Mat > &  img) [inline, virtual]

set disparity image

Definition at line 116 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setInputImage ( const boost::shared_ptr< const cv::Mat > &  img) [inline, virtual]

set color image

Definition at line 111 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setInputOginalCloud ( const boost::shared_ptr< const pcl::PointCloud< Point > > &  cloud) [inline, virtual]

sets orginal input cloud

Definition at line 106 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setMoved ( const bool  b) [inline, virtual]

Definition at line 140 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setOdometry ( const Eigen::Matrix4f &  odometry) [inline, virtual]

change transformation matrix (for example if odometry results are known)

Reimplemented in cob_3d_registration::Registration_Infobased< Point >.

Definition at line 95 of file general_registration.h.

template<typename Point >
virtual void cob_3d_registration::GeneralRegistration< Point >::setTransformation ( const Eigen::Matrix4f &  mat) [inline, virtual]

Member Data Documentation

template<typename Point >
boost::shared_ptr<const pcl::PointCloud<Point> > cob_3d_registration::GeneralRegistration< Point >::input_ [protected]

Definition at line 152 of file general_registration.h.

template<typename Point >
boost::shared_ptr<const cv::Mat> cob_3d_registration::GeneralRegistration< Point >::input_depth_image_ [protected]

Definition at line 153 of file general_registration.h.

template<typename Point >
boost::shared_ptr<const cv::Mat> cob_3d_registration::GeneralRegistration< Point >::input_image_ [protected]

Definition at line 153 of file general_registration.h.

template<typename Point >
boost::shared_ptr<const pcl::PointCloud<Point> > cob_3d_registration::GeneralRegistration< Point >::input_org_ [protected]

Definition at line 152 of file general_registration.h.

template<typename Point >
bool cob_3d_registration::GeneralRegistration< Point >::moved_ [protected]

Definition at line 155 of file general_registration.h.

template<typename Point >
bool cob_3d_registration::GeneralRegistration< Point >::scene_changed_ [protected]

Definition at line 155 of file general_registration.h.

template<typename Point >
Eigen::Matrix4f cob_3d_registration::GeneralRegistration< Point >::transformation_ [protected]

Definition at line 154 of file general_registration.h.


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


cob_3d_registration
Author(s): Joshua Hampp
autogenerated on Wed Aug 26 2015 11:02:36