CameraStereoImages.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/UStl.h>
30 #include <opencv2/imgproc/types_c.h>
31 
32 namespace rtabmap
33 {
34 
36 {
37  return true;
38 }
39 
41  const std::string & pathLeftImages,
42  const std::string & pathRightImages,
43  bool rectifyImages,
44  float imageRate,
45  const Transform & localTransform) :
46  CameraImages(pathLeftImages, imageRate, localTransform),
47  camera2_(new CameraImages(pathRightImages))
48 {
49  this->setImagesRectified(rectifyImages);
50 }
51 
53  const std::string & pathLeftRightImages,
54  bool rectifyImages,
55  float imageRate,
56  const Transform & localTransform) :
57  CameraImages("", imageRate, localTransform),
58  camera2_(0)
59 {
60  std::vector<std::string> paths = uListToVector(uSplit(pathLeftRightImages, uStrContains(pathLeftRightImages, ":")?':':';'));
61  if(paths.size() >= 1)
62  {
63  this->setPath(paths[0]);
64  this->setImagesRectified(rectifyImages);
65 
66  if(paths.size() >= 2)
67  {
68  camera2_ = new CameraImages(paths[1]);
69  }
70  }
71  else
72  {
73  UERROR("The path is empty!");
74  }
75 }
76 
78 {
79  UDEBUG("");
80  delete camera2_;
81  UDEBUG("");
82 }
83 
84 bool CameraStereoImages::init(const std::string & calibrationFolder, const std::string & cameraName)
85 {
86  UINFO("Calibration folder: \"%s\", name=\"%s\"", calibrationFolder.c_str(), cameraName.c_str());
87 
88  // look for calibration files
89  if(!calibrationFolder.empty() && !cameraName.empty())
90  {
91  if(!stereoModel_.load(calibrationFolder, cameraName, false) && !stereoModel_.isValidForProjection())
92  {
93  UWARN("Missing calibration files for camera \"%s\" in \"%s\" folder, you should calibrate the camera!",
94  cameraName.c_str(), calibrationFolder.c_str());
95  }
96  else
97  {
98  UINFO("Stereo parameters: fx=%f cx=%f cy=%f baseline=%f",
99  stereoModel_.left().fx(),
100  stereoModel_.left().cx(),
101  stereoModel_.left().cy(),
103  }
104  }
105 
107  stereoModel_.setName(cameraName);
109  {
110  UWARN("Parameter \"rectifyImages\" is set, but no stereo model is loaded or valid for rectification. This can be ignored if input images are already rectified.");
111  }
112 
113  //desactivate before init as we will do it in this class instead for convenience
114  bool rectify = this->isImagesRectified();
115  this->setImagesRectified(false);
116 
117  bool success = false;
118  if(CameraImages::init())
119  {
120  if(camera2_)
121  {
123  if(camera2_->init())
124  {
125  if(this->imagesCount() == camera2_->imagesCount())
126  {
127  success = true;
128  }
129  else
130  {
131  UERROR("Cameras don't have the same number of images (%d vs %d)",
132  this->imagesCount(), camera2_->imagesCount());
133  }
134  }
135  else
136  {
137  UERROR("Cannot initialize the second camera.");
138  }
139  }
140  else
141  {
142  success = true;
143  }
144  }
145  this->setImagesRectified(rectify); // reset the flag
146  return success;
147 }
148 
150 {
152 }
153 
154 std::string CameraStereoImages::getSerial() const
155 {
156  return stereoModel_.name();
157 }
158 
160 {
162 
163  SensorData left, right;
164  left = CameraImages::captureImage(info);
165  if(!left.imageRaw().empty())
166  {
167  if(camera2_)
168  {
170  right = camera2_->takeImage(info);
171  }
172  else
173  {
174  right = this->takeImage(info);
175  }
176 
177  if(!right.imageRaw().empty())
178  {
179  // Rectification
180  cv::Mat leftImage = left.imageRaw();
181  cv::Mat rightImage = right.imageRaw();
182  if(rightImage.type() != CV_8UC1)
183  {
184  cv::Mat tmp;
185  cv::cvtColor(rightImage, tmp, CV_BGR2GRAY);
186  rightImage = tmp;
187  }
189  {
190  leftImage = stereoModel_.left().rectifyImage(leftImage);
191  rightImage = stereoModel_.right().rectifyImage(rightImage);
192  }
193 
194  if(stereoModel_.left().imageHeight() == 0 || stereoModel_.left().imageWidth() == 0)
195  {
196  stereoModel_.setImageSize(leftImage.size());
197  }
198 
199  data = SensorData(left.laserScanRaw(), leftImage, rightImage, stereoModel_, left.id()/(camera2_?1:2), left.stamp());
200  data.setGroundTruth(left.groundTruth());
201  }
202  }
203  return data;
204 }
205 
206 } // namespace rtabmap
void setPath(const std::string &dir)
Definition: CameraImages.h:63
int imageHeight() const
Definition: CameraModel.h:121
void setImagesRectified(bool enabled)
Definition: CameraImages.h:67
virtual SensorData captureImage(CameraInfo *info=0)
bool isImagesRectified() const
Definition: CameraImages.h:59
virtual std::string getSerial() const
virtual bool isCalibrated() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
data
virtual SensorData captureImage(CameraInfo *info=0)
double fx() const
Definition: CameraModel.h:102
bool uStrContains(const std::string &string, const std::string &substring)
Definition: UStl.h:787
const std::string & name() const
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:72
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:566
int id() const
Definition: SensorData.h:174
int getBayerMode() const
Definition: CameraImages.h:60
void setBayerMode(int mode)
Definition: CameraImages.h:68
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
CameraStereoImages(const std::string &pathLeftImages, const std::string &pathRightImages, bool rectifyImages=false, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
unsigned int imagesCount() const
const Transform & getLocalTransform() const
Definition: Camera.h:65
double cx() const
Definition: CameraModel.h:104
std::vector< V > uListToVector(const std::list< V > &list)
Definition: UStl.h:475
bool load(const std::string &directory, const std::string &cameraName, bool ignoreStereoTransform=true)
const Transform & groundTruth() const
Definition: SensorData.h:280
double cy() const
Definition: CameraModel.h:105
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
#define UDEBUG(...)
cv::Mat rectifyImage(const cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
#define UERROR(...)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
#define UWARN(...)
double stamp() const
Definition: SensorData.h:176
void setName(const std::string &name, const std::string &leftSuffix="left", const std::string &rightSuffix="right")
void setGroundTruth(const Transform &pose)
Definition: SensorData.h:279
void setLocalTransform(const Transform &transform)
void setImageSize(const cv::Size &size)
int imageWidth() const
Definition: CameraModel.h:120
const CameraModel & right() const
const CameraModel & left() const
#define UINFO(...)


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