#include <ndt_map_matcher_d2d_2d.h>
Public Member Functions | |
NDTMapMatcherD2D_2D (double map_resolution, lslgeneric::NDTMap< PointT > &nd_map, double miniz=0.0, double maxiz=0.0) | |
void | setSensorPose (Eigen::Affine3d spose) |
bool | update (Eigen::Affine3d Tinit, pcl::PointCloud< PointT > &cloud) |
bool | updateNoFilt (Eigen::Affine3d &Tinit, pcl::PointCloud< PointT > &cloud) |
Public Attributes | |
lslgeneric::NDTMap< PointT > | map |
da map | |
Private Attributes | |
bool | isInit |
double | max_z |
values larger than this are removed | |
double | min_z |
values less than this are removed | |
double | resolution |
resolution of the map | |
Eigen::Affine3d | sensor_pose |
Definition at line 72 of file ndt_map_matcher_d2d_2d.h.
lslgeneric::NDTMapMatcherD2D_2D< PointT >::NDTMapMatcherD2D_2D | ( | double | map_resolution, |
lslgeneric::NDTMap< PointT > & | nd_map, | ||
double | miniz = 0.0 , |
||
double | maxiz = 0.0 |
||
) | [inline] |
Constructor
map_resolution | the desired map resolution of the map that is used for localization (can be equal or lower than given one) |
&nd_map | Map used for localization |
miniz | The minimum accepted z-value (components lower than this will be disregarded) |
maxiz | The maximum accepted z-value |
First, lets make our target map match the given map This is done because we want (possibly) lower resolution target map
Definition at line 83 of file ndt_map_matcher_d2d_2d.h.
void lslgeneric::NDTMapMatcherD2D_2D< PointT >::setSensorPose | ( | Eigen::Affine3d | spose | ) | [inline] |
Set sensor pose with respect to base The localization is done in base coordinates!
Definition at line 128 of file ndt_map_matcher_d2d_2d.h.
bool lslgeneric::NDTMapMatcherD2D_2D< PointT >::update | ( | Eigen::Affine3d | Tinit, |
pcl::PointCloud< PointT > & | cloud | ||
) | [inline] |
Update function NOTE: this function will transform the cloud to base coordinates and does the min-max filtering! Tinit is the global pose expressed as Eigen::Affine3d The result is saved to Tinit!
Set the cloud to sensor frame with respect to base
Min max filter
Create local map
Definition at line 138 of file ndt_map_matcher_d2d_2d.h.
bool lslgeneric::NDTMapMatcherD2D_2D< PointT >::updateNoFilt | ( | Eigen::Affine3d & | Tinit, |
pcl::PointCloud< PointT > & | cloud | ||
) | [inline] |
The same as update, but assumes that the scan already is in the base frame and the filtration has been done
Create local map
Definition at line 164 of file ndt_map_matcher_d2d_2d.h.
bool lslgeneric::NDTMapMatcherD2D_2D< PointT >::isInit [private] |
Definition at line 176 of file ndt_map_matcher_d2d_2d.h.
lslgeneric::NDTMap<PointT> lslgeneric::NDTMapMatcherD2D_2D< PointT >::map |
da map
Definition at line 74 of file ndt_map_matcher_d2d_2d.h.
double lslgeneric::NDTMapMatcherD2D_2D< PointT >::max_z [private] |
values larger than this are removed
Definition at line 180 of file ndt_map_matcher_d2d_2d.h.
double lslgeneric::NDTMapMatcherD2D_2D< PointT >::min_z [private] |
values less than this are removed
Definition at line 179 of file ndt_map_matcher_d2d_2d.h.
double lslgeneric::NDTMapMatcherD2D_2D< PointT >::resolution [private] |
resolution of the map
Definition at line 178 of file ndt_map_matcher_d2d_2d.h.
Eigen::Affine3d lslgeneric::NDTMapMatcherD2D_2D< PointT >::sensor_pose [private] |
Definition at line 182 of file ndt_map_matcher_d2d_2d.h.