#include <ndt_frame.h>
Public Member Functions | |
| void | assignPts () |
| void | clear () |
| void | computeNDT (bool estimateDI=false, bool nonMean=false) |
| pcl::PointCloud< pcl::PointXYZRGB > | getColoredPointCloud () |
| const PointT & | getKeyPointCenter (int keyPointIdx) |
| NDTFrame () | |
| NDTFrame (const NDTFrame &other) | |
| virtual | ~NDTFrame () |
Public Attributes | |
| lslgeneric::DepthCamera< PointT > | cameraParams |
| double | current_res |
| cv::Mat | depth_img |
| cv::Mat | dtors |
| lslgeneric::CellVector< PointT > | idx_prototype |
| cv::Mat | img |
| std::vector< cv::KeyPoint > | kpts |
| double | maxVar |
| lslgeneric::NDTMap< PointT > | ndt_map |
| pcl::PointCloud< PointT > | pc_kpts |
| std::vector< Eigen::Vector4d, Eigen::aligned_allocator < Eigen::Vector4d > > | pts |
| 3d points, linked to keypoints and SBA points for point-to-point matches. /pc_kpts in 4d vector | |
| size_t | supportSize |
Definition at line 70 of file ndt_frame.h.
| ndt_feature_reg::NDTFrame< PointT >::NDTFrame | ( | ) | [inline] |
Definition at line 75 of file ndt_frame.h.
| virtual ndt_feature_reg::NDTFrame< PointT >::~NDTFrame | ( | ) | [inline, virtual] |
Definition at line 79 of file ndt_frame.h.
| ndt_feature_reg::NDTFrame< PointT >::NDTFrame | ( | const NDTFrame< PointT > & | other | ) | [inline] |
Definition at line 82 of file ndt_frame.h.
| void ndt_feature_reg::NDTFrame< PointT >::assignPts | ( | ) | [inline] |
Definition at line 132 of file ndt_frame.h.
| void ndt_feature_reg::NDTFrame< PointT >::clear | ( | void | ) | [inline] |
Definition at line 98 of file ndt_frame.h.
| void ndt_feature_reg::NDTFrame< PointT >::computeNDT | ( | bool | estimateDI = false, |
| bool | nonMean = false |
||
| ) | [inline] |
Definition at line 146 of file ndt_frame.h.
| pcl::PointCloud<pcl::PointXYZRGB> ndt_feature_reg::NDTFrame< PointT >::getColoredPointCloud | ( | ) | [inline] |
Definition at line 207 of file ndt_frame.h.
| const PointT& ndt_feature_reg::NDTFrame< PointT >::getKeyPointCenter | ( | int | keyPointIdx | ) | [inline] |
Definition at line 125 of file ndt_frame.h.
| lslgeneric::DepthCamera<PointT> ndt_feature_reg::NDTFrame< PointT >::cameraParams |
Definition at line 116 of file ndt_frame.h.
| double ndt_feature_reg::NDTFrame< PointT >::current_res |
Definition at line 115 of file ndt_frame.h.
| cv::Mat ndt_feature_reg::NDTFrame< PointT >::depth_img |
Definition at line 112 of file ndt_frame.h.
| cv::Mat ndt_feature_reg::NDTFrame< PointT >::dtors |
Definition at line 278 of file ndt_frame.h.
| lslgeneric::CellVector<PointT> ndt_feature_reg::NDTFrame< PointT >::idx_prototype |
Definition at line 122 of file ndt_frame.h.
| cv::Mat ndt_feature_reg::NDTFrame< PointT >::img |
Definition at line 111 of file ndt_frame.h.
| std::vector<cv::KeyPoint> ndt_feature_reg::NDTFrame< PointT >::kpts |
Definition at line 117 of file ndt_frame.h.
| double ndt_feature_reg::NDTFrame< PointT >::maxVar |
Definition at line 114 of file ndt_frame.h.
| lslgeneric::NDTMap<PointT> ndt_feature_reg::NDTFrame< PointT >::ndt_map |
Definition at line 123 of file ndt_frame.h.
| pcl::PointCloud<PointT> ndt_feature_reg::NDTFrame< PointT >::pc_kpts |
Definition at line 118 of file ndt_frame.h.
| std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > ndt_feature_reg::NDTFrame< PointT >::pts |
3d points, linked to keypoints and SBA points for point-to-point matches. /pc_kpts in 4d vector
Definition at line 120 of file ndt_frame.h.
| size_t ndt_feature_reg::NDTFrame< PointT >::supportSize |
Definition at line 113 of file ndt_frame.h.