This class fuses new point clouds into a common ndt map reference, keeping tack of the camera postion. More...
#include <ndt_fuser_hmt.h>
Public Member Functions | |
| double | getDoubleTime () |
| void | initialize (Eigen::Affine3d initPos, pcl::PointCloud< pcl::PointXYZ > &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< pcl::PointXYZ > &cloud) |
| bool | wasInit () |
| ~NDTFuserHMT () | |
Public Attributes | |
| bool | be2D |
| bool | beHMT |
| bool | checkConsistency |
| int | ctr |
| bool | disableRegistration |
| bool | doMultires |
| FILE * | fAddTimes |
| FILE * | fRegTimes |
| bool | fuseIncomplete |
| std::string | hmt_map_dir |
| lslgeneric::NDTMap * | 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 * | 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 | 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 24 of file ndt_fuser_hmt.h.
| lslgeneric::NDTFuserHMT::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 40 of file ndt_fuser_hmt.h.
| lslgeneric::NDTFuserHMT::~NDTFuserHMT | ( | ) | [inline] |
Definition at line 86 of file ndt_fuser_hmt.h.
| double lslgeneric::NDTFuserHMT::getDoubleTime | ( | ) | [inline] |
Definition at line 96 of file ndt_fuser_hmt.h.
| void lslgeneric::NDTFuserHMT::initialize | ( | Eigen::Affine3d | initPos, |
| pcl::PointCloud< pcl::PointXYZ > & | cloud, | ||
| bool | preLoad = false |
||
| ) |
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_hmt.cpp.
| bool lslgeneric::NDTFuserHMT::saveMap | ( | ) | [inline] |
Definition at line 111 of file ndt_fuser_hmt.h.
| void lslgeneric::NDTFuserHMT::setSensorPose | ( | Eigen::Affine3d | spose | ) | [inline] |
Definition at line 102 of file ndt_fuser_hmt.h.
| Eigen::Affine3d lslgeneric::NDTFuserHMT::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 60 of file ndt_fuser_hmt.cpp.
| bool lslgeneric::NDTFuserHMT::wasInit | ( | ) | [inline] |
Definition at line 106 of file ndt_fuser_hmt.h.
Definition at line 31 of file ndt_fuser_hmt.h.
Definition at line 31 of file ndt_fuser_hmt.h.
Definition at line 28 of file ndt_fuser_hmt.h.
Definition at line 32 of file ndt_fuser_hmt.h.
Definition at line 31 of file ndt_fuser_hmt.h.
Definition at line 31 of file ndt_fuser_hmt.h.
Definition at line 38 of file ndt_fuser_hmt.h.
Definition at line 38 of file ndt_fuser_hmt.h.
Definition at line 31 of file ndt_fuser_hmt.h.
| std::string lslgeneric::NDTFuserHMT::hmt_map_dir |
Definition at line 34 of file ndt_fuser_hmt.h.
bool lslgeneric::NDTFuserHMT::isInit [private] |
Definition at line 137 of file ndt_fuser_hmt.h.
Eigen::Vector3d lslgeneric::NDTFuserHMT::localMapSize [private] |
Definition at line 151 of file ndt_fuser_hmt.h.
da map
Definition at line 27 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::map_size [private] |
Definition at line 140 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::map_size_x [private] |
Definition at line 143 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::map_size_y [private] |
Definition at line 144 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::map_size_z [private] |
Definition at line 145 of file ndt_fuser_hmt.h.
Definition at line 149 of file ndt_fuser_hmt.h.
Definition at line 150 of file ndt_fuser_hmt.h.
Definition at line 29 of file ndt_fuser_hmt.h.
perform a check for consistency against initial estimate
Definition at line 29 of file ndt_fuser_hmt.h.
| std::string lslgeneric::NDTFuserHMT::prefix |
Definition at line 33 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::resolution [private] |
resolution of the map
Definition at line 139 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::rotation_fuse_delta [private] |
Definition at line 142 of file ndt_fuser_hmt.h.
Eigen::Affine3d lslgeneric::NDTFuserHMT::sensor_pose [private] |
Definition at line 148 of file ndt_fuser_hmt.h.
Definition at line 30 of file ndt_fuser_hmt.h.
| Eigen::Affine3d lslgeneric::NDTFuserHMT::Tlast_fuse |
Definition at line 26 of file ndt_fuser_hmt.h.
| Eigen::Affine3d lslgeneric::NDTFuserHMT::Tnow |
Definition at line 26 of file ndt_fuser_hmt.h.
| Eigen::Affine3d lslgeneric::NDTFuserHMT::Todom |
current pose
Definition at line 26 of file ndt_fuser_hmt.h.
double lslgeneric::NDTFuserHMT::translation_fuse_delta [private] |
Definition at line 142 of file ndt_fuser_hmt.h.
Definition at line 36 of file ndt_fuser_hmt.h.
bool lslgeneric::NDTFuserHMT::visualize [private] |
Definition at line 146 of file ndt_fuser_hmt.h.