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


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