This class fuses new point clouds into a common ndt map reference, keeping tack of the camera postion. More...
#include <ndt_fuser.h>
Public Member Functions | |
double | getDoubleTime () |
void | initialize (Eigen::Affine3d initPos, pcl::PointCloud< pcl::PointXYZ > &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< pcl::PointXYZ > &cloud) |
bool | wasInit () |
~NDTFuser () | |
Public Attributes | |
bool | be2D |
bool | checkConsistency |
lslgeneric::NDTMap * | 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 * | viewer |
Private Attributes | |
bool | isInit |
double | map_size |
double | map_size_x |
double | map_size_y |
double | map_size_z |
lslgeneric::NDTMatcherD2D | matcher |
lslgeneric::NDTMatcherD2D_2D | matcher2D |
double | resolution |
resolution of the map | |
double | rotation_fuse_delta |
Eigen::Affine3d | sensor_pose |
double | translation_fuse_delta |
bool | visualize |
This class fuses new point clouds into a common ndt map reference, keeping tack of the camera postion.
Definition at line 21 of file ndt_fuser.h.
lslgeneric::NDTFuser::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 32 of file ndt_fuser.h.
lslgeneric::NDTFuser::~NDTFuser | ( | ) | [inline] |
Definition at line 54 of file ndt_fuser.h.
double lslgeneric::NDTFuser::getDoubleTime | ( | ) | [inline] |
Definition at line 62 of file ndt_fuser.h.
void lslgeneric::NDTFuser::initialize | ( | Eigen::Affine3d | initPos, |
pcl::PointCloud< pcl::PointXYZ > & | cloud | ||
) |
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 4 of file ndt_fuser.cpp.
void lslgeneric::NDTFuser::setSensorPose | ( | Eigen::Affine3d | spose | ) | [inline] |
Definition at line 68 of file ndt_fuser.h.
Eigen::Affine3d lslgeneric::NDTFuser::update | ( | Eigen::Affine3d | Tmotion, |
pcl::PointCloud< pcl::PointXYZ > & | cloud | ||
) |
Set the cloud to sensor frame with respect to base
Create local map
Definition at line 24 of file ndt_fuser.cpp.
bool lslgeneric::NDTFuser::wasInit | ( | ) | [inline] |
Definition at line 72 of file ndt_fuser.h.
Definition at line 28 of file ndt_fuser.h.
Definition at line 25 of file ndt_fuser.h.
bool lslgeneric::NDTFuser::isInit [private] |
Definition at line 88 of file ndt_fuser.h.
da map
Definition at line 24 of file ndt_fuser.h.
double lslgeneric::NDTFuser::map_size [private] |
Definition at line 91 of file ndt_fuser.h.
double lslgeneric::NDTFuser::map_size_x [private] |
Definition at line 94 of file ndt_fuser.h.
double lslgeneric::NDTFuser::map_size_y [private] |
Definition at line 95 of file ndt_fuser.h.
double lslgeneric::NDTFuser::map_size_z [private] |
Definition at line 96 of file ndt_fuser.h.
Definition at line 100 of file ndt_fuser.h.
Definition at line 101 of file ndt_fuser.h.
Definition at line 26 of file ndt_fuser.h.
perform a check for consistency against initial estimate
Definition at line 26 of file ndt_fuser.h.
double lslgeneric::NDTFuser::resolution [private] |
resolution of the map
Definition at line 90 of file ndt_fuser.h.
double lslgeneric::NDTFuser::rotation_fuse_delta [private] |
Definition at line 93 of file ndt_fuser.h.
Eigen::Affine3d lslgeneric::NDTFuser::sensor_pose [private] |
Definition at line 99 of file ndt_fuser.h.
Definition at line 27 of file ndt_fuser.h.
Eigen::Affine3d lslgeneric::NDTFuser::Tlast_fuse |
current pose
Definition at line 23 of file ndt_fuser.h.
Eigen::Affine3d lslgeneric::NDTFuser::Tnow |
Definition at line 23 of file ndt_fuser.h.
double lslgeneric::NDTFuser::translation_fuse_delta [private] |
Definition at line 93 of file ndt_fuser.h.
Definition at line 30 of file ndt_fuser.h.
bool lslgeneric::NDTFuser::visualize [private] |
Definition at line 97 of file ndt_fuser.h.