#include <GainCompensator.h>
Public Member Functions | |
| void | apply (int id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, bool rgb=true) const |
| void | apply (int id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool rgb=true) const |
| void | apply (int id, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool rgb=true) const |
| void | apply (int id, cv::Mat &image, bool rgb=true) const |
| void | feed (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudA, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudB, const Transform &transformB) |
| void | feed (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudA, const pcl::IndicesPtr &indicesA, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudB, const pcl::IndicesPtr &indicesB, const Transform &transformB) |
| void | feed (const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > &clouds, const std::multimap< int, Link > &links) |
| void | feed (const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > &clouds, const std::map< int, pcl::IndicesPtr > &indices, const std::multimap< int, Link > &links) |
| void | feed (const std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > &clouds, const std::map< int, pcl::IndicesPtr > &indices, const std::multimap< int, Link > &links) |
| void | feed (const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr, pcl::IndicesPtr > > &clouds, const std::multimap< int, Link > &links) |
| GainCompensator (double maxCorrespondenceDistance=0.02, double minOverlap=0.0, double alpha=0.01, double beta=10) | |
| double | getGain (int id, double *r=0, double *g=0, double *b=0) const |
| int | getIndex (int id) const |
| virtual | ~GainCompensator () |
Private Attributes | |
| double | alpha_ |
| double | beta_ |
| cv::Mat_< double > | gains_ |
| std::map< int, int > | idToIndex_ |
| double | maxCorrespondenceDistance_ |
| double | minOverlap_ |
Works like cv::GainCompensator but with point clouds
Definition at line 44 of file GainCompensator.h.
| rtabmap::GainCompensator::GainCompensator | ( | double | maxCorrespondenceDistance = 0.02, |
| double | minOverlap = 0.0, |
||
| double | alpha = 0.01, |
||
| double | beta = 10 |
||
| ) |
Definition at line 46 of file GainCompensator.cpp.
|
virtual |
Definition at line 54 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::apply | ( | int | id, |
| pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, | ||
| bool | rgb = true |
||
| ) | const |
Definition at line 426 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::apply | ( | int | id, |
| pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, | ||
| const pcl::IndicesPtr & | indices, | ||
| bool | rgb = true |
||
| ) | const |
Definition at line 434 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::apply | ( | int | id, |
| pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr & | cloud, | ||
| const pcl::IndicesPtr & | indices, | ||
| bool | rgb = true |
||
| ) | const |
Definition at line 443 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::apply | ( | int | id, |
| cv::Mat & | image, | ||
| bool | rgb = true |
||
| ) | const |
Definition at line 453 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::feed | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloudA, |
| const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloudB, | ||
| const Transform & | transformB | ||
| ) |
Definition at line 57 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::feed | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloudA, |
| const pcl::IndicesPtr & | indicesA, | ||
| const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloudB, | ||
| const pcl::IndicesPtr & | indicesB, | ||
| const Transform & | transformB | ||
| ) |
Definition at line 70 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::feed | ( | const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & | clouds, |
| const std::multimap< int, Link > & | links | ||
| ) |
Definition at line 88 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::feed | ( | const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & | clouds, |
| const std::map< int, pcl::IndicesPtr > & | indices, | ||
| const std::multimap< int, Link > & | links | ||
| ) |
Definition at line 364 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::feed | ( | const std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > & | clouds, |
| const std::map< int, pcl::IndicesPtr > & | indices, | ||
| const std::multimap< int, Link > & | links | ||
| ) |
Definition at line 371 of file GainCompensator.cpp.
| void rtabmap::GainCompensator::feed | ( | const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr, pcl::IndicesPtr > > & | clouds, |
| const std::multimap< int, Link > & | links | ||
| ) |
Definition at line 378 of file GainCompensator.cpp.
| double rtabmap::GainCompensator::getGain | ( | int | id, |
| double * | r = 0, |
||
| double * | g = 0, |
||
| double * | b = 0 |
||
| ) | const |
Definition at line 475 of file GainCompensator.cpp.
| int rtabmap::GainCompensator::getIndex | ( | int | id | ) | const |
Definition at line 495 of file GainCompensator.cpp.
|
private |
Definition at line 101 of file GainCompensator.h.
|
private |
Definition at line 102 of file GainCompensator.h.
|
private |
Definition at line 97 of file GainCompensator.h.
|
private |
Definition at line 98 of file GainCompensator.h.
|
private |
Definition at line 99 of file GainCompensator.h.
|
private |
Definition at line 100 of file GainCompensator.h.