28 #ifndef CORELIB_SRC_GAINCOMPENSATOR_H_
29 #define CORELIB_SRC_GAINCOMPENSATOR_H_
31 #include "rtabmap/core/rtabmap_core_export.h"
33 #include <pcl/point_cloud.h>
34 #include <pcl/point_types.h>
35 #include <pcl/pcl_base.h>
36 #include <opencv2/opencv.hpp>
46 GainCompensator(
double maxCorrespondenceDistance = 0.02,
double minOverlap = 0.0,
double alpha = 0.01,
double beta = 10);
50 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudA,
51 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudB,
54 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudA,
55 const pcl::IndicesPtr & indicesA,
56 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudB,
57 const pcl::IndicesPtr & indicesB,
60 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds,
61 const std::multimap<int, Link> & links);
63 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds,
64 const std::map<int, pcl::IndicesPtr> &
indices,
65 const std::multimap<int, Link> & links);
67 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
68 const std::map<int, pcl::IndicesPtr> &
indices,
69 const std::multimap<int, Link> & links);
71 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > & clouds,
72 const std::multimap<int, Link> & links);
76 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
77 bool rgb =
true)
const;
80 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
81 const pcl::IndicesPtr &
indices,
82 bool rgb =
true)
const;
85 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
86 const pcl::IndicesPtr &
indices,
87 bool rgb =
true)
const;
91 bool rgb =
true)
const;
93 double getGain(
int id,
double * r=0,
double *
g=0,
double *
b=0)
const;
94 int getIndex(
int id)
const;