Classes | Public Member Functions | Private Member Functions | Private Attributes
cob_3d_registration::Registration_Infobased< Point > Class Template Reference

#include <registration_info.h>

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

List of all members.

Classes

struct  SORT_S

Public Member Functions

virtual bool compute ()
int getBadCounter () const
void getClouds (pcl::PointCloud< Point > &tmp_pc_old, pcl::PointCloud< Point > &tmp_pc_new)
 debug purpose: get HIRN points H+ and H-
pcl::PointCloud< PointgetLastInput ()
 inserted input (debug)
pcl::PointCloud< PointgetLastInput2 ()
 reprojected input (debug)
virtual boost::shared_ptr
< pcl::PointCloud< Point > > 
getMap ()
 map is not necessarily implemented
virtual boost::shared_ptr
< const pcl::PointCloud
< pcl::PointXYZRGB > > 
getMarkers2 ()
pcl::PointCloud< Point > & getSource ()
pcl::PointCloud< Point > & getTarget ()
 Registration_Infobased ()
void reset ()
void SetAlwaysRelevantChanges (const bool b)
 if pose information is used, the changes are always relevant!
void setCheckBySamples (const bool b)
 check plausibility of result (only with Kinect)
void setKinectParameters (const float f, const float dx, const float dy)
 setting up reprojection parameters, if not set it will be calculated (at least tried to)
void setMaxAngularDistance (const float f)
void setMaxInfo (const int f)
void setMaxTranslationDistance (const float f)
void setMinChanges (const int f)
void setMinInfo (const int f)
virtual void setOdometry (const Eigen::Matrix4f &odometry)
 change transformation matrix (for example if odometry results are known)
void setThresholdDiff (const float f)
void setThresholdStep (const float f)
virtual void setTransformation (const Eigen::Matrix4f &mat)
void setUseICP (const bool b)
 always use ICP instead of HIRN-backend
virtual ~Registration_Infobased ()

Private Member Functions

bool checkSamples (const Eigen::Matrix4f &T, int *bad_out=NULL)
virtual bool compute_corrospondences ()
virtual bool compute_features ()
virtual bool compute_transformation ()
int getI (const int ind, const pcl::PointCloud< Point > &pc)
void getKinectParameters ()
float getMaxDiff (const pcl::PointCloud< Point > &pc, const int ind)
float getMaxDiff2 (const pcl::PointCloud< Point > &pc, const int ind, const pcl::PointCloud< Point > &pc2, int &mi)
void reproject ()

Private Attributes

bool always_relevant_changes_
int bad_counter_
bool check_samples_
 check result with raycasted samples, forcing well aligned results for mapping (only with Kinect!!!)
unsigned char * depth_map
 binary map of interesting points
int failed_
std::vector< int > indices_neg2
std::vector< int > indices_pos2
 indices of HIRN points
float kinect_dx_
float kinect_dy_
float kinect_f_
boost::shared_ptr< const
pcl::PointCloud< Point > > 
last_input2_
boost::shared_ptr< const
pcl::PointCloud< Point > > 
last_input_
 frame to register against
pcl::PointCloud< pcl::PointXYZRGB > markers_
int max_info_
int min_changes_
int min_info_
bool odo_is_good_
Eigen::Matrix4f odometry_
Eigen::Matrix4f odometry_last_
pcl::PointCloud< Pointregister_
float rmax_
 max. rotation speed between two frames
pcl::PointCloud< Pointsource
pcl::PointCloud< Pointsource2_
 debug output
int standing_
pcl::PointCloud< Pointtarget
pcl::PointCloud< Pointtarget2_
float threshold_diff_
 see thesis
float threshold_step_
float tmax_
 max. translation speed between two frames
bool use_icp_
 use icp instead of global optimation
bool use_odometry_

Detailed Description

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

registration based on HIRN implementation after diploma thesis of Joshua Hampp using points of high interest for registration of 3d data input data have to stay within a defined movement speed using data without color is faster

Definition at line 87 of file registration_info.h.


Constructor & Destructor Documentation

Definition at line 133 of file registration_info.h.

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

Definition at line 171 of file registration_info.h.


Member Function Documentation

template<typename Point >
bool cob_3d_registration::Registration_Infobased< Point >::checkSamples ( const Eigen::Matrix4f &  T,
int *  bad_out = NULL 
) [private]

Definition at line 500 of file registration_info.hpp.

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

compute transformation

Returns:
true for success

Reimplemented from cob_3d_registration::GeneralRegistration< Point >.

Definition at line 196 of file registration_info.h.

template<typename Point >
bool cob_3d_registration::Registration_Infobased< Point >::compute_corrospondences ( ) [private, virtual]
template<typename Point >
bool cob_3d_registration::Registration_Infobased< Point >::compute_features ( ) [private, virtual]
template<typename Point >
bool cob_3d_registration::Registration_Infobased< Point >::compute_transformation ( ) [private, virtual]
template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::getBadCounter ( ) const [inline]

Definition at line 146 of file registration_info.h.

template<typename Point >
void cob_3d_registration::Registration_Infobased< Point >::getClouds ( pcl::PointCloud< Point > &  tmp_pc_old,
pcl::PointCloud< Point > &  tmp_pc_new 
)

debug purpose: get HIRN points H+ and H-

Definition at line 541 of file registration_info.hpp.

template<typename Point >
int cob_3d_registration::Registration_Infobased< Point >::getI ( const int  ind,
const pcl::PointCloud< Point > &  pc 
) [inline, private]

Definition at line 418 of file registration_info.hpp.

template<typename Point >
void cob_3d_registration::Registration_Infobased< Point >::getKinectParameters ( ) [private]

Definition at line 437 of file registration_info.hpp.

inserted input (debug)

Definition at line 178 of file registration_info.h.

reprojected input (debug)

Definition at line 180 of file registration_info.h.

template<typename Point>
virtual boost::shared_ptr<pcl::PointCloud<Point> > cob_3d_registration::Registration_Infobased< Point >::getMap ( ) [inline, virtual]

map is not necessarily implemented

Reimplemented from cob_3d_registration::GeneralRegistration< Point >.

Definition at line 175 of file registration_info.h.

template<typename Point>
virtual boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGB> > cob_3d_registration::Registration_Infobased< Point >::getMarkers2 ( ) [inline, virtual]

Definition at line 185 of file registration_info.h.

template<typename Point >
float cob_3d_registration::Registration_Infobased< Point >::getMaxDiff ( const pcl::PointCloud< Point > &  pc,
const int  ind 
) [inline, private]

Definition at line 359 of file registration_info.hpp.

template<typename Point >
float cob_3d_registration::Registration_Infobased< Point >::getMaxDiff2 ( const pcl::PointCloud< Point > &  pc,
const int  ind,
const pcl::PointCloud< Point > &  pc2,
int &  mi 
) [inline, private]

Definition at line 384 of file registration_info.hpp.

Definition at line 182 of file registration_info.h.

Definition at line 184 of file registration_info.h.

template<typename Point >
void cob_3d_registration::Registration_Infobased< Point >::reproject ( ) [private]

Definition at line 560 of file registration_info.hpp.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::reset ( ) [inline]

Definition at line 147 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::SetAlwaysRelevantChanges ( const bool  b) [inline]

if pose information is used, the changes are always relevant!

Definition at line 208 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setCheckBySamples ( const bool  b) [inline]

check plausibility of result (only with Kinect)

Definition at line 157 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setKinectParameters ( const float  f,
const float  dx,
const float  dy 
) [inline]

setting up reprojection parameters, if not set it will be calculated (at least tried to)

Definition at line 162 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setMaxAngularDistance ( const float  f) [inline]

Definition at line 154 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setMaxInfo ( const int  f) [inline]

Definition at line 153 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setMaxTranslationDistance ( const float  f) [inline]

Definition at line 155 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setMinChanges ( const int  f) [inline]

Definition at line 151 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setMinInfo ( const int  f) [inline]

Definition at line 152 of file registration_info.h.

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

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

Reimplemented from cob_3d_registration::GeneralRegistration< Point >.

Definition at line 188 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setThresholdDiff ( const float  f) [inline]

Definition at line 149 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setThresholdStep ( const float  f) [inline]

Definition at line 150 of file registration_info.h.

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

Reimplemented from cob_3d_registration::GeneralRegistration< Point >.

Definition at line 210 of file registration_info.h.

template<typename Point>
void cob_3d_registration::Registration_Infobased< Point >::setUseICP ( const bool  b) [inline]

always use ICP instead of HIRN-backend

for kinect only

Definition at line 159 of file registration_info.h.


Member Data Documentation

template<typename Point>
bool cob_3d_registration::Registration_Infobased< Point >::always_relevant_changes_ [private]

Definition at line 217 of file registration_info.h.

template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::bad_counter_ [private]

Definition at line 131 of file registration_info.h.

template<typename Point>
bool cob_3d_registration::Registration_Infobased< Point >::check_samples_ [private]

check result with raycasted samples, forcing well aligned results for mapping (only with Kinect!!!)

Definition at line 117 of file registration_info.h.

template<typename Point>
unsigned char* cob_3d_registration::Registration_Infobased< Point >::depth_map [private]

binary map of interesting points

Definition at line 101 of file registration_info.h.

template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::failed_ [private]

Definition at line 216 of file registration_info.h.

template<typename Point>
std::vector<int> cob_3d_registration::Registration_Infobased< Point >::indices_neg2 [private]

Definition at line 107 of file registration_info.h.

template<typename Point>
std::vector<int> cob_3d_registration::Registration_Infobased< Point >::indices_pos2 [private]

indices of HIRN points

Definition at line 107 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::kinect_dx_ [private]

Definition at line 218 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::kinect_dy_ [private]

Definition at line 218 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::kinect_f_ [private]

Definition at line 218 of file registration_info.h.

template<typename Point>
boost::shared_ptr<const pcl::PointCloud<Point> > cob_3d_registration::Registration_Infobased< Point >::last_input2_ [private]

Definition at line 104 of file registration_info.h.

template<typename Point>
boost::shared_ptr<const pcl::PointCloud<Point> > cob_3d_registration::Registration_Infobased< Point >::last_input_ [private]

frame to register against

Definition at line 104 of file registration_info.h.

template<typename Point>
pcl::PointCloud<pcl::PointXYZRGB> cob_3d_registration::Registration_Infobased< Point >::markers_ [private]

Definition at line 214 of file registration_info.h.

template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::max_info_ [private]

Definition at line 123 of file registration_info.h.

template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::min_changes_ [private]

Definition at line 123 of file registration_info.h.

template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::min_info_ [private]

Definition at line 123 of file registration_info.h.

template<typename Point>
bool cob_3d_registration::Registration_Infobased< Point >::odo_is_good_ [private]

Definition at line 217 of file registration_info.h.

template<typename Point>
Eigen::Matrix4f cob_3d_registration::Registration_Infobased< Point >::odometry_ [private]

Definition at line 215 of file registration_info.h.

template<typename Point>
Eigen::Matrix4f cob_3d_registration::Registration_Infobased< Point >::odometry_last_ [private]

Definition at line 215 of file registration_info.h.

Definition at line 213 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::rmax_ [private]

max. rotation speed between two frames

Definition at line 129 of file registration_info.h.

Definition at line 108 of file registration_info.h.

debug output

Definition at line 111 of file registration_info.h.

template<typename Point>
int cob_3d_registration::Registration_Infobased< Point >::standing_ [private]

Definition at line 216 of file registration_info.h.

Definition at line 108 of file registration_info.h.

Definition at line 111 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::threshold_diff_ [private]

see thesis

Definition at line 122 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::threshold_step_ [private]

Definition at line 122 of file registration_info.h.

template<typename Point>
float cob_3d_registration::Registration_Infobased< Point >::tmax_ [private]

max. translation speed between two frames

Definition at line 126 of file registration_info.h.

template<typename Point>
bool cob_3d_registration::Registration_Infobased< Point >::use_icp_ [private]

use icp instead of global optimation

Definition at line 114 of file registration_info.h.

template<typename Point>
bool cob_3d_registration::Registration_Infobased< Point >::use_odometry_ [private]

Definition at line 217 of file registration_info.h.


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


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