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"
39 #include <opencv2/stitching/detail/exposure_compensate.hpp>
40 #include <rtabmap/utilite/UTimer.h>
42 
43 #include <pcl/io/io.h>
44 
45 namespace rtabmap
46 {
47 
48 // ownership transferred
49 CameraThread::CameraThread(Camera * camera, const ParametersMap & parameters) :
50  _camera(camera),
51  _mirroring(false),
52  _stereoExposureCompensation(false),
53  _colorOnly(false),
54  _imageDecimation(1),
55  _stereoToDepth(false),
56  _scanFromDepth(false),
57  _scanDecimation(4),
58  _scanMaxDepth(4.0f),
59  _scanMinDepth(0.0f),
60  _scanVoxelSize(0.0f),
61  _scanNormalsK(0),
62  _scanNormalsRadius(0.0f),
63  _stereoDense(new StereoBM(parameters)),
64  _distortionModel(0),
65  _bilateralFiltering(false),
66  _bilateralSigmaS(10),
67  _bilateralSigmaR(0.1)
68 {
69  UASSERT(_camera != 0);
70 }
71 
73 {
74  UDEBUG("");
75  join(true);
76  delete _camera;
77  delete _distortionModel;
78  delete _stereoDense;
79 }
80 
81 void CameraThread::setImageRate(float imageRate)
82 {
83  if(_camera)
84  {
85  _camera->setImageRate(imageRate);
86  }
87 }
88 
89 void CameraThread::setDistortionModel(const std::string & path)
90 {
92  {
93  delete _distortionModel;
94  _distortionModel = 0;
95  }
96  if(!path.empty())
97  {
99  _distortionModel->load(path);
100  if(!_distortionModel->isValid())
101  {
102  UERROR("Loaded distortion model \"%s\" is not valid!", path.c_str());
103  delete _distortionModel;
104  _distortionModel = 0;
105  }
106  }
107 }
108 
109 void CameraThread::enableBilateralFiltering(float sigmaS, float sigmaR)
110 {
111  UASSERT(sigmaS > 0.0f && sigmaR > 0.0f);
112  _bilateralFiltering = true;
113  _bilateralSigmaS = sigmaS;
114  _bilateralSigmaR = sigmaR;
115 }
116 
118 {
120  _camera->resetTimer();
121 }
122 
124 {
125  UTimer totalTime;
126  UDEBUG("");
127  CameraInfo info;
128  SensorData data = _camera->takeImage(&info);
129 
130  if(!data.imageRaw().empty() || (dynamic_cast<DBReader*>(_camera) != 0 && data.id()>0)) // intermediate nodes could not have image set
131  {
132  postUpdate(&data, &info);
133 
134  info.cameraName = _camera->getSerial();
135  info.timeTotal = totalTime.ticks();
136  this->post(new CameraEvent(data, info));
137  }
138  else if(!this->isKilled())
139  {
140  UWARN("no more images...");
141  this->kill();
142  this->post(new CameraEvent());
143  }
144 }
145 
147 {
148  UDEBUG("");
149  if(dynamic_cast<CameraFreenect2*>(_camera) != 0)
150  {
151  int i=20;
152  while(i-->0)
153  {
154  uSleep(100);
155  if(!this->isKilled())
156  {
157  break;
158  }
159  }
160  if(this->isKilled())
161  {
162  //still in killed state, maybe a deadlock
163  UERROR("CameraFreenect2: Failed to kill normally the Freenect2 driver! The thread is locked "
164  "on waitForNewFrame() method of libfreenect2. This maybe caused by not linking on the right libusb. "
165  "Note that rtabmap should link on libusb of libfreenect2. "
166  "Tip before starting rtabmap: \"$ export LD_LIBRARY_PATH=~/libfreenect2/depends/libusb/lib:$LD_LIBRARY_PATH\"");
167  }
168 
169  }
170 }
171 
172 void CameraThread::postUpdate(SensorData * dataPtr, CameraInfo * info) const
173 {
174  UASSERT(dataPtr!=0);
175  SensorData & data = *dataPtr;
176  if(_colorOnly && !data.depthRaw().empty())
177  {
178  data.setDepthOrRightRaw(cv::Mat());
179  }
180 
181  if(_distortionModel && !data.depthRaw().empty())
182  {
183  UTimer timer;
184  if(_distortionModel->getWidth() == data.depthRaw().cols &&
185  _distortionModel->getHeight() == data.depthRaw().rows )
186  {
187  cv::Mat depth = data.depthRaw().clone();// make sure we are not modifying data in cached signatures.
188  _distortionModel->undistort(depth);
189  data.setDepthOrRightRaw(depth);
190  }
191  else
192  {
193  UERROR("Distortion model size is %dx%d but dpeth image is %dx%d!",
195  data.depthRaw().cols, data.depthRaw().rows);
196  }
197  if(info) info->timeUndistortDepth = timer.ticks();
198  }
199 
200  if(_bilateralFiltering && !data.depthRaw().empty())
201  {
202  UTimer timer;
204  if(info) info->timeBilateralFiltering = timer.ticks();
205  }
206 
207  if(_imageDecimation>1 && !data.imageRaw().empty())
208  {
209  UDEBUG("");
210  UTimer timer;
211  if(!data.depthRaw().empty() &&
212  !(data.depthRaw().rows % _imageDecimation == 0 && data.depthRaw().cols % _imageDecimation == 0))
213  {
214  UERROR("Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! "
215  "Images won't be resized.", _imageDecimation, data.depthRaw().cols, data.depthRaw().rows);
216  }
217  else
218  {
221  std::vector<CameraModel> models = data.cameraModels();
222  for(unsigned int i=0; i<models.size(); ++i)
223  {
224  if(models[i].isValidForProjection())
225  {
226  models[i] = models[i].scaled(1.0/double(_imageDecimation));
227  }
228  }
229  data.setCameraModels(models);
230  StereoCameraModel stereoModel = data.stereoCameraModel();
231  if(stereoModel.isValidForProjection())
232  {
233  stereoModel.scale(1.0/double(_imageDecimation));
234  data.setStereoCameraModel(stereoModel);
235  }
236  }
237  if(info) info->timeImageDecimation = timer.ticks();
238  }
239  if(_mirroring && !data.imageRaw().empty() && data.cameraModels().size() == 1)
240  {
241  UDEBUG("");
242  UTimer timer;
243  cv::Mat tmpRgb;
244  cv::flip(data.imageRaw(), tmpRgb, 1);
245  data.setImageRaw(tmpRgb);
246  UASSERT_MSG(data.cameraModels().size() <= 1 && !data.stereoCameraModel().isValidForProjection(), "Only single RGBD cameras are supported for mirroring.");
247  if(data.cameraModels().size() && data.cameraModels()[0].cx())
248  {
249  CameraModel tmpModel(
250  data.cameraModels()[0].fx(),
251  data.cameraModels()[0].fy(),
252  float(data.imageRaw().cols) - data.cameraModels()[0].cx(),
253  data.cameraModels()[0].cy(),
254  data.cameraModels()[0].localTransform(),
255  data.cameraModels()[0].Tx(),
256  data.cameraModels()[0].imageSize());
257  data.setCameraModel(tmpModel);
258  }
259  if(!data.depthRaw().empty())
260  {
261  cv::Mat tmpDepth;
262  cv::flip(data.depthRaw(), tmpDepth, 1);
263  data.setDepthOrRightRaw(tmpDepth);
264  }
265  if(info) info->timeMirroring = timer.ticks();
266  }
267 
268  if(_stereoExposureCompensation && !data.imageRaw().empty() && !data.rightRaw().empty())
269  {
270 #if CV_MAJOR_VERSION < 3
271  UWARN("Stereo exposure compensation not implemented for OpenCV version under 3.");
272 #else
273  UDEBUG("");
274  UTimer timer;
275  cv::Ptr<cv::detail::ExposureCompensator> compensator = cv::detail::ExposureCompensator::createDefault(cv::detail::ExposureCompensator::GAIN);
276  std::vector<cv::Point> topLeftCorners(2, cv::Point(0,0));
277  std::vector<cv::UMat> images;
278  std::vector<cv::UMat> masks(2, cv::UMat(data.imageRaw().size(), CV_8UC1, cv::Scalar(255)));
279  images.push_back(data.imageRaw().getUMat(cv::ACCESS_READ));
280  images.push_back(data.rightRaw().getUMat(cv::ACCESS_READ));
281  compensator->feed(topLeftCorners, images, masks);
282  cv::Mat img = data.imageRaw().clone();
283  compensator->apply(0, cv::Point(0,0), img, masks[0]);
284  data.setImageRaw(img);
285  img = data.rightRaw().clone();
286  compensator->apply(1, cv::Point(0,0), img, masks[1]);
287  data.setDepthOrRightRaw(img);
288  cv::detail::GainCompensator * gainCompensator = (cv::detail::GainCompensator*)compensator.get();
289  UDEBUG("gains = %f %f ", gainCompensator->gains()[0], gainCompensator->gains()[1]);
290  if(info) info->timeStereoExposureCompensation = timer.ticks();
291 #endif
292  }
293 
294  if(_stereoToDepth && !data.imageRaw().empty() && data.stereoCameraModel().isValidForProjection() && !data.rightRaw().empty())
295  {
296  UDEBUG("");
297  UTimer timer;
298  cv::Mat depth = util2d::depthFromDisparity(
300  data.stereoCameraModel().left().fx(),
301  data.stereoCameraModel().baseline());
302  // set Tx for stereo bundle adjustment (when used)
303  CameraModel model = CameraModel(
304  data.stereoCameraModel().left().fx(),
305  data.stereoCameraModel().left().fy(),
306  data.stereoCameraModel().left().cx(),
307  data.stereoCameraModel().left().cy(),
309  -data.stereoCameraModel().baseline()*data.stereoCameraModel().left().fx(),
310  data.stereoCameraModel().left().imageSize());
311  data.setCameraModel(model);
312  data.setDepthOrRightRaw(depth);
314  if(info) info->timeDisparity = timer.ticks();
315  }
316  if(_scanFromDepth &&
317  data.cameraModels().size() &&
318  data.cameraModels().at(0).isValidForProjection() &&
319  !data.depthRaw().empty())
320  {
321  UDEBUG("");
322  if(data.laserScanRaw().isEmpty())
323  {
324  UASSERT(_scanDecimation >= 1);
325  UTimer timer;
326  pcl::IndicesPtr validIndices(new std::vector<int>);
327  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
328  data,
332  validIndices.get());
333  float maxPoints = (data.depthRaw().rows/_scanDecimation)*(data.depthRaw().cols/_scanDecimation);
334  cv::Mat scan;
335  const Transform & baseToScan = data.cameraModels()[0].localTransform();
337  if(validIndices->size())
338  {
339  if(_scanVoxelSize>0.0f)
340  {
341  cloud = util3d::voxelize(cloud, validIndices, _scanVoxelSize);
342  float ratio = float(cloud->size()) / float(validIndices->size());
343  maxPoints = ratio * maxPoints;
344  }
345  else if(!cloud->is_dense)
346  {
347  pcl::PointCloud<pcl::PointXYZRGB>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGB>);
348  pcl::copyPointCloud(*cloud, *validIndices, *denseCloud);
349  cloud = denseCloud;
350  }
351 
352  if(cloud->size())
353  {
355  {
356  Eigen::Vector3f viewPoint(baseToScan.x(), baseToScan.y(), baseToScan.z());
357  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloud, _scanNormalsK, _scanNormalsRadius, viewPoint);
358  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudNormals(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
359  pcl::concatenateFields(*cloud, *normals, *cloudNormals);
360  scan = util3d::laserScanFromPointCloud(*cloudNormals, baseToScan.inverse());
361  format = LaserScan::kXYZRGBNormal;
362  }
363  else
364  {
365  scan = util3d::laserScanFromPointCloud(*cloud, baseToScan.inverse());
366  }
367  }
368  }
369  data.setLaserScanRaw(LaserScan(scan, (int)maxPoints, _scanMaxDepth, format, baseToScan));
370  if(info) info->timeScanFromDepth = timer.ticks();
371  }
372  else
373  {
374  UWARN("Option to create laser scan from depth image is enabled, but "
375  "there is already a laser scan in the captured sensor data. Scan from "
376  "depth will not be created.");
377  }
378  }
379 }
380 
381 } // namespace rtabmap
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true)
Definition: util3d.cpp:1266
Definition: UTimer.h:46
const cv::Size & imageSize() const
Definition: CameraModel.h:112
f
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:66
void kill()
Definition: UThread.cpp:48
cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
Definition: util2d.cpp:758
bool isEmpty() const
Definition: LaserScan.h:69
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Definition: util2d.cpp:1809
void setCameraModels(const std::vector< CameraModel > &models)
Definition: SensorData.h:168
void setImageRate(float imageRate)
const LaserScan & laserScanRaw() const
Definition: SensorData.h:163
const cv::Mat & imageRaw() const
Definition: SensorData.h:161
void post(UEvent *event, bool async=true) const
cv::Mat rightRaw() const
Definition: SensorData.h:173
void setImageRaw(const cv::Mat &imageRaw)
Definition: SensorData.h:164
virtual void mainLoopKill()
void setCameraModel(const CameraModel &model)
Definition: SensorData.h:167
virtual std::string getSerial() const =0
#define UASSERT(condition)
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:67
float timeStereoExposureCompensation
Definition: CameraInfo.h:62
clams::DiscreteDepthDistortionModel * _distortionModel
Definition: CameraThread.h:116
const CameraModel & left() const
double cx() const
Definition: CameraModel.h:97
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:96
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
Definition: util2d.cpp:1196
static void registerCurrentThread(const std::string &name)
Definition: ULogger.cpp:218
StereoDense * _stereoDense
Definition: CameraThread.h:115
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)
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:162
virtual void mainLoop()
int id() const
Definition: SensorData.h:152
void setDistortionModel(const std::string &path)
std::string cameraName
Definition: CameraInfo.h:56
double cy() const
Definition: CameraModel.h:98
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:193
#define UDEBUG(...)
double fx() const
Definition: CameraModel.h:95
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:194
#define UWARN(...)
float timeImageDecimation
Definition: CameraInfo.h:63
double ticks()
Definition: UTimer.cpp:110
Transform inverse() const
Definition: Transform.cpp:169
float timeBilateralFiltering
Definition: CameraInfo.h:66
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)
void setStereoCameraModel(const StereoCameraModel &stereoCameraModel)
Definition: SensorData.h:169
const Transform & localTransform() const
void setDepthOrRightRaw(const cv::Mat &depthOrImageRaw)
Definition: SensorData.h:165
cv::Mat depthRaw() const
Definition: SensorData.h:172
float timeUndistortDepth
Definition: CameraInfo.h:65
void setLaserScanRaw(const LaserScan &laserScanRaw)
Definition: SensorData.h:166


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30