CameraStereoVideo.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/utilite/UTimer.h>
31 #include <opencv2/imgproc/types_c.h>
32 #if CV_MAJOR_VERSION > 3
33 #include <opencv2/videoio/videoio_c.h>
34 #if CV_MAJOR_VERSION > 4
35 #include <opencv2/videoio/legacy/constants_c.h>
36 #endif
37 #endif
38 
39 namespace rtabmap
40 {
41 
43 {
44  return true;
45 }
46 
48  const std::string & path,
49  bool rectifyImages,
50  float imageRate,
51  const Transform & localTransform) :
52  Camera(imageRate, localTransform),
53  path_(path),
54  rectifyImages_(rectifyImages),
55  src_(CameraVideo::kVideoFile),
56  usbDevice_(0),
57  usbDevice2_(-1),
58  _width(0),
59  _height(0),
60  rightGrayScale_(true)
61 {
62 }
63 
65  const std::string & pathLeft,
66  const std::string & pathRight,
67  bool rectifyImages,
68  float imageRate,
69  const Transform & localTransform) :
70  Camera(imageRate, localTransform),
71  path_(pathLeft),
72  path2_(pathRight),
73  rectifyImages_(rectifyImages),
74  src_(CameraVideo::kVideoFile),
75  usbDevice_(0),
76  usbDevice2_(-1),
77  _width(0),
78  _height(0),
79  rightGrayScale_(true)
80 {
81 }
82 
84  int device,
85  bool rectifyImages,
86  float imageRate,
87  const Transform & localTransform) :
88  Camera(imageRate, localTransform),
89  rectifyImages_(rectifyImages),
90  src_(CameraVideo::kUsbDevice),
91  usbDevice_(device),
92  usbDevice2_(-1),
93  _width(0),
94  _height(0),
95  rightGrayScale_(true)
96 {
97 }
98 
100  int deviceLeft,
101  int deviceRight,
102  bool rectifyImages,
103  float imageRate,
104  const Transform & localTransform) :
105  Camera(imageRate, localTransform),
106  rectifyImages_(rectifyImages),
107  src_(CameraVideo::kUsbDevice),
108  usbDevice_(deviceLeft),
109  usbDevice2_(deviceRight),
110  _width(0),
111  _height(0),
112  rightGrayScale_(true)
113 {
114 }
115 
117 {
118  capture_.release();
119  capture2_.release();
120 }
121 
122 bool CameraStereoVideo::init(const std::string & calibrationFolder, const std::string & cameraName)
123 {
124  cameraName_ = cameraName;
125  if(capture_.isOpened())
126  {
127  capture_.release();
128  }
129  if(capture2_.isOpened())
130  {
131  capture2_.release();
132  }
133 
135  {
136  capture_.open(usbDevice_);
137  if(usbDevice2_ < 0)
138  {
139  ULOGGER_DEBUG("CameraStereoVideo: Usb device initialization on device %d", usbDevice_);
140  }
141  else
142  {
143  ULOGGER_DEBUG("CameraStereoVideo: Usb device initialization on devices %d and %d", usbDevice_, usbDevice2_);
144  capture2_.open(usbDevice2_);
145  }
146  }
147  else if (src_ == CameraVideo::kVideoFile)
148  {
149  capture_.open(path_.c_str());
150  if(path2_.empty())
151  {
152  ULOGGER_DEBUG("CameraStereoVideo: filename=\"%s\"", path_.c_str());
153  }
154  else
155  {
156  ULOGGER_DEBUG("CameraStereoVideo: filenames=\"%s\" and \"%s\"", path_.c_str(), path2_.c_str());
157  capture2_.open(path2_.c_str());
158  }
159  }
160  else
161  {
162  ULOGGER_ERROR("CameraStereoVideo: Unknown source...");
163  }
164 
165  if(!capture_.isOpened() || ((!path2_.empty() || usbDevice2_>=0) && !capture2_.isOpened()))
166  {
167  ULOGGER_ERROR("CameraStereoVideo: Failed to create a capture object!");
168  capture_.release();
169  capture2_.release();
170  return false;
171  }
172 
173  if (cameraName_.empty())
174  {
175  unsigned int guid = (unsigned int)capture_.get(CV_CAP_PROP_GUID);
176  if (guid != 0 && guid != 0xffffffff)
177  {
178  cameraName_ = uFormat("%08x", guid);
179  }
180  }
181 
182  // look for calibration files
183  if(!calibrationFolder.empty() && !cameraName_.empty())
184  {
185  if(!stereoModel_.load(calibrationFolder, cameraName_, false))
186  {
187  UWARN("Missing calibration files for camera \"%s\" in \"%s\" folder, you should calibrate the camera!",
188  cameraName_.c_str(), calibrationFolder.c_str());
189  }
190  else
191  {
192  UINFO("Stereo parameters: fx=%f cx=%f cy=%f baseline=%f",
193  stereoModel_.left().fx(),
194  stereoModel_.left().cx(),
195  stereoModel_.left().cy(),
197  }
198  }
199 
201 
203  {
205  {
207  {
208  UWARN("Desired resolution of %dx%d is set but calibration has "
209  "been loaded with resolution %dx%d, using calibration resolution.",
210  _width, _height,
212  }
213 
214  if(capture_.isOpened())
215  {
216  bool resolutionSet = false;
217  resolutionSet = capture_.set(CV_CAP_PROP_FRAME_WIDTH, stereoModel_.left().imageWidth()*(capture2_.isOpened()?1:2));
218  resolutionSet = resolutionSet && capture_.set(CV_CAP_PROP_FRAME_HEIGHT, stereoModel_.left().imageHeight());
219  if(capture2_.isOpened())
220  {
221  resolutionSet = resolutionSet && capture2_.set(CV_CAP_PROP_FRAME_WIDTH, stereoModel_.right().imageWidth());
222  resolutionSet = resolutionSet && capture2_.set(CV_CAP_PROP_FRAME_HEIGHT, stereoModel_.right().imageHeight());
223  }
224 
225  // Check if the resolution was set successfully
226  int actualWidth = int(capture_.get(CV_CAP_PROP_FRAME_WIDTH));
227  int actualHeight = int(capture_.get(CV_CAP_PROP_FRAME_HEIGHT));
228  if(!resolutionSet ||
229  actualWidth != stereoModel_.left().imageWidth()*(capture2_.isOpened()?1:2) ||
230  actualHeight != stereoModel_.left().imageHeight())
231  {
232  UERROR("Calibration resolution (%dx%d) cannot be set to camera driver, "
233  "actual resolution is %dx%d. You would have to re-calibrate with one "
234  "supported format by your camera. "
235  "Do \"v4l2-ctl --list-formats-ext\" to list all supported "
236  "formats by your camera. For side-by-side format, you should set listed width/2.",
238  actualWidth/(capture2_.isOpened()?1:2), actualHeight);
239  }
240  }
241  }
242  else if(_width > 0 && _height > 0)
243  {
244  if(capture_.isOpened())
245  {
246  bool resolutionSet = false;
247  resolutionSet = capture_.set(CV_CAP_PROP_FRAME_WIDTH, _width*(capture2_.isOpened()?1:2));
248  resolutionSet = resolutionSet && capture_.set(CV_CAP_PROP_FRAME_HEIGHT, _height);
249  if(capture2_.isOpened())
250  {
251  resolutionSet = resolutionSet && capture2_.set(CV_CAP_PROP_FRAME_WIDTH, _width);
252  resolutionSet = resolutionSet && capture2_.set(CV_CAP_PROP_FRAME_HEIGHT, _height);
253  }
254 
255  // Check if the resolution was set successfully
256  int actualWidth = int(capture_.get(CV_CAP_PROP_FRAME_WIDTH));
257  int actualHeight = int(capture_.get(CV_CAP_PROP_FRAME_HEIGHT));
258  if(!resolutionSet ||
259  actualWidth != _width*(capture2_.isOpened()?1:2) ||
260  actualHeight != _height)
261  {
262  UWARN("Desired resolution (%dx%d) cannot be set to camera driver, "
263  "actual resolution is %dx%d. "
264  "Do \"v4l2-ctl --list-formats-ext\" to list all supported "
265  "formats by your camera. For side-by-side format, you should set listed width/2.",
266  _width, _height,
267  actualWidth/(capture2_.isOpened()?1:2), actualHeight);
268  }
269  }
270  }
271 
272  // Set FPS
273  if (this->getFrameRate() > 0)
274  {
275  bool fpsSupported = false;
276  fpsSupported = capture_.set(CV_CAP_PROP_FPS, this->getFrameRate());
277  if (capture2_.isOpened())
278  {
279  fpsSupported = fpsSupported && capture2_.set(CV_CAP_PROP_FPS, this->getFrameRate());
280  }
281  if(fpsSupported)
282  {
283  // Check if the FPS was set successfully
284  double actualFPS = capture_.get(cv::CAP_PROP_FPS);
285 
286  if(fabs(actualFPS - this->getFrameRate()) < 0.01)
287  {
288  this->setFrameRate(0);
289  }
290  else
291  {
292  UWARN("Desired FPS (%f Hz) cannot be set to camera driver, "
293  "actual FPS is %f Hz. We will throttle to lowest FPS. "
294  "Do \"v4l2-ctl --list-formats-ext\" to list all supported "
295  "formats by your camera.",
296  this->getFrameRate(), actualFPS);
297  if(this->getFrameRate() > actualFPS)
298  {
299  this->setFrameRate(0);
300  }
301  }
302  }
303  }
304 
305  // Set FOURCC
306  if (!_fourcc.empty())
307  {
308  if(_fourcc.size() == 4)
309  {
310  std::string fourccUpperCase = uToUpperCase(_fourcc);
311  int fourcc = cv::VideoWriter::fourcc(fourccUpperCase.at(0), fourccUpperCase.at(1), fourccUpperCase.at(2), fourccUpperCase.at(3));
312  bool fourccSupported = false;
313  fourccSupported = capture_.set(CV_CAP_PROP_FOURCC, fourcc);
314  if (capture2_.isOpened())
315  {
316  fourccSupported = fourccSupported && capture2_.set(CV_CAP_PROP_FOURCC, fourcc);
317  }
318 
319  // Check if the FOURCC was set successfully
320  int actualFourcc = int(capture_.get(CV_CAP_PROP_FOURCC));
321 
322  if(!fourccSupported || actualFourcc != fourcc)
323  {
324  UWARN("Camera doesn't support provided FOURCC \"%s\". "
325  "Do \"v4l2-ctl --list-formats-ext\" to list all supported "
326  "formats by your camera.", fourccUpperCase.c_str());
327  }
328  }
329  else
330  {
331  UERROR("FOURCC parameter should be 4 characters, current value is \"%s\"", _fourcc.c_str());
332  }
333  }
334  }
335 
337  {
338  UERROR("Parameter \"rectifyImages\" is set, but no stereo model is loaded or valid.");
339  return false;
340  }
341  return true;
342 }
343 
345 {
347 }
348 
349 std::string CameraStereoVideo::getSerial() const
350 {
351  return cameraName_;
352 }
353 
355 {
357 
358  cv::Mat img;
359  if(capture_.isOpened() && ((path2_.empty() && usbDevice2_ < 0) || capture2_.isOpened()))
360  {
361  cv::Mat leftImage;
362  cv::Mat rightImage;
363  if(path2_.empty() && usbDevice2_ < 0)
364  {
365  if(!capture_.read(img))
366  {
367  return data;
368  }
369  // Side by side stream
370  leftImage = cv::Mat(img, cv::Rect( 0, 0, img.size().width/2, img.size().height ));
371  rightImage = cv::Mat(img, cv::Rect( img.size().width/2, 0, img.size().width/2, img.size().height ));
372  }
373  else if(!capture_.read(leftImage) || !capture2_.read(rightImage))
374  {
375  return data;
376  }
377  else if(leftImage.cols != rightImage.cols || leftImage.rows != rightImage.rows)
378  {
379  UERROR("Left and right streams don't have image of the same size: left=%dx%d right=%dx%d",
380  leftImage.cols, leftImage.rows, rightImage.cols, rightImage.rows);
381  return data;
382  }
383 
384  // Rectification
385  bool rightCvt = false;
386  if(rightImage.type() != CV_8UC1 && rightGrayScale_)
387  {
388  cv::Mat tmp;
389  cv::cvtColor(rightImage, tmp, CV_BGR2GRAY);
390  rightImage = tmp;
391  rightCvt = true;
392  }
393 
395  {
396  leftImage = stereoModel_.left().rectifyImage(leftImage);
397  rightImage = stereoModel_.right().rectifyImage(rightImage);
398  }
399  else
400  {
401  leftImage = leftImage.clone();
402  if(!rightCvt)
403  {
404  rightImage = rightImage.clone();
405  }
406  }
407 
408  if(stereoModel_.left().imageHeight() == 0 || stereoModel_.left().imageWidth() == 0)
409  {
410  stereoModel_.setImageSize(leftImage.size());
411  }
412 
413  data = SensorData(leftImage, rightImage, stereoModel_, this->getNextSeqID(), UTimer::now());
414  }
415  else
416  {
417  ULOGGER_WARN("The camera must be initialized before requesting an image.");
418  }
419 
420  return data;
421 }
422 
423 
424 } // namespace rtabmap
rtabmap::SensorData
Definition: SensorData.h:51
int
int
rtabmap::CameraModel::fx
double fx() const
Definition: CameraModel.h:102
rtabmap::CameraModel::cx
double cx() const
Definition: CameraModel.h:104
rtabmap::CameraStereoVideo::getSerial
virtual std::string getSerial() const
Definition: CameraStereoVideo.cpp:349
rtabmap::CameraModel::imageWidth
int imageWidth() const
Definition: CameraModel.h:120
UINFO
#define UINFO(...)
rtabmap::CameraStereoVideo::~CameraStereoVideo
virtual ~CameraStereoVideo()
Definition: CameraStereoVideo.cpp:116
UTimer::now
static double now()
Definition: UTimer.cpp:80
rtabmap::CameraStereoVideo::usbDevice_
int usbDevice_
Definition: CameraStereoVideo.h:87
rtabmap::CameraStereoVideo::rectifyImages_
bool rectifyImages_
Definition: CameraStereoVideo.h:83
rtabmap::CameraStereoVideo::stereoModel_
StereoCameraModel stereoModel_
Definition: CameraStereoVideo.h:84
rtabmap::StereoCameraModel::load
bool load(const std::string &directory, const std::string &cameraName, bool ignoreStereoTransform=true)
Definition: StereoCameraModel.cpp:223
rtabmap::CameraVideo::kVideoFile
@ kVideoFile
Definition: CameraVideo.h:40
rtabmap::CameraModel::cy
double cy() const
Definition: CameraModel.h:105
rtabmap::StereoCameraModel::setImageSize
void setImageSize(const cv::Size &size)
Definition: StereoCameraModel.h:95
rtabmap::CameraStereoVideo::cameraName_
std::string cameraName_
Definition: CameraStereoVideo.h:85
rtabmap_netvlad.img
img
Definition: rtabmap_netvlad.py:78
rtabmap::StereoCameraModel::baseline
double baseline() const
Definition: StereoCameraModel.h:104
rtabmap::SensorCapture::setFrameRate
void setFrameRate(float frameRate)
Definition: SensorCapture.h:65
rtabmap::SensorCapture::getLocalTransform
const Transform & getLocalTransform() const
Definition: SensorCapture.h:62
true
#define true
Definition: ConvertUTF.c:57
rtabmap::CameraStereoVideo::_fourcc
std::string _fourcc
Definition: CameraStereoVideo.h:91
rtabmap::CameraStereoVideo::available
static bool available()
Definition: CameraStereoVideo.cpp:42
UTimer.h
rtabmap::StereoCameraModel::setLocalTransform
void setLocalTransform(const Transform &transform)
Definition: StereoCameraModel.h:118
ULOGGER_DEBUG
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
rtabmap::CameraVideo::kUsbDevice
@ kUsbDevice
Definition: CameraVideo.h:40
rtabmap::CameraStereoVideo::rightGrayScale_
bool rightGrayScale_
Definition: CameraStereoVideo.h:92
fabs
Real fabs(const Real &a)
rtabmap::CameraStereoVideo::path_
std::string path_
Definition: CameraStereoVideo.h:81
rtabmap::SensorCaptureInfo
Definition: SensorCaptureInfo.h:36
CameraStereoVideo.h
rtabmap::CameraStereoVideo::_width
int _width
Definition: CameraStereoVideo.h:89
rtabmap::StereoCameraModel::right
const CameraModel & right() const
Definition: StereoCameraModel.h:123
data
int data[]
UConversion.h
Some conversion functions.
rtabmap_superglue.device
string device
Definition: rtabmap_superglue.py:21
rtabmap::CameraModel::rectifyImage
cv::Mat rectifyImage(const cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
Definition: CameraModel.cpp:695
rtabmap::CameraStereoVideo::capture2_
cv::VideoCapture capture2_
Definition: CameraStereoVideo.h:80
rtabmap::CameraStereoVideo::capture_
cv::VideoCapture capture_
Definition: CameraStereoVideo.h:79
rtabmap::StereoCameraModel::left
const CameraModel & left() const
Definition: StereoCameraModel.h:122
rtabmap::StereoCameraModel::isValidForProjection
bool isValidForProjection() const
Definition: StereoCameraModel.h:85
rtabmap::Camera
Definition: Camera.h:43
rtabmap::CameraModel::isValidForRectification
bool isValidForRectification() const
Definition: CameraModel.h:89
path
path
UWARN
#define UWARN(...)
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
rtabmap::StereoCameraModel::isValidForRectification
bool isValidForRectification() const
Definition: StereoCameraModel.h:86
rtabmap::Transform
Definition: Transform.h:41
rtabmap::CameraStereoVideo::captureImage
virtual SensorData captureImage(SensorCaptureInfo *info=0)
Definition: CameraStereoVideo.cpp:354
rtabmap::CameraStereoVideo::isCalibrated
virtual bool isCalibrated() const
Definition: CameraStereoVideo.cpp:344
ULOGGER_ERROR
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
uToUpperCase
std::string UTILITE_EXPORT uToUpperCase(const std::string &str)
Definition: UConversion.cpp:63
rtabmap::CameraModel::imageHeight
int imageHeight() const
Definition: CameraModel.h:121
rtabmap::CameraStereoVideo::src_
CameraVideo::Source src_
Definition: CameraStereoVideo.h:86
rtabmap::CameraStereoVideo::init
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
Definition: CameraStereoVideo.cpp:122
rtabmap::CameraStereoVideo::_height
int _height
Definition: CameraStereoVideo.h:90
rtabmap::CameraStereoVideo::path2_
std::string path2_
Definition: CameraStereoVideo.h:82
rtabmap::SensorCapture::getFrameRate
float getFrameRate() const
Definition: SensorCapture.h:61
rtabmap::CameraStereoVideo::usbDevice2_
int usbDevice2_
Definition: CameraStereoVideo.h:88
rtabmap
Definition: CameraARCore.cpp:35
UERROR
#define UERROR(...)
ULOGGER_WARN
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
rtabmap::SensorCapture::getNextSeqID
int getNextSeqID()
Definition: SensorCapture.h:83
rtabmap::CameraStereoVideo::CameraStereoVideo
CameraStereoVideo(const std::string &pathSideBySide, bool rectifyImages=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
Definition: CameraStereoVideo.cpp:47
rtabmap::CameraVideo
Definition: CameraVideo.h:36


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:51