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 {
61 }
62 
64  const std::string & pathLeft,
65  const std::string & pathRight,
66  bool rectifyImages,
67  float imageRate,
68  const Transform & localTransform) :
69  Camera(imageRate, localTransform),
70  path_(pathLeft),
71  path2_(pathRight),
72  rectifyImages_(rectifyImages),
73  src_(CameraVideo::kVideoFile),
74  usbDevice_(0),
75  usbDevice2_(-1),
76  _width(0),
77  _height(0)
78 {
79 }
80 
82  int device,
83  bool rectifyImages,
84  float imageRate,
85  const Transform & localTransform) :
86  Camera(imageRate, localTransform),
87  rectifyImages_(rectifyImages),
88  src_(CameraVideo::kUsbDevice),
89  usbDevice_(device),
90  usbDevice2_(-1),
91  _width(0),
92  _height(0)
93 {
94 }
95 
97  int deviceLeft,
98  int deviceRight,
99  bool rectifyImages,
100  float imageRate,
101  const Transform & localTransform) :
102  Camera(imageRate, localTransform),
103  rectifyImages_(rectifyImages),
104  src_(CameraVideo::kUsbDevice),
105  usbDevice_(deviceLeft),
106  usbDevice2_(deviceRight),
107  _width(0),
108  _height(0)
109 {
110 }
111 
113 {
114  capture_.release();
115  capture2_.release();
116 }
117 
118 bool CameraStereoVideo::init(const std::string & calibrationFolder, const std::string & cameraName)
119 {
120  cameraName_ = cameraName;
121  if(capture_.isOpened())
122  {
123  capture_.release();
124  }
125  if(capture2_.isOpened())
126  {
127  capture2_.release();
128  }
129 
131  {
132  capture_.open(usbDevice_);
133  if(usbDevice2_ < 0)
134  {
135  ULOGGER_DEBUG("CameraStereoVideo: Usb device initialization on device %d", usbDevice_);
136  }
137  else
138  {
139  ULOGGER_DEBUG("CameraStereoVideo: Usb device initialization on devices %d and %d", usbDevice_, usbDevice2_);
140  capture2_.open(usbDevice2_);
141  }
142  }
143  else if (src_ == CameraVideo::kVideoFile)
144  {
145  capture_.open(path_.c_str());
146  if(path2_.empty())
147  {
148  ULOGGER_DEBUG("CameraStereoVideo: filename=\"%s\"", path_.c_str());
149  }
150  else
151  {
152  ULOGGER_DEBUG("CameraStereoVideo: filenames=\"%s\" and \"%s\"", path_.c_str(), path2_.c_str());
153  capture2_.open(path2_.c_str());
154  }
155  }
156  else
157  {
158  ULOGGER_ERROR("CameraStereoVideo: Unknown source...");
159  }
160 
161  if(!capture_.isOpened() || ((!path2_.empty() || usbDevice2_>=0) && !capture2_.isOpened()))
162  {
163  ULOGGER_ERROR("CameraStereoVideo: Failed to create a capture object!");
164  capture_.release();
165  capture2_.release();
166  return false;
167  }
168 
169  if (cameraName_.empty())
170  {
171  unsigned int guid = (unsigned int)capture_.get(CV_CAP_PROP_GUID);
172  if (guid != 0 && guid != 0xffffffff)
173  {
174  cameraName_ = uFormat("%08x", guid);
175  }
176  }
177 
178  // look for calibration files
179  if(!calibrationFolder.empty() && !cameraName_.empty())
180  {
181  if(!stereoModel_.load(calibrationFolder, cameraName_, false))
182  {
183  UWARN("Missing calibration files for camera \"%s\" in \"%s\" folder, you should calibrate the camera!",
184  cameraName_.c_str(), calibrationFolder.c_str());
185  }
186  else
187  {
188  UINFO("Stereo parameters: fx=%f cx=%f cy=%f baseline=%f",
189  stereoModel_.left().fx(),
190  stereoModel_.left().cx(),
191  stereoModel_.left().cy(),
193  }
194  }
195 
197 
199  {
201  {
202  if(capture_.isOpened())
203  {
204  capture_.set(CV_CAP_PROP_FRAME_WIDTH, stereoModel_.left().imageWidth()*(capture2_.isOpened()?1:2));
205  capture_.set(CV_CAP_PROP_FRAME_HEIGHT, stereoModel_.left().imageHeight());
206  if(capture2_.isOpened())
207  {
208  capture2_.set(CV_CAP_PROP_FRAME_WIDTH, stereoModel_.right().imageWidth());
209  capture2_.set(CV_CAP_PROP_FRAME_HEIGHT, stereoModel_.right().imageHeight());
210  }
211  }
212  }
213  else if(_width > 0 && _height > 0)
214  {
215  if(capture_.isOpened())
216  {
217  capture_.set(CV_CAP_PROP_FRAME_WIDTH, _width*(capture2_.isOpened()?1:2));
218  capture_.set(CV_CAP_PROP_FRAME_HEIGHT, _height);
219  if(capture2_.isOpened())
220  {
221  capture2_.set(CV_CAP_PROP_FRAME_WIDTH, _width);
222  capture2_.set(CV_CAP_PROP_FRAME_HEIGHT, _height);
223  }
224  }
225  }
226  }
227 
229  {
230  UERROR("Parameter \"rectifyImages\" is set, but no stereo model is loaded or valid.");
231  return false;
232  }
233  return true;
234 }
235 
237 {
239 }
240 
241 std::string CameraStereoVideo::getSerial() const
242 {
243  return cameraName_;
244 }
245 
247 {
249 
250  cv::Mat img;
251  if(capture_.isOpened() && ((path2_.empty() && usbDevice2_ < 0) || capture2_.isOpened()))
252  {
253  cv::Mat leftImage;
254  cv::Mat rightImage;
255  if(path2_.empty() && usbDevice2_ < 0)
256  {
257  if(!capture_.read(img))
258  {
259  return data;
260  }
261  // Side by side stream
262  leftImage = cv::Mat(img, cv::Rect( 0, 0, img.size().width/2, img.size().height ));
263  rightImage = cv::Mat(img, cv::Rect( img.size().width/2, 0, img.size().width/2, img.size().height ));
264  }
265  else if(!capture_.read(leftImage) || !capture2_.read(rightImage))
266  {
267  return data;
268  }
269  else if(leftImage.cols != rightImage.cols || leftImage.rows != rightImage.rows)
270  {
271  UERROR("Left and right streams don't have image of the same size: left=%dx%d right=%dx%d",
272  leftImage.cols, leftImage.rows, rightImage.cols, rightImage.rows);
273  return data;
274  }
275 
276  // Rectification
277  bool rightCvt = false;
278  if(rightImage.type() != CV_8UC1)
279  {
280  cv::Mat tmp;
281  cv::cvtColor(rightImage, tmp, CV_BGR2GRAY);
282  rightImage = tmp;
283  rightCvt = true;
284  }
285 
287  {
288  leftImage = stereoModel_.left().rectifyImage(leftImage);
289  rightImage = stereoModel_.right().rectifyImage(rightImage);
290  }
291  else
292  {
293  leftImage = leftImage.clone();
294  if(!rightCvt)
295  {
296  rightImage = rightImage.clone();
297  }
298  }
299 
300  if(stereoModel_.left().imageHeight() == 0 || stereoModel_.left().imageWidth() == 0)
301  {
302  stereoModel_.setImageSize(leftImage.size());
303  }
304 
305  data = SensorData(leftImage, rightImage, stereoModel_, this->getNextSeqID(), UTimer::now());
306  }
307  else
308  {
309  ULOGGER_WARN("The camera must be initialized before requesting an image.");
310  }
311 
312  return data;
313 }
314 
315 
316 } // namespace rtabmap
int imageHeight() const
Definition: CameraModel.h:121
virtual SensorData captureImage(CameraInfo *info=0)
data
CameraStereoVideo(const std::string &pathSideBySide, bool rectifyImages=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
double fx() const
Definition: CameraModel.h:102
Some conversion functions.
virtual bool isCalibrated() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
CameraVideo::Source src_
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
virtual std::string getSerial() const
bool isValidForRectification() const
Definition: CameraModel.h:89
StereoCameraModel stereoModel_
const Transform & getLocalTransform() const
Definition: Camera.h:65
double cx() const
Definition: CameraModel.h:104
bool load(const std::string &directory, const std::string &cameraName, bool ignoreStereoTransform=true)
int getNextSeqID()
Definition: Camera.h:86
double cy() const
Definition: CameraModel.h:105
cv::Mat rectifyImage(const cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
#define UERROR(...)
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
#define UWARN(...)
static double now()
Definition: UTimer.cpp:80
void setLocalTransform(const Transform &transform)
void setImageSize(const cv::Size &size)
int imageWidth() const
Definition: CameraModel.h:120
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
std::string UTILITE_EXP uFormat(const char *fmt,...)
const CameraModel & right() const
const CameraModel & left() const
#define UINFO(...)


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