34 #include <pcl/search/kdtree.h> 35 #include <pcl/common/common.h> 36 #include <pcl/common/transforms.h> 37 #include <pcl/correspondence.h> 43 return double(v)*double(v);
47 maxCorrespondenceDistance_(maxCorrespondenceDistance),
48 minOverlap_(minOverlap),
58 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudA,
59 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudB,
62 std::multimap<int, Link> links;
64 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> clouds;
65 clouds.insert(std::make_pair(0, cloudA));
66 clouds.insert(std::make_pair(1, cloudB));
71 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudA,
72 const pcl::IndicesPtr & indicesA,
73 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloudB,
74 const pcl::IndicesPtr & indicesB,
77 std::multimap<int, Link> links;
79 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> clouds;
80 clouds.insert(std::make_pair(0, cloudA));
81 clouds.insert(std::make_pair(1, cloudB));
82 std::map<int, pcl::IndicesPtr> indices;
83 indices.insert(std::make_pair(0, indicesA));
84 indices.insert(std::make_pair(1, indicesB));
85 feed(clouds, indices, links);
89 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds,
90 const std::multimap<int, Link> & links)
92 std::map<int, pcl::IndicesPtr> indices;
93 feed(clouds, indices, links);
101 AABB(
const Eigen::Vector3f & center,
const Eigen::Vector3f & halfwidths)
112 if ( fabs(a.
c[0] - b.
c[0]) > (a.
r[0] + b.
r[0]) )
return false;
113 if ( fabs(a.
c[1] - b.
c[1]) > (a.
r[1] + b.
r[1]) )
return false;
114 if ( fabs(a.
c[2] - b.
c[2]) > (a.
r[2] + b.
r[2]) )
return false;
123 template<
typename Po
intT>
125 const std::map<
int,
typename pcl::PointCloud<PointT>::Ptr> & clouds,
126 const std::map<int, pcl::IndicesPtr> & indices,
127 const std::multimap<int, Link> & links,
128 float maxCorrespondenceDistance,
132 cv::Mat_<double> & gains,
133 std::map<int, int> & idToIndex)
135 UDEBUG(
"Exposure compensation...");
137 UASSERT(maxCorrespondenceDistance > 0.0
f);
138 UASSERT(indices.size() == 0 || clouds.size() == indices.size());
140 const int num_images =
static_cast<int>(clouds.size());
141 cv::Mat_<int> N(num_images, num_images); N.setTo(0);
142 cv::Mat_<double> I(num_images, num_images); I.setTo(0);
144 cv::Mat_<double> IR(num_images, num_images); IR.setTo(0);
145 cv::Mat_<double> IG(num_images, num_images); IG.setTo(0);
146 cv::Mat_<double> IB(num_images, num_images); IB.setTo(0);
150 std::vector<int> indexToId(clouds.size());
152 std::map<int, std::pair<pcl::PointXYZ, pcl::PointXYZ> > boundingBoxes;
153 for(
typename std::map<
int,
typename pcl::PointCloud<PointT>::Ptr>::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
155 idToIndex.insert(std::make_pair(iter->first, oi));
156 indexToId[oi] = iter->first;
158 Eigen::Vector4f minPt(0,0,0,0);
159 Eigen::Vector4f maxPt(0,0,0,0);
160 if(indices.empty() || indices.at(iter->first)->empty())
162 N(oi,oi) = iter->second->size();
167 N(oi,oi) = indices.at(iter->first)->size();
170 minPt[0] -= maxCorrespondenceDistance;
171 minPt[1] -= maxCorrespondenceDistance;
172 minPt[2] -= maxCorrespondenceDistance;
173 maxPt[0] += maxCorrespondenceDistance;
174 maxPt[1] += maxCorrespondenceDistance;
175 maxPt[2] += maxCorrespondenceDistance;
176 boundingBoxes.insert(std::make_pair(iter->first, std::make_pair(pcl::PointXYZ(minPt[0], minPt[1], minPt[2]), pcl::PointXYZ(maxPt[0], maxPt[1], maxPt[2]))));
180 typename pcl::search::KdTree<PointT>
kdtree;
181 int lastKdTreeId = 0;
182 for(std::multimap<int, Link>::const_iterator iter=links.begin(); iter!=links.end(); ++iter)
184 if(
uContains(idToIndex, iter->second.from()) &&
uContains(idToIndex, iter->second.to()))
186 const typename pcl::PointCloud<PointT>::Ptr & cloudFrom = clouds.at(iter->second.from());
187 const typename pcl::PointCloud<PointT>::Ptr & cloudTo = clouds.at(iter->second.to());
188 if(cloudFrom->size() && cloudTo->size())
191 std::pair<pcl::PointXYZ, pcl::PointXYZ> bbMinMaxFrom = boundingBoxes.at(iter->second.from());
192 std::pair<pcl::PointXYZ, pcl::PointXYZ> bbMinMaxTo = boundingBoxes.at(iter->second.to());
194 if(!iter->second.transform().isIdentity() && !iter->second.transform().isNull())
196 t = iter->second.transform().toEigen3f();
200 AABB bbFrom(Eigen::Vector3f((bbMinMaxFrom.second.x + bbMinMaxFrom.first.x)/2.0f, (bbMinMaxFrom.second.y + bbMinMaxFrom.first.y)/2.0f, (bbMinMaxFrom.second.z + bbMinMaxFrom.first.z)/2.0f),
201 Eigen::Vector3f((bbMinMaxFrom.second.x - bbMinMaxFrom.first.x)/2.0f, (bbMinMaxFrom.second.y - bbMinMaxFrom.first.y)/2.0f, (bbMinMaxFrom.second.z - bbMinMaxFrom.first.z)/2.0f));
202 AABB bbTo(Eigen::Vector3f((bbMinMaxTo.second.x + bbMinMaxTo.first.x)/2.0f, (bbMinMaxTo.second.y + bbMinMaxTo.first.y)/2.0f, (bbMinMaxTo.second.z + bbMinMaxTo.first.z)/2.0f),
203 Eigen::Vector3f((bbMinMaxTo.second.x - bbMinMaxTo.first.x)/2.0f, (bbMinMaxTo.second.y - bbMinMaxTo.first.y)/2.0f, (bbMinMaxTo.second.z - bbMinMaxTo.first.z)/2.0f));
208 if(lastKdTreeId <= 0 || lastKdTreeId!=iter->second.from())
211 if(indices.size() && indices.at(iter->second.from())->size())
213 kdtree.setInputCloud(cloudFrom, indices.at(iter->second.from()));
217 kdtree.setInputCloud(cloudFrom);
221 pcl::Correspondences correspondences;
222 pcl::IndicesPtr indicesTo(
new std::vector<int>);
223 std::set<int> addedFrom;
224 if(indices.size() && indices.at(iter->second.to())->size())
226 const pcl::IndicesPtr & indicesTo = indices.at(iter->second.to());
227 correspondences.resize(indicesTo->size());
229 for(
unsigned int i=0; i<indicesTo->size(); ++i)
231 std::vector<int> k_indices;
232 std::vector<float> k_sqr_distances;
233 if(kdtree.radiusSearch(
pcl::transformPoint(cloudTo->at(indicesTo->at(i)), t), maxCorrespondenceDistance, k_indices, k_sqr_distances, 1))
235 if(addedFrom.find(k_indices[0]) == addedFrom.end())
237 correspondences[oi].index_match = k_indices[0];
238 correspondences[oi].index_query = indicesTo->at(i);
239 correspondences[oi].distance = k_sqr_distances[0];
240 addedFrom.insert(k_indices[0]);
245 correspondences.resize(oi);
249 correspondences.resize(cloudTo->size());
251 for(
unsigned int i=0; i<cloudTo->size(); ++i)
253 std::vector<int> k_indices;
254 std::vector<float> k_sqr_distances;
255 if(kdtree.radiusSearch(
pcl::transformPoint(cloudTo->at(i), t), maxCorrespondenceDistance, k_indices, k_sqr_distances, 1))
257 if(addedFrom.find(k_indices[0]) == addedFrom.end())
259 correspondences[oi].index_match = k_indices[0];
260 correspondences[oi].index_query = i;
261 correspondences[oi].distance = k_sqr_distances[0];
262 addedFrom.insert(k_indices[0]);
267 correspondences.resize(oi);
270 UDEBUG(
"%d->%d: correspondences = %d", iter->second.from(), iter->second.to(), (int)correspondences.size());
271 if(correspondences.size() && (minOverlap <= 0.0 ||
272 (double(correspondences.size()) /
double(clouds.at(iter->second.from())->size()) >= minOverlap &&
273 double(correspondences.size()) /
double(clouds.at(iter->second.to())->size()) >= minOverlap)))
275 int i = idToIndex.at(iter->second.from());
276 int j = idToIndex.at(iter->second.to());
278 double Isum1 = 0, Isum2 = 0;
279 double IRsum1 = 0, IRsum2 = 0;
280 double IGsum1 = 0, IGsum2 = 0;
281 double IBsum1 = 0, IBsum2 = 0;
282 for (
unsigned int c = 0; c < correspondences.size(); ++c)
284 const PointT & pt1 = cloudFrom->at(correspondences.at(c).index_match);
285 const PointT & pt2 = cloudTo->at(correspondences.at(c).index_query);
290 IRsum1 +=
static_cast<double>(pt1.r);
291 IRsum2 +=
static_cast<double>(pt2.r);
292 IGsum1 +=
static_cast<double>(pt1.g);
293 IGsum2 +=
static_cast<double>(pt2.g);
294 IBsum1 +=
static_cast<double>(pt1.b);
295 IBsum2 +=
static_cast<double>(pt2.b);
297 N(i, j) = N(j, i) = correspondences.size();
298 I(i, j) = Isum1 / N(i, j);
299 I(j, i) = Isum2 / N(i, j);
301 IR(i, j) = IRsum1 / N(i, j);
302 IR(j, i) = IRsum2 / N(i, j);
303 IG(i, j) = IGsum1 / N(i, j);
304 IG(j, i) = IGsum2 / N(i, j);
305 IB(i, j) = IBsum1 / N(i, j);
306 IB(j, i) = IBsum2 / N(i, j);
313 cv::Mat_<double> A(num_images, num_images); A.setTo(0);
314 cv::Mat_<double> b(num_images, 1); b.setTo(0);
315 cv::Mat_<double> AR(num_images, num_images); AR.setTo(0);
316 cv::Mat_<double> AG(num_images, num_images); AG.setTo(0);
317 cv::Mat_<double> AB(num_images, num_images); AB.setTo(0);
318 for (
int i = 0; i < num_images; ++i)
320 for (
int j = 0; j < num_images; ++j)
322 b(i, 0) += beta * N(i, j);
323 A(i, i) += beta * N(i, j);
324 AR(i, i) += beta * N(i, j);
325 AG(i, i) += beta * N(i, j);
326 AB(i, i) += beta * N(i, j);
327 if (j == i)
continue;
328 A(i, i) += 2 * alpha * I(i, j) * I(i, j) * N(i, j);
329 A(i, j) -= 2 * alpha * I(i, j) * I(j, i) * N(i, j);
331 AR(i, i) += 2 * alpha * IR(i, j) * IR(i, j) * N(i, j);
332 AR(i, j) -= 2 * alpha * IR(i, j) * IR(j, i) * N(i, j);
334 AG(i, i) += 2 * alpha * IG(i, j) * IG(i, j) * N(i, j);
335 AG(i, j) -= 2 * alpha * IG(i, j) * IG(j, i) * N(i, j);
337 AB(i, i) += 2 * alpha * IB(i, j) * IB(i, j) * N(i, j);
338 AB(i, j) -= 2 * alpha * IB(i, j) * IB(j, i) * N(i, j);
342 cv::Mat_<double> gainsGray, gainsR, gainsG, gainsB;
343 cv::solve(A, b, gainsGray);
345 cv::solve(AR, b, gainsR);
346 cv::solve(AG, b, gainsG);
347 cv::solve(AB, b, gainsB);
349 gains = cv::Mat_<double>(gainsGray.rows, 4);
350 gainsGray.copyTo(gains.col(0));
351 gainsR.copyTo(gains.col(1));
352 gainsG.copyTo(gains.col(2));
353 gainsB.copyTo(gains.col(3));
357 for(
int i=0; i<gains.rows; ++i)
359 UINFO(
"Gain index=%d (id=%d) = %f (%f,%f,%f)", i, indexToId[i], gains(i, 0), gains(i, 1), gains(i, 2), gains(i, 3));
365 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds,
366 const std::map<int, pcl::IndicesPtr> & indices,
367 const std::multimap<int, Link> & links)
372 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
373 const std::map<int, pcl::IndicesPtr> & indices,
374 const std::multimap<int, Link> & links)
379 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > & cloudsIndices,
380 const std::multimap<int, Link> & links)
382 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
383 std::map<int, pcl::IndicesPtr> indices;
384 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator iter=cloudsIndices.begin(); iter!=cloudsIndices.end(); ++iter)
386 clouds.insert(std::make_pair(iter->first, iter->second.first));
387 indices.insert(std::make_pair(iter->first, iter->second.second));
392 template<
typename Po
intT>
395 typename pcl::PointCloud<PointT>::Ptr & cloud,
396 const pcl::IndicesPtr & indices,
397 const cv::Mat_<double> & gains,
400 double gainR = gains(index, rgb?1:0);
401 double gainG = gains(index, rgb?2:0);
402 double gainB = gains(index, rgb?3:0);
403 UDEBUG(
"index=%d gain=%f (%f,%f,%f)", index, gains(index, 0), gainR, gainG, gainB);
406 for(
unsigned int i=0; i<indices->size(); ++i)
408 PointT & pt = cloud->at(indices->at(i));
416 for(
unsigned int i=0; i<cloud->size(); ++i)
418 PointT & pt = cloud->at(i);
428 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
431 pcl::IndicesPtr indices(
new std::vector<int>);
432 apply(
id, cloud, indices, rgb);
436 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
437 const pcl::IndicesPtr & indices,
441 applyImpl<pcl::PointXYZRGB>(
idToIndex_.at(
id), cloud, indices,
gains_, rgb);
445 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
446 const pcl::IndicesPtr & indices,
450 applyImpl<pcl::PointXYZRGBNormal>(
idToIndex_.at(
id), cloud, indices,
gains_, rgb);
459 if(image.channels() == 1 || !rgb)
463 else if(image.channels()>=3)
465 std::vector<cv::Mat> channels;
466 cv::split(image, channels);
471 cv::merge(channels, image);
cv::Mat_< double > gains_
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
virtual ~GainCompensator()
AABB(const Eigen::Vector3f ¢er, const Eigen::Vector3f &halfwidths)
void apply(int id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, bool rgb=true) const
Some conversion functions.
GainCompensator(double maxCorrespondenceDistance=0.02, double minOverlap=0.0, double alpha=0.01, double beta=10)
double maxCorrespondenceDistance_
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::map< int, int > idToIndex_
void feedImpl(const std::map< int, typename pcl::PointCloud< PointT >::Ptr > &clouds, const std::map< int, pcl::IndicesPtr > &indices, const std::multimap< int, Link > &links, float maxCorrespondenceDistance, double minOverlap, double alpha, double beta, cv::Mat_< double > &gains, std::map< int, int > &idToIndex)
#define UASSERT_MSG(condition, msg_str)
bool uContains(const std::list< V > &list, const V &value)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
void applyImpl(int index, typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const cv::Mat_< double > &gains, bool rgb)
int getIndex(int id) const
ULogger class and convenient macros.
void feed(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudA, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudB, const Transform &transformB)
bool testAABBAABB(const AABB &a, const AABB &b)
std::string UTILITE_EXP uFormat(const char *fmt,...)
double getGain(int id, double *r=0, double *g=0, double *b=0) const