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  _odomSensor(0),
53  _odomAsGt(false),
54  _poseTimeOffset(0.0),
55  _poseScaleFactor(1.0f),
56  _mirroring(false),
57  _stereoExposureCompensation(false),
58  _colorOnly(false),
59  _imageDecimation(1),
60  _stereoToDepth(false),
61  _scanFromDepth(false),
62  _scanDownsampleStep(1),
63  _scanRangeMin(0.0f),
64  _scanRangeMax(0.0f),
65  _scanVoxelSize(0.0f),
66  _scanNormalsK(0),
67  _scanNormalsRadius(0.0f),
68  _scanForceGroundNormalsUp(false),
69  _stereoDense(StereoDense::create(parameters)),
70  _distortionModel(0),
71  _bilateralFiltering(false),
72  _bilateralSigmaS(10),
73  _bilateralSigmaR(0.1),
74  _imuFilter(0),
75  _imuBaseFrameConversion(false)
76 {
77  UASSERT(_camera != 0);
78 }
79 
80 // ownership transferred
82  Camera * camera,
84  const Transform & extrinsics,
85  double poseTimeOffset,
86  float poseScaleFactor,
87  bool odomAsGt,
88  const ParametersMap & parameters) :
89  _camera(camera),
90  _odomSensor(odomSensor),
91  _extrinsicsOdomToCamera(extrinsics * CameraModel::opticalRotation()),
92  _odomAsGt(odomAsGt),
93  _poseTimeOffset(poseTimeOffset),
94  _poseScaleFactor(poseScaleFactor),
102  _scanRangeMin(0.0f),
103  _scanRangeMax(0.0f),
104  _scanVoxelSize(0.0f),
105  _scanNormalsK(0),
106  _scanNormalsRadius(0.0f),
108  _stereoDense(StereoDense::create(parameters)),
109  _distortionModel(0),
111  _bilateralSigmaS(10),
112  _bilateralSigmaR(0.1),
113  _imuFilter(0),
115 {
117  UDEBUG("_extrinsicsOdomToCamera=%s", _extrinsicsOdomToCamera.prettyPrint().c_str());
118  UDEBUG("_poseTimeOffset =%f", _poseTimeOffset);
119  UDEBUG("_poseScaleFactor =%f", _poseScaleFactor);
120  UDEBUG("_odomAsGt =%s", _odomAsGt?"true":"false");
121 }
122 
123 // ownership transferred
125  Camera * camera,
126  bool odomAsGt,
127  const ParametersMap & parameters) :
128  _camera(camera),
129  _odomSensor(0),
130  _odomAsGt(odomAsGt),
131  _poseTimeOffset(0.0),
132  _poseScaleFactor(1.0f),
133  _mirroring(false),
135  _colorOnly(false),
136  _imageDecimation(1),
140  _scanRangeMin(0.0f),
141  _scanRangeMax(0.0f),
142  _scanVoxelSize(0.0f),
143  _scanNormalsK(0),
144  _scanNormalsRadius(0.0f),
146  _stereoDense(StereoDense::create(parameters)),
147  _distortionModel(0),
149  _bilateralSigmaS(10),
150  _bilateralSigmaR(0.1),
151  _imuFilter(0),
153 {
154  UASSERT(_camera != 0);
155  UDEBUG("_odomAsGt =%s", _odomAsGt?"true":"false");
156 }
157 
159 {
160  join(true);
161  delete _camera;
162  delete _odomSensor;
163  delete _distortionModel;
164  delete _stereoDense;
165  delete _imuFilter;
166 }
167 
168 void CameraThread::setImageRate(float imageRate)
169 {
170  if(_camera)
171  {
172  _camera->setImageRate(imageRate);
173  }
174 }
175 
176 void CameraThread::setDistortionModel(const std::string & path)
177 {
178  if(_distortionModel)
179  {
180  delete _distortionModel;
181  _distortionModel = 0;
182  }
183  if(!path.empty())
184  {
186  _distortionModel->load(path);
187  if(!_distortionModel->isValid())
188  {
189  UERROR("Loaded distortion model \"%s\" is not valid!", path.c_str());
190  delete _distortionModel;
191  _distortionModel = 0;
192  }
193  }
194 }
195 
196 void CameraThread::enableBilateralFiltering(float sigmaS, float sigmaR)
197 {
198  UASSERT(sigmaS > 0.0f && sigmaR > 0.0f);
199  _bilateralFiltering = true;
200  _bilateralSigmaS = sigmaS;
201  _bilateralSigmaR = sigmaR;
202 }
203 
204 void CameraThread::enableIMUFiltering(int filteringStrategy, const ParametersMap & parameters, bool baseFrameConversion)
205 {
206  delete _imuFilter;
207  _imuFilter = IMUFilter::create((IMUFilter::Type)filteringStrategy, parameters);
208  _imuBaseFrameConversion = baseFrameConversion;
209 }
210 
212 {
213  delete _imuFilter;
214  _imuFilter = 0;
215 }
216 
218  bool fromDepth,
219  int downsampleStep,
220  float rangeMin,
221  float rangeMax,
222  float voxelSize,
223  int normalsK,
224  int normalsRadius,
225  bool forceGroundNormalsUp)
226 {
227  setScanParameters(fromDepth, downsampleStep, rangeMin, rangeMax, voxelSize, normalsK, normalsRadius, forceGroundNormalsUp?0.8f:0.0f);
228 }
229 
231  bool fromDepth,
232  int downsampleStep, // decimation of the depth image in case the scan is from depth image
233  float rangeMin,
234  float rangeMax,
235  float voxelSize,
236  int normalsK,
237  int normalsRadius,
238  float groundNormalsUp)
239 {
240  _scanFromDepth = fromDepth;
241  _scanDownsampleStep=downsampleStep;
242  _scanRangeMin = rangeMin;
243  _scanRangeMax = rangeMax;
244  _scanVoxelSize = voxelSize;
245  _scanNormalsK = normalsK;
246  _scanNormalsRadius = normalsRadius;
247  _scanForceGroundNormalsUp = groundNormalsUp;
248 }
249 
251 {
253 }
254 
256 {
258  _camera->resetTimer();
259 }
260 
262 {
263  UTimer totalTime;
264  CameraInfo info;
265  SensorData data = _camera->takeImage(&info);
266 
267  if(_odomSensor)
268  {
269  Transform pose;
270  Transform poseToLeftCam;
271  cv::Mat covariance;
272  if(_odomSensor->getPose(data.stamp()+_poseTimeOffset, pose, covariance))
273  {
274  info.odomPose = pose;
275  info.odomCovariance = covariance;
276  if(_poseScaleFactor>0 && _poseScaleFactor!=1.0f)
277  {
278  info.odomPose.x() *= _poseScaleFactor;
279  info.odomPose.y() *= _poseScaleFactor;
280  info.odomPose.z() *= _poseScaleFactor;
281  }
282  // Adjust local transform of the camera based on the pose frame
283  if(!data.cameraModels().empty())
284  {
285  UASSERT(data.cameraModels().size()==1);
286  CameraModel model = data.cameraModels()[0];
287  model.setLocalTransform(_extrinsicsOdomToCamera);
288  data.setCameraModel(model);
289  }
290  else if(!data.stereoCameraModels().empty())
291  {
292  UASSERT(data.stereoCameraModels().size()==1);
294  model.setLocalTransform(_extrinsicsOdomToCamera);
295  data.setStereoCameraModel(model);
296  }
297  }
298  else
299  {
300  UWARN("Could not get pose at stamp %f", data.stamp());
301  }
302  }
303 
304  if(_odomAsGt && !info.odomPose.isNull())
305  {
306  data.setGroundTruth(info.odomPose);
307  info.odomPose.setNull();
308  }
309 
310  if(!data.imageRaw().empty() || !data.laserScanRaw().empty() || (dynamic_cast<DBReader*>(_camera) != 0 && data.id()>0)) // intermediate nodes could not have image set
311  {
312  postUpdate(&data, &info);
313  info.cameraName = _camera->getSerial();
314  info.timeTotal = totalTime.ticks();
315  this->post(new CameraEvent(data, info));
316  }
317  else if(!this->isKilled())
318  {
319  UWARN("no more images...");
320  this->kill();
321  this->post(new CameraEvent());
322  }
323 }
324 
326 {
327  if(dynamic_cast<CameraFreenect2*>(_camera) != 0)
328  {
329  int i=20;
330  while(i-->0)
331  {
332  uSleep(100);
333  if(!this->isKilled())
334  {
335  break;
336  }
337  }
338  if(this->isKilled())
339  {
340  //still in killed state, maybe a deadlock
341  UERROR("CameraFreenect2: Failed to kill normally the Freenect2 driver! The thread is locked "
342  "on waitForNewFrame() method of libfreenect2. This maybe caused by not linking on the right libusb. "
343  "Note that rtabmap should link on libusb of libfreenect2. "
344  "Tip before starting rtabmap: \"$ export LD_LIBRARY_PATH=~/libfreenect2/depends/libusb/lib:$LD_LIBRARY_PATH\"");
345  }
346 
347  }
348 }
349 
350 void CameraThread::postUpdate(SensorData * dataPtr, CameraInfo * info) const
351 {
352  UASSERT(dataPtr!=0);
353  SensorData & data = *dataPtr;
354  if(_colorOnly)
355  {
356  if(!data.depthRaw().empty())
357  {
358  data.setRGBDImage(data.imageRaw(), cv::Mat(), data.cameraModels());
359  }
360  else if(!data.rightRaw().empty())
361  {
362  std::vector<CameraModel> models;
363  for(size_t i=0; i<data.stereoCameraModels().size(); ++i)
364  {
365  models.push_back(data.stereoCameraModels()[i].left());
366  }
367  data.setRGBDImage(data.imageRaw(), cv::Mat(), models);
368  }
369  }
370 
371  if(_distortionModel && !data.depthRaw().empty())
372  {
373  UTimer timer;
374  if(_distortionModel->getWidth() >= data.depthRaw().cols &&
375  _distortionModel->getHeight() >= data.depthRaw().rows &&
376  _distortionModel->getWidth() % data.depthRaw().cols == 0 &&
377  _distortionModel->getHeight() % data.depthRaw().rows == 0)
378  {
379  cv::Mat depth = data.depthRaw().clone();// make sure we are not modifying data in cached signatures.
380  _distortionModel->undistort(depth);
381  data.setRGBDImage(data.imageRaw(), depth, data.cameraModels());
382  }
383  else
384  {
385  UERROR("Distortion model size is %dx%d but depth image is %dx%d!",
387  data.depthRaw().cols, data.depthRaw().rows);
388  }
389  if(info) info->timeUndistortDepth = timer.ticks();
390  }
391 
392  if(_bilateralFiltering && !data.depthRaw().empty())
393  {
394  UTimer timer;
396  if(info) info->timeBilateralFiltering = timer.ticks();
397  }
398 
399  if(_imageDecimation>1 && !data.imageRaw().empty())
400  {
401  UDEBUG("");
402  UTimer timer;
403  if(!data.depthRaw().empty() &&
404  !(data.depthRaw().rows % _imageDecimation == 0 && data.depthRaw().cols % _imageDecimation == 0))
405  {
406  UERROR("Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! "
407  "Images won't be resized.", _imageDecimation, data.depthRaw().cols, data.depthRaw().rows);
408  }
409  else
410  {
411  cv::Mat image = util2d::decimate(data.imageRaw(), _imageDecimation);
412 
413  int depthDecimation = _imageDecimation;
414  if(data.depthOrRightRaw().rows <= image.rows || data.depthOrRightRaw().cols <= image.cols)
415  {
416  depthDecimation = 1;
417  }
418  else
419  {
420  depthDecimation = 2;
421  while(data.depthOrRightRaw().rows / depthDecimation > image.rows ||
422  data.depthOrRightRaw().cols / depthDecimation > image.cols ||
423  data.depthOrRightRaw().rows % depthDecimation != 0 ||
424  data.depthOrRightRaw().cols % depthDecimation != 0)
425  {
426  ++depthDecimation;
427  }
428  UDEBUG("depthDecimation=%d", depthDecimation);
429  }
430  cv::Mat depthOrRight = util2d::decimate(data.depthOrRightRaw(), depthDecimation);
431 
432  std::vector<CameraModel> models = data.cameraModels();
433  for(unsigned int i=0; i<models.size(); ++i)
434  {
435  if(models[i].isValidForProjection())
436  {
437  models[i] = models[i].scaled(1.0/double(_imageDecimation));
438  }
439  }
440  if(!models.empty())
441  {
442  data.setRGBDImage(image, depthOrRight, models);
443  }
444 
445 
446  std::vector<StereoCameraModel> stereoModels = data.stereoCameraModels();
447  for(unsigned int i=0; i<stereoModels.size(); ++i)
448  {
449  if(stereoModels[i].isValidForProjection())
450  {
451  stereoModels[i].scale(1.0/double(_imageDecimation));
452  }
453  }
454  if(!stereoModels.empty())
455  {
456  data.setStereoImage(image, depthOrRight, stereoModels);
457  }
458  }
459  if(info) info->timeImageDecimation = timer.ticks();
460  }
461  if(_mirroring && !data.imageRaw().empty() && data.cameraModels().size()>=1)
462  {
463  if(data.cameraModels().size() == 1)
464  {
465  UDEBUG("");
466  UTimer timer;
467  cv::Mat tmpRgb;
468  cv::flip(data.imageRaw(), tmpRgb, 1);
469 
470  CameraModel tmpModel = data.cameraModels()[0];
471  if(data.cameraModels()[0].cx())
472  {
473  tmpModel = CameraModel(
474  data.cameraModels()[0].fx(),
475  data.cameraModels()[0].fy(),
476  float(data.imageRaw().cols) - data.cameraModels()[0].cx(),
477  data.cameraModels()[0].cy(),
478  data.cameraModels()[0].localTransform(),
479  data.cameraModels()[0].Tx(),
480  data.cameraModels()[0].imageSize());
481  }
482  cv::Mat tmpDepth = data.depthOrRightRaw();
483  if(!data.depthRaw().empty())
484  {
485  cv::flip(data.depthRaw(), tmpDepth, 1);
486  }
487  data.setRGBDImage(tmpRgb, tmpDepth, tmpModel);
488  if(info) info->timeMirroring = timer.ticks();
489  }
490  else
491  {
492  UWARN("Mirroring is not implemented for multiple cameras or stereo...");
493  }
494  }
495 
496  if(_stereoExposureCompensation && !data.imageRaw().empty() && !data.rightRaw().empty())
497  {
498  if(data.stereoCameraModels().size()==1)
499  {
500 #if CV_MAJOR_VERSION < 3
501  UWARN("Stereo exposure compensation not implemented for OpenCV version under 3.");
502 #else
503  UDEBUG("");
504  UTimer timer;
505  cv::Ptr<cv::detail::ExposureCompensator> compensator = cv::detail::ExposureCompensator::createDefault(cv::detail::ExposureCompensator::GAIN);
506  std::vector<cv::Point> topLeftCorners(2, cv::Point(0,0));
507  std::vector<cv::UMat> images;
508  std::vector<cv::UMat> masks(2, cv::UMat(data.imageRaw().size(), CV_8UC1, cv::Scalar(255)));
509  images.push_back(data.imageRaw().getUMat(cv::ACCESS_READ));
510  images.push_back(data.rightRaw().getUMat(cv::ACCESS_READ));
511  compensator->feed(topLeftCorners, images, masks);
512  cv::Mat imgLeft = data.imageRaw().clone();
513  compensator->apply(0, cv::Point(0,0), imgLeft, masks[0]);
514  cv::Mat imgRight = data.rightRaw().clone();
515  compensator->apply(1, cv::Point(0,0), imgRight, masks[1]);
516  data.setStereoImage(imgLeft, imgRight, data.stereoCameraModels()[0]);
517  cv::detail::GainCompensator * gainCompensator = (cv::detail::GainCompensator*)compensator.get();
518  UDEBUG("gains = %f %f ", gainCompensator->gains()[0], gainCompensator->gains()[1]);
519  if(info) info->timeStereoExposureCompensation = timer.ticks();
520 #endif
521  }
522  else
523  {
524  UWARN("Stereo exposure compensation only is not implemented to multiple stereo cameras...");
525  }
526  }
527 
528  if(_stereoToDepth && !data.imageRaw().empty() && !data.stereoCameraModels().empty() && data.stereoCameraModels()[0].isValidForProjection() && !data.rightRaw().empty())
529  {
530  if(data.stereoCameraModels().size()==1)
531  {
532  UDEBUG("");
533  UTimer timer;
534  cv::Mat depth = util2d::depthFromDisparity(
536  data.stereoCameraModels()[0].left().fx(),
537  data.stereoCameraModels()[0].baseline());
538  // set Tx for stereo bundle adjustment (when used)
540  data.stereoCameraModels()[0].left().fx(),
541  data.stereoCameraModels()[0].left().fy(),
542  data.stereoCameraModels()[0].left().cx(),
543  data.stereoCameraModels()[0].left().cy(),
544  data.stereoCameraModels()[0].localTransform(),
545  -data.stereoCameraModels()[0].baseline()*data.stereoCameraModels()[0].left().fx(),
546  data.stereoCameraModels()[0].left().imageSize());
547  data.setRGBDImage(data.imageRaw(), depth, model);
548  if(info) info->timeDisparity = timer.ticks();
549  }
550  else
551  {
552  UWARN("Stereo to depth is not implemented for multiple stereo cameras...");
553  }
554  }
555  if(_scanFromDepth &&
556  data.cameraModels().size() &&
557  data.cameraModels().at(0).isValidForProjection() &&
558  !data.depthRaw().empty())
559  {
560  UDEBUG("");
561  if(data.laserScanRaw().isEmpty())
562  {
564  UTimer timer;
565  pcl::IndicesPtr validIndices(new std::vector<int>);
566  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
567  data,
571  validIndices.get());
572  float maxPoints = (data.depthRaw().rows/_scanDownsampleStep)*(data.depthRaw().cols/_scanDownsampleStep);
573  LaserScan scan;
574  const Transform & baseToScan = data.cameraModels()[0].localTransform();
575  if(validIndices->size())
576  {
577  if(_scanVoxelSize>0.0f)
578  {
579  cloud = util3d::voxelize(cloud, validIndices, _scanVoxelSize);
580  float ratio = float(cloud->size()) / float(validIndices->size());
581  maxPoints = ratio * maxPoints;
582  }
583  else if(!cloud->is_dense)
584  {
585  pcl::PointCloud<pcl::PointXYZRGB>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGB>);
586  pcl::copyPointCloud(*cloud, *validIndices, *denseCloud);
587  cloud = denseCloud;
588  }
589 
590  if(cloud->size())
591  {
593  {
594  Eigen::Vector3f viewPoint(baseToScan.x(), baseToScan.y(), baseToScan.z());
595  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloud, _scanNormalsK, _scanNormalsRadius, viewPoint);
596  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudNormals(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
597  pcl::concatenateFields(*cloud, *normals, *cloudNormals);
598  scan = util3d::laserScanFromPointCloud(*cloudNormals, baseToScan.inverse());
599  }
600  else
601  {
602  scan = util3d::laserScanFromPointCloud(*cloud, baseToScan.inverse());
603  }
604  }
605  }
606  data.setLaserScan(LaserScan(scan, (int)maxPoints, _scanRangeMax, baseToScan));
607  if(info) info->timeScanFromDepth = timer.ticks();
608  }
609  else
610  {
611  UWARN("Option to create laser scan from depth image is enabled, but "
612  "there is already a laser scan in the captured sensor data. Scan from "
613  "depth will not be created.");
614  }
615  }
616  else if(!data.laserScanRaw().isEmpty())
617  {
618  UDEBUG("");
619  // filter the scan after registration
621  }
622 
623  // IMU filtering
624  if(_imuFilter && !data.imu().empty())
625  {
626  if(data.imu().angularVelocity()[0] == 0 &&
627  data.imu().angularVelocity()[1] == 0 &&
628  data.imu().angularVelocity()[2] == 0 &&
629  data.imu().linearAcceleration()[0] == 0 &&
630  data.imu().linearAcceleration()[1] == 0 &&
631  data.imu().linearAcceleration()[2] == 0)
632  {
633  UWARN("IMU's acc and gyr values are null! Please disable IMU filtering.");
634  }
635  else
636  {
637  // Transform IMU data in base_link to correctly initialize yaw
638  IMU imu = data.imu();
640  {
641  UASSERT(!data.imu().localTransform().isNull());
642  imu.convertToBaseFrame();
643 
644  }
646  imu.angularVelocity()[0],
647  imu.angularVelocity()[1],
648  imu.angularVelocity()[2],
649  imu.linearAcceleration()[0],
650  imu.linearAcceleration()[1],
651  imu.linearAcceleration()[2],
652  data.stamp());
653  double qx,qy,qz,qw;
654  _imuFilter->getOrientation(qx,qy,qz,qw);
655 
656  data.setIMU(IMU(
657  cv::Vec4d(qx,qy,qz,qw), cv::Mat::eye(3,3,CV_64FC1),
660  imu.localTransform()));
661 
662  UDEBUG("%f %f %f %f (gyro=%f %f %f, acc=%f %f %f, %fs)",
663  data.imu().orientation()[0],
664  data.imu().orientation()[1],
665  data.imu().orientation()[2],
666  data.imu().orientation()[3],
667  data.imu().angularVelocity()[0],
668  data.imu().angularVelocity()[1],
669  data.imu().angularVelocity()[2],
670  data.imu().linearAcceleration()[0],
671  data.imu().linearAcceleration()[1],
672  data.imu().linearAcceleration()[2],
673  data.stamp());
674  }
675  }
676 }
677 
678 } // namespace rtabmap
Transform _extrinsicsOdomToCamera
Definition: CameraThread.h:128
cv::Mat odomCovariance
Definition: CameraInfo.h:70
Definition: UTimer.h:46
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
Definition: SensorData.cpp:381
f
CameraThread(Camera *camera, const ParametersMap &parameters=ParametersMap())
void resetTimer()
Definition: Camera.cpp:62
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
void enableBilateralFiltering(float sigmaS, float sigmaR)
void setImageRate(float imageRate)
Definition: Camera.h:68
data
void convertToBaseFrame()
Definition: IMU.cpp:33
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
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:227
const std::vector< StereoCameraModel > & stereoCameraModels() const
Definition: SensorData.h:237
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
const cv::Vec4d & orientation() const
Definition: IMU.h:53
void setImageRate(float imageRate)
bool isEmpty() const
Definition: LaserScan.h:125
void post(UEvent *event, bool async=true) const
IMUFilter * _imuFilter
Definition: CameraThread.h:150
virtual void mainLoopKill()
cv::Mat rightRaw() const
Definition: SensorData.h:211
void setCameraModel(const CameraModel &model)
Definition: SensorData.h:204
virtual std::string getSerial() const =0
#define UASSERT(condition)
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:72
float timeStereoExposureCompensation
Definition: CameraInfo.h:63
int id() const
Definition: SensorData.h:174
clams::DiscreteDepthDistortionModel * _distortionModel
Definition: CameraThread.h:146
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:236
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)
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
cv::Mat depthRaw() const
Definition: SensorData.h:210
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)
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
Definition: util2d.cpp:1201
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap &parameters=ParametersMap(), bool baseFrameConversion=false)
static void registerCurrentThread(const std::string &name)
Definition: ULogger.cpp:218
StereoDense * _stereoDense
Definition: CameraThread.h:145
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:1056
std::string prettyPrint() const
Definition: Transform.cpp:316
virtual bool getPose(double stamp, Transform &pose, cv::Mat &covariance)
Definition: Camera.h:61
bool empty() const
Definition: LaserScan.h:124
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
LaserScan laserScanFromPointCloud(const PointCloud2T &cloud, bool filterNaNs, bool is2D, const Transform &transform)
Definition: util3d.hpp:37
void setStereoImage(const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &stereoCameraModel, bool clearPreviousData=true)
Definition: SensorData.cpp:304
virtual void mainLoop()
void setDistortionModel(const std::string &path)
std::string cameraName
Definition: CameraInfo.h:57
const Transform & localTransform() const
Definition: IMU.h:62
bool isNull() const
Definition: Transform.cpp:107
const cv::Mat & linearAccelerationCovariance() const
Definition: IMU.h:60
const cv::Vec3d & angularVelocity() const
Definition: IMU.h:56
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
void postUpdate(SensorData *data, CameraInfo *info=0) const
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
#define UDEBUG(...)
bool empty() const
Definition: IMU.h:67
virtual void mainLoopBegin()
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
double stamp() const
Definition: SensorData.h:176
const cv::Mat & angularVelocityCovariance() const
Definition: IMU.h:57
virtual bool odomProvided() const
Definition: Camera.h:60
float timeImageDecimation
Definition: CameraInfo.h:64
double ticks()
Definition: UTimer.cpp:117
model
Definition: trace.py:4
bool odomProvided() const
void setIMU(const IMU &imu)
Definition: SensorData.h:289
const cv::Vec3d linearAcceleration() const
Definition: IMU.h:59
void setGroundTruth(const Transform &pose)
Definition: SensorData.h:279
float timeBilateralFiltering
Definition: CameraInfo.h:67
void join(bool killFirst=false)
Definition: UThread.cpp:85
const IMU & imu() const
Definition: SensorData.h:290
bool isKilled() const
Definition: UThread.cpp:255
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
Transform odomPose
Definition: CameraInfo.h:69
void setStereoCameraModel(const StereoCameraModel &stereoCameraModel)
Definition: SensorData.h:206
virtual void getOrientation(double &qx, double &qy, double &qz, double &qw) const =0
Transform inverse() const
Definition: Transform.cpp:178
float timeUndistortDepth
Definition: CameraInfo.h:66


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28