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 #ifndef CORELIB_SRC_GAINCOMPENSATOR_H_
00029 #define CORELIB_SRC_GAINCOMPENSATOR_H_
00030
00031 #include "rtabmap/core/RtabmapExp.h"
00032
00033 #include <pcl/point_cloud.h>
00034 #include <pcl/point_types.h>
00035 #include <pcl/pcl_base.h>
00036 #include <opencv2/opencv.hpp>
00037 #include <rtabmap/core/Link.h>
00038
00039 namespace rtabmap {
00040
00044 class RTABMAP_EXP GainCompensator {
00045 public:
00046 GainCompensator(double maxCorrespondenceDistance = 0.02, double minOverlap = 0.0, double alpha = 0.01, double beta = 10);
00047 virtual ~GainCompensator();
00048
00049 void feed(
00050 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudA,
00051 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudB,
00052 const Transform & transformB);
00053 void feed(
00054 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudA,
00055 const pcl::IndicesPtr & indicesA,
00056 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudB,
00057 const pcl::IndicesPtr & indicesB,
00058 const Transform & transformB);
00059 void feed(
00060 const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds,
00061 const std::multimap<int, Link> & links);
00062 void feed(
00063 const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds,
00064 const std::map<int, pcl::IndicesPtr> & indices,
00065 const std::multimap<int, Link> & links);
00066 void feed(
00067 const std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
00068 const std::map<int, pcl::IndicesPtr> & indices,
00069 const std::multimap<int, Link> & links);
00070 void feed(
00071 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > & clouds,
00072 const std::multimap<int, Link> & links);
00073
00074 void apply(
00075 int id,
00076 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00077 bool rgb = true) const;
00078 void apply(
00079 int id,
00080 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00081 const pcl::IndicesPtr & indices,
00082 bool rgb = true) const;
00083 void apply(
00084 int id,
00085 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00086 const pcl::IndicesPtr & indices,
00087 bool rgb = true) const;
00088 void apply(
00089 int id,
00090 cv::Mat & image,
00091 bool rgb = true) const;
00092
00093 double getGain(int id, double * r=0, double * g=0, double * b=0) const;
00094 int getIndex(int id) const;
00095
00096 private:
00097 cv::Mat_<double> gains_;
00098 std::map<int, int> idToIndex_;
00099 double maxCorrespondenceDistance_;
00100 double minOverlap_;
00101 double alpha_;
00102 double beta_;
00103
00104 };
00105
00106 }
00107
00108 #endif