CameraThread.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "rtabmap/core/Camera.h"
32 #include "rtabmap/core/util2d.h"
33 #include "rtabmap/core/util3d.h"
37 #include "rtabmap/core/DBReader.h"
38 #include "rtabmap/core/IMUFilter.h"
40 #include <opencv2/stitching/detail/exposure_compensate.hpp>
41 #include <rtabmap/utilite/UTimer.h>
43 
44 #include <pcl/io/io.h>
45 
46 namespace rtabmap
47 {
48 
49 // ownership transferred
50 CameraThread::CameraThread(Camera * camera, const ParametersMap & parameters) :
51  _camera(camera),
52  _mirroring(false),
53  _stereoExposureCompensation(false),
54  _colorOnly(false),
55  _imageDecimation(1),
56  _stereoToDepth(false),
57  _scanFromDepth(false),
58  _scanDownsampleStep(1),
59  _scanRangeMin(0.0f),
60  _scanRangeMax(0.0f),
61  _scanVoxelSize(0.0f),
62  _scanNormalsK(0),
63  _scanNormalsRadius(0.0f),
64  _scanForceGroundNormalsUp(false),
65  _stereoDense(StereoDense::create(parameters)),
66  _distortionModel(0),
67  _bilateralFiltering(false),
68  _bilateralSigmaS(10),
69  _bilateralSigmaR(0.1),
70  _imuFilter(0)
71 {
72  UASSERT(_camera != 0);
73 }
74 
76 {
77  join(true);
78  delete _camera;
79  delete _distortionModel;
80  delete _stereoDense;
81  delete _imuFilter;
82 }
83 
84 void CameraThread::setImageRate(float imageRate)
85 {
86  if(_camera)
87  {
88  _camera->setImageRate(imageRate);
89  }
90 }
91 
92 void CameraThread::setDistortionModel(const std::string & path)
93 {
95  {
96  delete _distortionModel;
97  _distortionModel = 0;
98  }
99  if(!path.empty())
100  {
102  _distortionModel->load(path);
103  if(!_distortionModel->isValid())
104  {
105  UERROR("Loaded distortion model \"%s\" is not valid!", path.c_str());
106  delete _distortionModel;
107  _distortionModel = 0;
108  }
109  }
110 }
111 
112 void CameraThread::enableBilateralFiltering(float sigmaS, float sigmaR)
113 {
114  UASSERT(sigmaS > 0.0f && sigmaR > 0.0f);
115  _bilateralFiltering = true;
116  _bilateralSigmaS = sigmaS;
117  _bilateralSigmaR = sigmaR;
118 }
119 
120 void CameraThread::enableIMUFiltering(int filteringStrategy, const ParametersMap & parameters)
121 {
122  delete _imuFilter;
123  _imuFilter = IMUFilter::create((IMUFilter::Type)filteringStrategy, parameters);
124 }
125 
127 {
128  delete _imuFilter;
129  _imuFilter = 0;
130 }
131 
133  bool fromDepth,
134  int downsampleStep,
135  float rangeMin,
136  float rangeMax,
137  float voxelSize,
138  int normalsK,
139  int normalsRadius,
140  bool forceGroundNormalsUp)
141 {
142  setScanParameters(fromDepth, downsampleStep, rangeMin, rangeMax, voxelSize, normalsK, normalsRadius, forceGroundNormalsUp?0.8f:0.0f);
143 }
144 
146  bool fromDepth,
147  int downsampleStep, // decimation of the depth image in case the scan is from depth image
148  float rangeMin,
149  float rangeMax,
150  float voxelSize,
151  int normalsK,
152  int normalsRadius,
153  float groundNormalsUp)
154 {
155  _scanFromDepth = fromDepth;
156  _scanDownsampleStep=downsampleStep;
157  _scanRangeMin = rangeMin;
158  _scanRangeMax = rangeMax;
159  _scanVoxelSize = voxelSize;
160  _scanNormalsK = normalsK;
161  _scanNormalsRadius = normalsRadius;
162  _scanForceGroundNormalsUp = groundNormalsUp;
163 }
164 
166 {
168  _camera->resetTimer();
169 }
170 
172 {
173  UTimer totalTime;
174  CameraInfo info;
175  SensorData data = _camera->takeImage(&info);
176 
177  if(!data.imageRaw().empty() || (dynamic_cast<DBReader*>(_camera) != 0 && data.id()>0)) // intermediate nodes could not have image set
178  {
179  postUpdate(&data, &info);
180 
181  info.cameraName = _camera->getSerial();
182  info.timeTotal = totalTime.ticks();
183  this->post(new CameraEvent(data, info));
184  }
185  else if(!this->isKilled())
186  {
187  UWARN("no more images...");
188  this->kill();
189  this->post(new CameraEvent());
190  }
191 }
192 
194 {
195  if(dynamic_cast<CameraFreenect2*>(_camera) != 0)
196  {
197  int i=20;
198  while(i-->0)
199  {
200  uSleep(100);
201  if(!this->isKilled())
202  {
203  break;
204  }
205  }
206  if(this->isKilled())
207  {
208  //still in killed state, maybe a deadlock
209  UERROR("CameraFreenect2: Failed to kill normally the Freenect2 driver! The thread is locked "
210  "on waitForNewFrame() method of libfreenect2. This maybe caused by not linking on the right libusb. "
211  "Note that rtabmap should link on libusb of libfreenect2. "
212  "Tip before starting rtabmap: \"$ export LD_LIBRARY_PATH=~/libfreenect2/depends/libusb/lib:$LD_LIBRARY_PATH\"");
213  }
214 
215  }
216 }
217 
218 void CameraThread::postUpdate(SensorData * dataPtr, CameraInfo * info) const
219 {
220  UASSERT(dataPtr!=0);
221  SensorData & data = *dataPtr;
222  if(_colorOnly)
223  {
224  if(!data.depthRaw().empty())
225  {
226  data.setRGBDImage(data.imageRaw(), cv::Mat(), data.cameraModels());
227  }
228  else if(!data.rightRaw().empty())
229  {
230  data.setRGBDImage(data.imageRaw(), cv::Mat(), data.stereoCameraModel().left());
231  }
232  }
233 
234  if(_distortionModel && !data.depthRaw().empty())
235  {
236  UTimer timer;
237  if(_distortionModel->getWidth() == data.depthRaw().cols &&
238  _distortionModel->getHeight() == data.depthRaw().rows )
239  {
240  cv::Mat depth = data.depthRaw().clone();// make sure we are not modifying data in cached signatures.
241  _distortionModel->undistort(depth);
242  data.setRGBDImage(data.imageRaw(), depth, data.cameraModels());
243  }
244  else
245  {
246  UERROR("Distortion model size is %dx%d but dpeth image is %dx%d!",
248  data.depthRaw().cols, data.depthRaw().rows);
249  }
250  if(info) info->timeUndistortDepth = timer.ticks();
251  }
252 
253  if(_bilateralFiltering && !data.depthRaw().empty())
254  {
255  UTimer timer;
257  if(info) info->timeBilateralFiltering = timer.ticks();
258  }
259 
260  if(_imageDecimation>1 && !data.imageRaw().empty())
261  {
262  UDEBUG("");
263  UTimer timer;
264  if(!data.depthRaw().empty() &&
265  !(data.depthRaw().rows % _imageDecimation == 0 && data.depthRaw().cols % _imageDecimation == 0))
266  {
267  UERROR("Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! "
268  "Images won't be resized.", _imageDecimation, data.depthRaw().cols, data.depthRaw().rows);
269  }
270  else
271  {
272  cv::Mat image = util2d::decimate(data.imageRaw(), _imageDecimation);
273 
274  int depthDecimation = _imageDecimation;
275  if(data.depthOrRightRaw().rows <= image.rows || data.depthOrRightRaw().cols <= image.cols)
276  {
277  depthDecimation = 1;
278  }
279  else
280  {
281  depthDecimation = 2;
282  while(data.depthOrRightRaw().rows / depthDecimation > image.rows ||
283  data.depthOrRightRaw().cols / depthDecimation > image.cols ||
284  data.depthOrRightRaw().rows % depthDecimation != 0 ||
285  data.depthOrRightRaw().cols % depthDecimation != 0)
286  {
287  ++depthDecimation;
288  }
289  UDEBUG("depthDecimation=%d", depthDecimation);
290  }
291  cv::Mat depthOrRight = util2d::decimate(data.depthOrRightRaw(), depthDecimation);
292 
293  std::vector<CameraModel> models = data.cameraModels();
294  for(unsigned int i=0; i<models.size(); ++i)
295  {
296  if(models[i].isValidForProjection())
297  {
298  models[i] = models[i].scaled(1.0/double(_imageDecimation));
299  }
300  }
301  if(!models.empty())
302  {
303  data.setRGBDImage(image, depthOrRight, models);
304  }
305  else
306  {
307  StereoCameraModel stereoModel = data.stereoCameraModel();
308  if(stereoModel.isValidForProjection())
309  {
310  stereoModel.scale(1.0/double(_imageDecimation));
311  }
312  data.setStereoImage(image, depthOrRight, stereoModel);
313  }
314  }
315  if(info) info->timeImageDecimation = timer.ticks();
316  }
317  if(_mirroring && !data.imageRaw().empty() && data.cameraModels().size() == 1)
318  {
319  UDEBUG("");
320  UTimer timer;
321  cv::Mat tmpRgb;
322  cv::flip(data.imageRaw(), tmpRgb, 1);
323 
324  UASSERT_MSG(data.cameraModels().size() <= 1 && !data.stereoCameraModel().isValidForProjection(), "Only single RGBD cameras are supported for mirroring.");
325  CameraModel tmpModel = data.cameraModels()[0];
326  if(data.cameraModels()[0].cx())
327  {
328  tmpModel = CameraModel(
329  data.cameraModels()[0].fx(),
330  data.cameraModels()[0].fy(),
331  float(data.imageRaw().cols) - data.cameraModels()[0].cx(),
332  data.cameraModels()[0].cy(),
333  data.cameraModels()[0].localTransform(),
334  data.cameraModels()[0].Tx(),
335  data.cameraModels()[0].imageSize());
336  }
337  cv::Mat tmpDepth = data.depthOrRightRaw();
338  if(!data.depthRaw().empty())
339  {
340  cv::flip(data.depthRaw(), tmpDepth, 1);
341  }
342  data.setRGBDImage(tmpRgb, tmpDepth, tmpModel);
343  if(info) info->timeMirroring = timer.ticks();
344  }
345 
346  if(_stereoExposureCompensation && !data.imageRaw().empty() && !data.rightRaw().empty())
347  {
348 #if CV_MAJOR_VERSION < 3
349  UWARN("Stereo exposure compensation not implemented for OpenCV version under 3.");
350 #else
351  UDEBUG("");
352  UTimer timer;
353  cv::Ptr<cv::detail::ExposureCompensator> compensator = cv::detail::ExposureCompensator::createDefault(cv::detail::ExposureCompensator::GAIN);
354  std::vector<cv::Point> topLeftCorners(2, cv::Point(0,0));
355  std::vector<cv::UMat> images;
356  std::vector<cv::UMat> masks(2, cv::UMat(data.imageRaw().size(), CV_8UC1, cv::Scalar(255)));
357  images.push_back(data.imageRaw().getUMat(cv::ACCESS_READ));
358  images.push_back(data.rightRaw().getUMat(cv::ACCESS_READ));
359  compensator->feed(topLeftCorners, images, masks);
360  cv::Mat imgLeft = data.imageRaw().clone();
361  compensator->apply(0, cv::Point(0,0), imgLeft, masks[0]);
362  cv::Mat imgRight = data.rightRaw().clone();
363  compensator->apply(1, cv::Point(0,0), imgRight, masks[1]);
364  data.setStereoImage(imgLeft, imgRight, data.stereoCameraModel());
365  cv::detail::GainCompensator * gainCompensator = (cv::detail::GainCompensator*)compensator.get();
366  UDEBUG("gains = %f %f ", gainCompensator->gains()[0], gainCompensator->gains()[1]);
367  if(info) info->timeStereoExposureCompensation = timer.ticks();
368 #endif
369  }
370 
371  if(_stereoToDepth && !data.imageRaw().empty() && data.stereoCameraModel().isValidForProjection() && !data.rightRaw().empty())
372  {
373  UDEBUG("");
374  UTimer timer;
375  cv::Mat depth = util2d::depthFromDisparity(
377  data.stereoCameraModel().left().fx(),
378  data.stereoCameraModel().baseline());
379  // set Tx for stereo bundle adjustment (when used)
380  CameraModel model = CameraModel(
381  data.stereoCameraModel().left().fx(),
382  data.stereoCameraModel().left().fy(),
383  data.stereoCameraModel().left().cx(),
384  data.stereoCameraModel().left().cy(),
386  -data.stereoCameraModel().baseline()*data.stereoCameraModel().left().fx(),
387  data.stereoCameraModel().left().imageSize());
388  data.setRGBDImage(data.imageRaw(), depth, model);
389  if(info) info->timeDisparity = timer.ticks();
390  }
391  if(_scanFromDepth &&
392  data.cameraModels().size() &&
393  data.cameraModels().at(0).isValidForProjection() &&
394  !data.depthRaw().empty())
395  {
396  UDEBUG("");
397  if(data.laserScanRaw().isEmpty())
398  {
400  UTimer timer;
401  pcl::IndicesPtr validIndices(new std::vector<int>);
402  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
403  data,
407  validIndices.get());
408  float maxPoints = (data.depthRaw().rows/_scanDownsampleStep)*(data.depthRaw().cols/_scanDownsampleStep);
409  cv::Mat scan;
410  const Transform & baseToScan = data.cameraModels()[0].localTransform();
412  if(validIndices->size())
413  {
414  if(_scanVoxelSize>0.0f)
415  {
416  cloud = util3d::voxelize(cloud, validIndices, _scanVoxelSize);
417  float ratio = float(cloud->size()) / float(validIndices->size());
418  maxPoints = ratio * maxPoints;
419  }
420  else if(!cloud->is_dense)
421  {
422  pcl::PointCloud<pcl::PointXYZRGB>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGB>);
423  pcl::copyPointCloud(*cloud, *validIndices, *denseCloud);
424  cloud = denseCloud;
425  }
426 
427  if(cloud->size())
428  {
430  {
431  Eigen::Vector3f viewPoint(baseToScan.x(), baseToScan.y(), baseToScan.z());
432  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloud, _scanNormalsK, _scanNormalsRadius, viewPoint);
433  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudNormals(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
434  pcl::concatenateFields(*cloud, *normals, *cloudNormals);
435  scan = util3d::laserScanFromPointCloud(*cloudNormals, baseToScan.inverse());
436  format = LaserScan::kXYZRGBNormal;
437  }
438  else
439  {
440  scan = util3d::laserScanFromPointCloud(*cloud, baseToScan.inverse());
441  }
442  }
443  }
444  data.setLaserScan(LaserScan(scan, (int)maxPoints, _scanRangeMax, format, baseToScan));
445  if(info) info->timeScanFromDepth = timer.ticks();
446  }
447  else
448  {
449  UWARN("Option to create laser scan from depth image is enabled, but "
450  "there is already a laser scan in the captured sensor data. Scan from "
451  "depth will not be created.");
452  }
453  }
454  else if(!data.laserScanRaw().isEmpty())
455  {
456  UDEBUG("");
457  // filter the scan after registration
459  }
460 
461  // IMU filtering
462  if(_imuFilter && !data.imu().empty())
463  {
464  if(data.imu().angularVelocity()[0] == 0 &&
465  data.imu().angularVelocity()[1] == 0 &&
466  data.imu().angularVelocity()[2] == 0 &&
467  data.imu().linearAcceleration()[0] == 0 &&
468  data.imu().linearAcceleration()[1] == 0 &&
469  data.imu().linearAcceleration()[2] == 0)
470  {
471  UWARN("IMU's acc and gyr values are null! Please disable IMU filtering.");
472  }
473  else
474  {
476  data.imu().angularVelocity()[0],
477  data.imu().angularVelocity()[1],
478  data.imu().angularVelocity()[2],
479  data.imu().linearAcceleration()[0],
480  data.imu().linearAcceleration()[1],
481  data.imu().linearAcceleration()[2],
482  data.stamp());
483  double qx,qy,qz,qw;
484  _imuFilter->getOrientation(qx,qy,qz,qw);
485  data.setIMU(IMU(
486  cv::Vec4d(qx,qy,qz,qw), cv::Mat::eye(3,3,CV_64FC1),
489  data.imu().localTransform()));
490  UDEBUG("%f %f %f %f (gyro=%f %f %f, acc=%f %f %f, %fs)",
491  data.imu().orientation()[0],
492  data.imu().orientation()[1],
493  data.imu().orientation()[2],
494  data.imu().orientation()[3],
495  data.imu().angularVelocity()[0],
496  data.imu().angularVelocity()[1],
497  data.imu().angularVelocity()[2],
498  data.imu().linearAcceleration()[0],
499  data.imu().linearAcceleration()[1],
500  data.imu().linearAcceleration()[2],
501  data.stamp());
502  }
503  }
504 }
505 
506 } // namespace rtabmap
Definition: UTimer.h:46
const cv::Vec4d & orientation() const
Definition: IMU.h:52
const cv::Size & imageSize() const
Definition: CameraModel.h:119
bool empty() const
Definition: IMU.h:63
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
Definition: SensorData.cpp:337
f
const cv::Mat & linearAccelerationCovariance() const
Definition: IMU.h:59
CameraThread(Camera *camera, const ParametersMap &parameters=ParametersMap())
void resetTimer()
Definition: Camera.cpp:62
void enableBilateralFiltering(float sigmaS, float sigmaR)
void setImageRate(float imageRate)
Definition: Camera.h:67
void kill()
Definition: UThread.cpp:48
static IMUFilter * create(const ParametersMap &parameters=ParametersMap())
Definition: IMUFilter.cpp:38
cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
Definition: util2d.cpp:763
bool isEmpty() const
Definition: LaserScan.h:101
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:193
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Definition: util2d.cpp:1814
void setImageRate(float imageRate)
const LaserScan & laserScanRaw() const
Definition: SensorData.h:166
const cv::Mat & imageRaw() const
Definition: SensorData.h:164
const cv::Mat & angularVelocityCovariance() const
Definition: IMU.h:56
void post(UEvent *event, bool async=true) const
IMUFilter * _imuFilter
Definition: CameraThread.h:127
cv::Mat rightRaw() const
Definition: SensorData.h:190
virtual void mainLoopKill()
virtual std::string getSerial() const =0
#define UASSERT(condition)
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:72
float timeStereoExposureCompensation
Definition: CameraInfo.h:63
clams::DiscreteDepthDistortionModel * _distortionModel
Definition: CameraThread.h:123
const CameraModel & left() const
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
double cx() const
Definition: CameraModel.h:104
void update(double gx, double gy, double gz, double ax, double ay, double az, double stamp)
Definition: IMUFilter.cpp:72
virtual cv::Mat computeDisparity(const cv::Mat &leftImage, const cv::Mat &rightImage) const =0
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
double fy() const
Definition: CameraModel.h:103
void setScanParameters(bool fromDepth, int downsampleStep=1, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalsK=0, int normalsRadius=0.0f, float groundNormalsUp=0.0f)
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
Definition: util2d.cpp:1201
const cv::Vec3d linearAcceleration() const
Definition: IMU.h:58
static void registerCurrentThread(const std::string &name)
Definition: ULogger.cpp:218
StereoDense * _stereoDense
Definition: CameraThread.h:122
bool isKilled() const
Definition: UThread.cpp:255
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
Definition: util3d.cpp:1031
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void setStereoImage(const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &stereoCameraModel, bool clearPreviousData=true)
Definition: SensorData.cpp:270
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:165
virtual void mainLoop()
int id() const
Definition: SensorData.h:155
void setDistortionModel(const std::string &path)
std::string cameraName
Definition: CameraInfo.h:57
double stamp() const
Definition: SensorData.h:157
double cy() const
Definition: CameraModel.h:105
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
const IMU & imu() const
Definition: SensorData.h:269
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:215
const Transform & localTransform() const
Definition: IMU.h:61
#define UDEBUG(...)
double fx() const
Definition: CameraModel.h:102
virtual void mainLoopBegin()
void postUpdate(SensorData *data, CameraInfo *info=0) const
#define UERROR(...)
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
Definition: SensorData.h:216
#define UWARN(...)
float timeImageDecimation
Definition: CameraInfo.h:64
double ticks()
Definition: UTimer.cpp:117
void setIMU(const IMU &imu)
Definition: SensorData.h:268
Transform inverse() const
Definition: Transform.cpp:178
float timeBilateralFiltering
Definition: CameraInfo.h:67
void join(bool killFirst=false)
Definition: UThread.cpp:85
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
const Transform & localTransform() const
virtual void getOrientation(double &qx, double &qy, double &qz, double &qw) const =0
cv::Mat depthRaw() const
Definition: SensorData.h:189
const cv::Vec3d & angularVelocity() const
Definition: IMU.h:55
float timeUndistortDepth
Definition: CameraInfo.h:66
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap &parameters=ParametersMap())
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true, bool is2D=false, const Transform &transform=Transform())
Definition: util3d.cpp:1266


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58