#include <depth_camera.h>
Public Member Functions | |
| size_t | computeParamsAtIndex (const cv::Mat &depthImg, cv::KeyPoint &keyPointCenter, size_t &support_size, Eigen::Vector3d &mean, Eigen::Matrix3d &cov) |
| size_t | computePointsAtIndex (const cv::Mat &depthImg, cv::KeyPoint &keyPointCenter, size_t &support_size, pcl::PointCloud< PointT > &pc, PointT ¢er) |
| size_t | convertDepthImageToPointCloud (const cv::Mat &depthImg, pcl::PointCloud< PointT > &pc) |
| DepthCamera () | |
| DepthCamera (double &_fx, double &_fy, double &_cx, double &_cy, std::vector< double > &_distances, double _ds, bool _isFloatImg=false) | |
| DepthCamera (const DepthCamera &other) | |
| void | setLookupTable (cv::Mat lookup) |
| void | setupDepthPointCloudLookUpTable (const cv::Size &size) |
Public Attributes | |
| double | cx |
| double | cy |
| std::vector< double > | dist |
| double | ds |
| double | fx |
| double | fy |
| bool | isFloatImg |
| double | scale_ |
Private Member Functions | |
| cv::Mat | getCameraMatrix (double fx, double fy, double cx, double cy) |
| cv::Mat | getDistVector (double d0, double d1, double d2, double d3, double d4) |
Private Attributes | |
| cv::Mat | _camMat |
| cv::Mat | _dist |
| cv::Mat | _lookupTable |
Definition at line 46 of file depth_camera.h.
| lslgeneric::DepthCamera< PointT >::DepthCamera | ( | ) | [inline] |
Definition at line 81 of file depth_camera.h.
| lslgeneric::DepthCamera< PointT >::DepthCamera | ( | double & | _fx, |
| double & | _fy, | ||
| double & | _cx, | ||
| double & | _cy, | ||
| std::vector< double > & | _distances, | ||
| double | _ds, | ||
| bool | _isFloatImg = false |
||
| ) | [inline] |
Definition at line 82 of file depth_camera.h.
| lslgeneric::DepthCamera< PointT >::DepthCamera | ( | const DepthCamera< PointT > & | other | ) | [inline] |
Definition at line 89 of file depth_camera.h.
| size_t lslgeneric::DepthCamera< PointT >::computeParamsAtIndex | ( | const cv::Mat & | depthImg, |
| cv::KeyPoint & | keyPointCenter, | ||
| size_t & | support_size, | ||
| Eigen::Vector3d & | mean, | ||
| Eigen::Matrix3d & | cov | ||
| ) | [inline] |
Definition at line 345 of file depth_camera.h.
| size_t lslgeneric::DepthCamera< PointT >::computePointsAtIndex | ( | const cv::Mat & | depthImg, |
| cv::KeyPoint & | keyPointCenter, | ||
| size_t & | support_size, | ||
| pcl::PointCloud< PointT > & | pc, | ||
| PointT & | center | ||
| ) | [inline] |
Definition at line 227 of file depth_camera.h.
| size_t lslgeneric::DepthCamera< PointT >::convertDepthImageToPointCloud | ( | const cv::Mat & | depthImg, |
| pcl::PointCloud< PointT > & | pc | ||
| ) | [inline] |
Definition at line 147 of file depth_camera.h.
| cv::Mat lslgeneric::DepthCamera< PointT >::getCameraMatrix | ( | double | fx, |
| double | fy, | ||
| double | cx, | ||
| double | cy | ||
| ) | [inline, private] |
Definition at line 52 of file depth_camera.h.
| cv::Mat lslgeneric::DepthCamera< PointT >::getDistVector | ( | double | d0, |
| double | d1, | ||
| double | d2, | ||
| double | d3, | ||
| double | d4 | ||
| ) | [inline, private] |
Definition at line 63 of file depth_camera.h.
| void lslgeneric::DepthCamera< PointT >::setLookupTable | ( | cv::Mat | lookup | ) | [inline] |
Definition at line 103 of file depth_camera.h.
| void lslgeneric::DepthCamera< PointT >::setupDepthPointCloudLookUpTable | ( | const cv::Size & | size | ) | [inline] |
Definition at line 108 of file depth_camera.h.
cv::Mat lslgeneric::DepthCamera< PointT >::_camMat [private] |
Definition at line 49 of file depth_camera.h.
cv::Mat lslgeneric::DepthCamera< PointT >::_dist [private] |
Definition at line 49 of file depth_camera.h.
cv::Mat lslgeneric::DepthCamera< PointT >::_lookupTable [private] |
Definition at line 50 of file depth_camera.h.
| double lslgeneric::DepthCamera< PointT >::cx |
Definition at line 77 of file depth_camera.h.
| double lslgeneric::DepthCamera< PointT >::cy |
Definition at line 77 of file depth_camera.h.
| std::vector<double> lslgeneric::DepthCamera< PointT >::dist |
Definition at line 78 of file depth_camera.h.
| double lslgeneric::DepthCamera< PointT >::ds |
Definition at line 77 of file depth_camera.h.
| double lslgeneric::DepthCamera< PointT >::fx |
Definition at line 77 of file depth_camera.h.
| double lslgeneric::DepthCamera< PointT >::fy |
Definition at line 77 of file depth_camera.h.
| bool lslgeneric::DepthCamera< PointT >::isFloatImg |
Definition at line 79 of file depth_camera.h.
| double lslgeneric::DepthCamera< PointT >::scale_ |
Definition at line 77 of file depth_camera.h.