Public Member Functions | Public Attributes | Private Attributes
lslgeneric::NDTFuser< PointT > Class Template Reference

This class fuses new point clouds into a common ndt map reference, keeping tack of the camera postion. More...

#include <ndt_fuser.h>

List of all members.

Public Member Functions

double getDoubleTime ()
void initialize (Eigen::Affine3d initPos, pcl::PointCloud< PointT > &cloud)
 NDTFuser (double map_resolution, double map_size_x_, double map_size_y_, double map_size_z_, double sensor_range_=3, bool visualize_=false, bool be2D_=false)
void setSensorPose (Eigen::Affine3d spose)
Eigen::Affine3d update (Eigen::Affine3d Tmotion, pcl::PointCloud< PointT > &cloud)
bool wasInit ()
 ~NDTFuser ()

Public Attributes

bool be2D
bool checkConsistency
lslgeneric::NDTMap< PointT > * map
 da map
double max_rotation_norm
double max_translation_norm
 perform a check for consistency against initial estimate
double sensor_range
Eigen::Affine3d Tlast_fuse
 current pose
Eigen::Affine3d Tnow
NDTViz< PointT > * viewer

Private Attributes

bool isInit
double map_size
double map_size_x
double map_size_y
double map_size_z
lslgeneric::NDTMatcherD2D
< PointT, PointT
matcher
lslgeneric::NDTMatcherD2D_2D
< PointT, PointT
matcher2D
double resolution
 resolution of the map
double rotation_fuse_delta
Eigen::Affine3d sensor_pose
double translation_fuse_delta
bool visualize

Detailed Description

template<typename PointT>
class lslgeneric::NDTFuser< PointT >

This class fuses new point clouds into a common ndt map reference, keeping tack of the camera postion.

Author:
Jari, Todor

Definition at line 20 of file ndt_fuser.h.


Constructor & Destructor Documentation

template<typename PointT>
lslgeneric::NDTFuser< PointT >::NDTFuser ( double  map_resolution,
double  map_size_x_,
double  map_size_y_,
double  map_size_z_,
double  sensor_range_ = 3,
bool  visualize_ = false,
bool  be2D_ = false 
) [inline]

Definition at line 30 of file ndt_fuser.h.

template<typename PointT>
lslgeneric::NDTFuser< PointT >::~NDTFuser ( ) [inline]

Definition at line 50 of file ndt_fuser.h.


Member Function Documentation

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::getDoubleTime ( ) [inline]

Definition at line 56 of file ndt_fuser.h.

template<typename PointT>
void lslgeneric::NDTFuser< PointT >::initialize ( Eigen::Affine3d  initPos,
pcl::PointCloud< PointT > &  cloud 
) [inline]

Set the initial position and set the first scan to the map

Set the cloud to sensor frame with respect to base

Definition at line 74 of file ndt_fuser.h.

template<typename PointT>
void lslgeneric::NDTFuser< PointT >::setSensorPose ( Eigen::Affine3d  spose) [inline]

Definition at line 62 of file ndt_fuser.h.

template<typename PointT>
Eigen::Affine3d lslgeneric::NDTFuser< PointT >::update ( Eigen::Affine3d  Tmotion,
pcl::PointCloud< PointT > &  cloud 
) [inline]

Set the cloud to sensor frame with respect to base

Create local map

Definition at line 96 of file ndt_fuser.h.

template<typename PointT>
bool lslgeneric::NDTFuser< PointT >::wasInit ( ) [inline]

Definition at line 66 of file ndt_fuser.h.


Member Data Documentation

template<typename PointT>
bool lslgeneric::NDTFuser< PointT >::be2D

Definition at line 27 of file ndt_fuser.h.

template<typename PointT>
bool lslgeneric::NDTFuser< PointT >::checkConsistency

Definition at line 24 of file ndt_fuser.h.

template<typename PointT>
bool lslgeneric::NDTFuser< PointT >::isInit [private]

Definition at line 199 of file ndt_fuser.h.

template<typename PointT>
lslgeneric::NDTMap<PointT>* lslgeneric::NDTFuser< PointT >::map

da map

Definition at line 23 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::map_size [private]

Definition at line 202 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::map_size_x [private]

Definition at line 205 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::map_size_y [private]

Definition at line 206 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::map_size_z [private]

Definition at line 207 of file ndt_fuser.h.

template<typename PointT>
lslgeneric::NDTMatcherD2D<PointT,PointT> lslgeneric::NDTFuser< PointT >::matcher [private]

Definition at line 211 of file ndt_fuser.h.

Definition at line 212 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::max_rotation_norm

Definition at line 25 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::max_translation_norm

perform a check for consistency against initial estimate

Definition at line 25 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::resolution [private]

resolution of the map

Definition at line 201 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::rotation_fuse_delta [private]

Definition at line 204 of file ndt_fuser.h.

template<typename PointT>
Eigen::Affine3d lslgeneric::NDTFuser< PointT >::sensor_pose [private]

Definition at line 210 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::sensor_range

Definition at line 26 of file ndt_fuser.h.

template<typename PointT>
Eigen::Affine3d lslgeneric::NDTFuser< PointT >::Tlast_fuse

current pose

Definition at line 22 of file ndt_fuser.h.

template<typename PointT>
Eigen::Affine3d lslgeneric::NDTFuser< PointT >::Tnow

Definition at line 22 of file ndt_fuser.h.

template<typename PointT>
double lslgeneric::NDTFuser< PointT >::translation_fuse_delta [private]

Definition at line 204 of file ndt_fuser.h.

template<typename PointT>
NDTViz<PointT>* lslgeneric::NDTFuser< PointT >::viewer

Definition at line 28 of file ndt_fuser.h.

template<typename PointT>
bool lslgeneric::NDTFuser< PointT >::visualize [private]

Definition at line 208 of file ndt_fuser.h.


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


ndt_fuser
Author(s): Todor Stoyanov, Jari Saarinen
autogenerated on Mon Oct 6 2014 03:20:34