Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef FRAME_PROJECTOR_H
00031 #define FRAME_PROJECTOR_H
00032
00033 #include <pcl/point_cloud.h>
00034 #include <pcl/point_types.h>
00035 #include <opencv2/core/core.hpp>
00036 #include <rtabmap/core/CameraModel.h>
00037 #include "rtabmap/core/RtabmapExp.h"
00038
00039 #define MAX_MULT 1.3
00040 #define MIN_MULT 0.7
00041
00042 namespace clams
00043 {
00044
00048 class ProjectivePoint
00049 {
00050 public:
00051 ProjectivePoint() :
00052 u_(0),
00053 v_(0),
00054 z_(0.0f) {}
00055
00056 int u_;
00057 int v_;
00058 float z_;
00059 };
00060
00063 class RTABMAP_EXP FrameProjector
00064 {
00065 public:
00066
00067 typedef std::vector< std::vector< std::vector<double> > > RangeIndex;
00068
00069 FrameProjector(const rtabmap::CameraModel & model);
00070
00071 RangeIndex cloudToRangeIndex(const pcl::PointCloud<pcl::PointXYZ>::Ptr & pcd) const;
00075 cv::Mat estimateMapDepth(
00076 const pcl::PointCloud<pcl::PointXYZ>::Ptr & map,
00077 const rtabmap::Transform & transform,
00078 const cv::Mat & measurement,
00079 double coneRadius = 0.02,
00080 double coneStdevThresh = 0.03) const;
00081
00082 pcl::PointXYZ project(const ProjectivePoint& ppt) const;
00083 ProjectivePoint reproject(const pcl::PointXYZ& pt) const;
00084
00085 protected:
00086 bool coneFit(const cv::Size& imageSize, const RangeIndex& rindex,
00087 int uc, int vc, double radius, double measurement_depth,
00088 double* mean, double* stdev) const;
00089
00090 private:
00091 rtabmap::CameraModel model_;
00092 };
00093
00094 }
00095
00096 #endif // FRAME_PROJECTOR_H