Public Member Functions | Public Attributes | Private Attributes
lslgeneric::NDTFuserHMT< 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_hmt.h>

List of all members.

Public Member Functions

double getDoubleTime ()
void initialize (Eigen::Affine3d initPos, pcl::PointCloud< PointT > &cloud, bool preLoad=false)
 NDTFuserHMT (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, bool doMultires_=false, bool fuseIncomplete_=false, int max_itr=30, std::string prefix_="", bool beHMT_=true, std::string hmt_map_dir_="map", bool _step_control=true)
bool saveMap ()
void setSensorPose (Eigen::Affine3d spose)
Eigen::Affine3d update (Eigen::Affine3d Tmotion, pcl::PointCloud< PointT > &cloud)
bool wasInit ()
 ~NDTFuserHMT ()

Public Attributes

bool be2D
bool beHMT
bool checkConsistency
int ctr
bool doMultires
FILE * fAddTimes
FILE * fRegTimes
bool fuseIncomplete
std::string hmt_map_dir
lslgeneric::NDTMap< PointT > * map
 da map
double max_rotation_norm
double max_translation_norm
 perform a check for consistency against initial estimate
std::string prefix
double sensor_range
Eigen::Affine3d Tlast_fuse
Eigen::Affine3d Tnow
Eigen::Affine3d Todom
 current pose
NDTViz< PointT > * viewer

Private Attributes

bool isInit
Eigen::Vector3d localMapSize
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::NDTFuserHMT< 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 23 of file ndt_fuser_hmt.h.


Constructor & Destructor Documentation

template<typename PointT>
lslgeneric::NDTFuserHMT< PointT >::NDTFuserHMT ( 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,
bool  doMultires_ = false,
bool  fuseIncomplete_ = false,
int  max_itr = 30,
std::string  prefix_ = "",
bool  beHMT_ = true,
std::string  hmt_map_dir_ = "map",
bool  _step_control = true 
) [inline]

Definition at line 38 of file ndt_fuser_hmt.h.

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

Definition at line 76 of file ndt_fuser_hmt.h.


Member Function Documentation

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

Definition at line 84 of file ndt_fuser_hmt.h.

template<typename PointT>
void lslgeneric::NDTFuserHMT< PointT >::initialize ( Eigen::Affine3d  initPos,
pcl::PointCloud< PointT > &  cloud,
bool  preLoad = false 
) [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 116 of file ndt_fuser_hmt.h.

template<typename PointT>
bool lslgeneric::NDTFuserHMT< PointT >::saveMap ( ) [inline]

Definition at line 99 of file ndt_fuser_hmt.h.

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

Definition at line 90 of file ndt_fuser_hmt.h.

template<typename PointT>
Eigen::Affine3d lslgeneric::NDTFuserHMT< 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 160 of file ndt_fuser_hmt.h.

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

Definition at line 94 of file ndt_fuser_hmt.h.


Member Data Documentation

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

Definition at line 31 of file ndt_fuser_hmt.h.

template<typename PointT>
bool lslgeneric::NDTFuserHMT< PointT >::beHMT

Definition at line 31 of file ndt_fuser_hmt.h.

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

Definition at line 28 of file ndt_fuser_hmt.h.

template<typename PointT>
int lslgeneric::NDTFuserHMT< PointT >::ctr

Definition at line 32 of file ndt_fuser_hmt.h.

template<typename PointT>
bool lslgeneric::NDTFuserHMT< PointT >::doMultires

Definition at line 31 of file ndt_fuser_hmt.h.

template<typename PointT>
FILE* lslgeneric::NDTFuserHMT< PointT >::fAddTimes

Definition at line 36 of file ndt_fuser_hmt.h.

template<typename PointT>
FILE * lslgeneric::NDTFuserHMT< PointT >::fRegTimes

Definition at line 36 of file ndt_fuser_hmt.h.

template<typename PointT>
bool lslgeneric::NDTFuserHMT< PointT >::fuseIncomplete

Definition at line 31 of file ndt_fuser_hmt.h.

template<typename PointT>
std::string lslgeneric::NDTFuserHMT< PointT >::hmt_map_dir

Definition at line 34 of file ndt_fuser_hmt.h.

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

Definition at line 344 of file ndt_fuser_hmt.h.

template<typename PointT>
Eigen::Vector3d lslgeneric::NDTFuserHMT< PointT >::localMapSize [private]

Definition at line 358 of file ndt_fuser_hmt.h.

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

da map

Definition at line 27 of file ndt_fuser_hmt.h.

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

Definition at line 347 of file ndt_fuser_hmt.h.

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

Definition at line 350 of file ndt_fuser_hmt.h.

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

Definition at line 351 of file ndt_fuser_hmt.h.

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

Definition at line 352 of file ndt_fuser_hmt.h.

Definition at line 356 of file ndt_fuser_hmt.h.

Definition at line 357 of file ndt_fuser_hmt.h.

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

Definition at line 29 of file ndt_fuser_hmt.h.

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

perform a check for consistency against initial estimate

Definition at line 29 of file ndt_fuser_hmt.h.

template<typename PointT>
std::string lslgeneric::NDTFuserHMT< PointT >::prefix

Definition at line 33 of file ndt_fuser_hmt.h.

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

resolution of the map

Definition at line 346 of file ndt_fuser_hmt.h.

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

Definition at line 349 of file ndt_fuser_hmt.h.

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

Definition at line 355 of file ndt_fuser_hmt.h.

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

Definition at line 30 of file ndt_fuser_hmt.h.

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

Definition at line 25 of file ndt_fuser_hmt.h.

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

Definition at line 25 of file ndt_fuser_hmt.h.

template<typename PointT>
Eigen::Affine3d lslgeneric::NDTFuserHMT< PointT >::Todom

current pose

Definition at line 25 of file ndt_fuser_hmt.h.

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

Definition at line 349 of file ndt_fuser_hmt.h.

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

Definition at line 35 of file ndt_fuser_hmt.h.

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

Definition at line 353 of file ndt_fuser_hmt.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