CameraMobile.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 
28 #include "CameraMobile.h"
29 #include "util.h"
33 #include "rtabmap/core/util2d.h"
34 #include <glm/gtx/transform.hpp>
35 
36 namespace rtabmap {
37 
38 #define nullptr 0
39 
41 // CameraMobile
44 const float CameraMobile::bilateralFilteringSigmaR = 0.075f;
45 
47  0.0f, 0.0f, 1.0f, 0.0f,
48  -1.0f, 0.0f, 0.0f, 0.0f,
49  0.0f, -1.0f, 0.0f, 0.0f);
51  0.0f, -1.0f, 0.0f, 0.0f,
52  0.0f, 0.0f, -1.0f, 0.0f,
53  1.0f, 0.0f, 0.0f, 0.0f);
54 
55 CameraMobile::CameraMobile(bool smoothing) :
56  Camera(10),
57  deviceTColorCamera_(Transform::getIdentity()),
58  spinOncePreviousStamp_(0.0),
59  textureId_(0),
60  uvs_initialized_(false),
61  previousStamp_(0.0),
62  stampEpochOffset_(0.0),
63  smoothing_(smoothing),
64  colorCameraToDisplayRotation_(ROTATION_0),
65  originUpdate_(false)
66 {
67 }
68 
70  // Disconnect camera service
71  close();
72 }
73 
74 bool CameraMobile::init(const std::string &, const std::string &)
75 {
77  return true;
78 }
79 
81 {
83  previousStamp_ = 0.0;
84  lastKnownGPS_ = GPS();
85  lastEnvSensors_.clear();
87  originUpdate_ = false;
88  pose_ = Transform();
89  data_ = SensorData();
90 
91  if(textureId_ != 0)
92  {
93  glDeleteTextures(1, &textureId_);
94  textureId_ = 0;
95  }
96 }
97 
99 {
101  previousStamp_ = 0.0;
102  lastKnownGPS_ = GPS();
103  lastEnvSensors_.clear();
104  pose_ = Transform();
105  data_ = SensorData();
106  originUpdate_ = true;
107 }
108 
110 {
111  if(!pose.isNull())
112  {
113  // send pose of the camera (without optical rotation)
115  if(originUpdate_)
116  {
118  originUpdate_ = false;
119  }
120 
121  if(!originOffset_.isNull())
122  {
123  this->post(new PoseEvent(originOffset_*p));
124  }
125  else
126  {
127  this->post(new PoseEvent(p));
128  }
129  }
130 }
131 
133 {
134  return model_.isValidForProjection();
135 }
136 
137 void CameraMobile::setGPS(const GPS & gps)
138 {
139  lastKnownGPS_ = gps;
140 }
141 
142 void CameraMobile::setData(const SensorData & data, const Transform & pose, const glm::mat4 & viewMatrix, const glm::mat4 & projectionMatrix, const float * texCoord)
143 {
144  LOGD("CameraMobile::setData pose=%s stamp=%f", pose.prettyPrint().c_str(), data.stamp());
145  data_ = data;
146  pose_ = pose;
147 
148  viewMatrix_ = viewMatrix;
149  projectionMatrix_ = projectionMatrix;
150 
151  // adjust origin
152  if(!originOffset_.isNull())
153  {
156  }
157 
158  if(textureId_ == 0)
159  {
160  glGenTextures(1, &textureId_);
161  }
162 
163  if(texCoord)
164  {
165  memcpy(transformed_uvs_, texCoord, 8*sizeof(float));
166  uvs_initialized_ = true;
167  }
168 
169  LOGD("CameraMobile::setData textureId_=%d", (int)textureId_);
170 
171  if(textureId_ != 0 && texCoord != 0)
172  {
173  cv::Mat rgbImage;
174  cv::cvtColor(data.imageRaw(), rgbImage, cv::COLOR_BGR2RGBA);
175 
176  glBindTexture(GL_TEXTURE_2D, textureId_);
177  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
178  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
179  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
180  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
181 
182  glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
183  //glPixelStorei(GL_UNPACK_ROW_LENGTH, 0);
184  //glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0);
185  //glPixelStorei(GL_UNPACK_SKIP_ROWS, 0);
186  glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, rgbImage.cols, rgbImage.rows, 0, GL_RGBA, GL_UNSIGNED_BYTE, rgbImage.data);
187 
188  GLint error = glGetError();
189  if(error != GL_NO_ERROR)
190  {
191  LOGE("OpenGL: Could not allocate texture (0x%x)\n", error);
192  textureId_ = 0;
193  return;
194  }
195  }
196 }
197 
198 void CameraMobile::addEnvSensor(int type, float value)
199 {
200  lastEnvSensors_.insert(std::make_pair((EnvSensor::Type)type, EnvSensor((EnvSensor::Type)type, value)));
201 }
202 
204 {
205  if(!this->isRunning())
206  {
207  bool ignoreFrame = false;
208  //float rate = 10.0f; // maximum 10 FPS for image data
209  double now = UTimer::now();
210  /*if(rate>0.0f)
211  {
212  if((spinOncePreviousStamp_>=0.0 && now>spinOncePreviousStamp_ && now - spinOncePreviousStamp_ < 1.0f/rate) ||
213  ((spinOncePreviousStamp_<=0.0 || now<=spinOncePreviousStamp_) && spinOnceFrameRateTimer_.getElapsedTime() < 1.0f/rate))
214  {
215  ignoreFrame = true;
216  }
217  }*/
218 
219  if(!ignoreFrame)
220  {
223  mainLoop();
224  }
225  else
226  {
227  // just send pose
228  capturePoseOnly();
229  }
230  }
231 }
232 
234 {
235  double t = cameraStartedTime_.elapsed();
236  if(t < 5.0)
237  {
238  uSleep((5.0-t)*1000); // just to make sure that the camera is started
239  }
240 }
241 
243 {
244  CameraInfo info;
245  SensorData data = this->captureImage(&info);
246 
247  if(data.isValid() && !info.odomPose.isNull())
248  {
249  if(lastKnownGPS_.stamp() > 0.0 && data.stamp()-lastKnownGPS_.stamp()<1.0)
250  {
251  data.setGPS(lastKnownGPS_);
252  }
253  else if(lastKnownGPS_.stamp()>0.0)
254  {
255  LOGD("GPS too old (current time=%f, gps time = %f)", data.stamp(), lastKnownGPS_.stamp());
256  }
257 
258  if(lastEnvSensors_.size())
259  {
261  lastEnvSensors_.clear();
262  }
263 
264  if(smoothing_ && !data.depthRaw().empty())
265  {
266  //UTimer t;
268  //LOGD("Bilateral filtering, time=%fs", t.ticks());
269  }
270 
271  // Rotate image depending on the camera orientation
273  {
274  UDEBUG("ROTATION_90");
275  cv::Mat rgb, depth;
276  cv::Mat rgbt(data.imageRaw().cols, data.imageRaw().rows, data.imageRaw().type());
277  cv::flip(data.imageRaw(),rgb,1);
278  cv::transpose(rgb,rgbt);
279  rgb = rgbt;
280  cv::Mat deptht(data.depthRaw().cols, data.depthRaw().rows, data.depthRaw().type());
281  cv::flip(data.depthRaw(),depth,1);
282  cv::transpose(depth,deptht);
283  depth = deptht;
284  CameraModel model = data.cameraModels()[0];
285  cv::Size sizet(model.imageHeight(), model.imageWidth());
286  model = CameraModel(
287  model.fy(),
288  model.fx(),
289  model.cy(),
290  model.cx()>0?model.imageWidth()-model.cx():0,
291  model.localTransform()*rtabmap::Transform(0,-1,0,0, 1,0,0,0, 0,0,1,0));
292  model.setImageSize(sizet);
293  data.setRGBDImage(rgb, depth, model);
294 
295  std::vector<cv::KeyPoint> keypoints = data.keypoints();
296  for(size_t i=0; i<keypoints.size(); ++i)
297  {
298  keypoints[i].pt.x = data.keypoints()[i].pt.y;
299  keypoints[i].pt.y = rgb.rows - data.keypoints()[i].pt.x;
300  }
301  data.setFeatures(keypoints, data.keypoints3D(), cv::Mat());
302  }
304  {
305  UDEBUG("ROTATION_180");
306  cv::Mat rgb, depth;
307  cv::flip(data.imageRaw(),rgb,1);
308  cv::flip(rgb,rgb,0);
309  cv::flip(data.depthOrRightRaw(),depth,1);
310  cv::flip(depth,depth,0);
311  CameraModel model = data.cameraModels()[0];
312  cv::Size sizet(model.imageWidth(), model.imageHeight());
313  model = CameraModel(
314  model.fx(),
315  model.fy(),
316  model.cx()>0?model.imageWidth()-model.cx():0,
317  model.cy()>0?model.imageHeight()-model.cy():0,
318  model.localTransform()*rtabmap::Transform(0,0,0,0,0,1,0));
319  model.setImageSize(sizet);
320  data.setRGBDImage(rgb, depth, model);
321 
322  std::vector<cv::KeyPoint> keypoints = data.keypoints();
323  for(size_t i=0; i<keypoints.size(); ++i)
324  {
325  keypoints[i].pt.x = rgb.cols - data.keypoints()[i].pt.x;
326  keypoints[i].pt.y = rgb.rows - data.keypoints()[i].pt.y;
327  }
328  data.setFeatures(keypoints, data.keypoints3D(), cv::Mat());
329  }
331  {
332  UDEBUG("ROTATION_270");
333  cv::Mat rgb(data.imageRaw().cols, data.imageRaw().rows, data.imageRaw().type());
334  cv::transpose(data.imageRaw(),rgb);
335  cv::flip(rgb,rgb,1);
336  cv::Mat depth(data.depthOrRightRaw().cols, data.depthOrRightRaw().rows, data.depthOrRightRaw().type());
337  cv::transpose(data.depthOrRightRaw(),depth);
338  cv::flip(depth,depth,1);
339  CameraModel model = data.cameraModels()[0];
340  cv::Size sizet(model.imageHeight(), model.imageWidth());
341  model = CameraModel(
342  model.fy(),
343  model.fx(),
344  model.cy()>0?model.imageHeight()-model.cy():0,
345  model.cx(),
346  model.localTransform()*rtabmap::Transform(0,1,0,0, -1,0,0,0, 0,0,1,0));
347  model.setImageSize(sizet);
348  data.setRGBDImage(rgb, depth, model);
349 
350  std::vector<cv::KeyPoint> keypoints = data.keypoints();
351  for(size_t i=0; i<keypoints.size(); ++i)
352  {
353  keypoints[i].pt.x = rgb.cols - data.keypoints()[i].pt.y;
354  keypoints[i].pt.y = data.keypoints()[i].pt.x;
355  }
356  data.setFeatures(keypoints, data.keypoints3D(), cv::Mat());
357  }
358 
359  rtabmap::Transform pose = info.odomPose;
360  data.setGroundTruth(Transform());
361 
362  // convert stamp to epoch
363  bool firstFrame = previousPose_.isNull();
364  if(firstFrame)
365  {
367  }
368  data.setStamp(stampEpochOffset_ + data.stamp());
369  OdometryInfo info;
370  if(!firstFrame)
371  {
372  info.interval = data.stamp()-previousStamp_;
373  info.transform = previousPose_.inverse() * pose;
374  }
375  // linear cov = 0.0001
376  info.reg.covariance = cv::Mat::eye(6,6,CV_64FC1) * (firstFrame?9999.0:0.0001);
377  if(!firstFrame)
378  {
379  // angular cov = 0.000001
380  info.reg.covariance.at<double>(3,3) *= 0.01;
381  info.reg.covariance.at<double>(4,4) *= 0.01;
382  info.reg.covariance.at<double>(5,5) *= 0.01;
383  }
384  LOGI("Publish odometry message (variance=%f)", firstFrame?9999:0.0001);
385  this->post(new OdometryEvent(data, pose, info));
386  previousPose_ = pose;
387  previousStamp_ = data.stamp();
388  }
389  else if(!this->isKilled() && info.odomPose.isNull())
390  {
391  LOGW("Odometry lost");
392  this->post(new OdometryEvent());
393  }
394 }
395 
397 {
398  if(info)
399  {
400  info->odomPose = pose_;
401  }
402  return data_;
403 }
404 
406  const cv::Mat & pointCloudData,
407  int points,
408  const Transform & pose,
409  const CameraModel & model,
410  const cv::Mat & rgb,
411  std::vector<cv::KeyPoint> * kpts,
412  std::vector<cv::Point3f> * kpts3D,
413  int kptsSize)
414 {
415  if(!pointCloudData.empty())
416  {
417  cv::Mat scanData(1, pointCloudData.cols, CV_32FC4);
418  float * ptr = scanData.ptr<float>();
419  const float * inPtr = pointCloudData.ptr<float>();
420  int ic = pointCloudData.channels();
421  UASSERT(pointCloudData.depth() == CV_32F && ic >= 3);
422 
423  int oi = 0;
424  for(unsigned int i=0;i<points; ++i)
425  {
426  cv::Point3f pt(inPtr[i*ic], inPtr[i*ic + 1], inPtr[i*ic + 2]);
428  ptr[oi*4] = pt.x;
429  ptr[oi*4 + 1] = pt.y;
430  ptr[oi*4 + 2] = pt.z;
431 
432  //get color from rgb image
433  cv::Point3f org= pt;
435  int u,v;
436  model.reproject(pt.x, pt.y, pt.z, u, v);
437  unsigned char r=255,g=255,b=255;
438  if(model.inFrame(u, v))
439  {
440  b=rgb.at<cv::Vec3b>(v,u).val[0];
441  g=rgb.at<cv::Vec3b>(v,u).val[1];
442  r=rgb.at<cv::Vec3b>(v,u).val[2];
443  if(kpts)
444  kpts->push_back(cv::KeyPoint(u,v,kptsSize));
445  if(kpts3D)
446  kpts3D->push_back(org);
447 
448  *(int*)&ptr[oi*4 + 3] = int(b) | (int(g) << 8) | (int(r) << 16);
449  ++oi;
450  }
451 
452  //confidence
453  //*(int*)&ptr[i*4 + 3] = (int(pointCloudData[i*4 + 3] * 255.0f) << 8) | (int(255) << 16);
454 
455  }
456  return LaserScan::backwardCompatibility(scanData.colRange(0, oi), 0, 10, rtabmap::Transform::getIdentity());
457  }
458  return LaserScan();
459 }
460 
461 } /* namespace rtabmap */
glm::mat4 glmFromTransform(const rtabmap::Transform &transform)
Definition: util.h:124
virtual bool isCalibrated() const
void setImageSize(const cv::Size &size)
int imageHeight() const
Definition: CameraModel.h:121
0 degree rotation (natural orientation)
Definition: util.h:199
const double & stamp() const
Definition: GPS.h:59
#define LOGW(...)
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
void addEnvSensor(int type, float value)
const std::vector< cv::Point3f > & keypoints3D() const
Definition: SensorData.h:271
virtual SensorData captureImage(CameraInfo *info=0)
double elapsed()
Definition: UTimer.h:75
ScreenRotation colorCameraToDisplayRotation_
Definition: CameraMobile.h:149
static LaserScan scanFromPointCloudData(const cv::Mat &pointCloudData, int points, const Transform &pose, const CameraModel &model, const cv::Mat &rgb, std::vector< cv::KeyPoint > *kpts=0, std::vector< cv::Point3f > *kpts3D=0, int kptsSize=3)
static Transform getIdentity()
Definition: Transform.cpp:401
virtual void mainLoop()
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
data
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:227
static const rtabmap::Transform rtabmap_world_T_opengl_world(0.0f, 0.0f,-1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f)
const std::vector< cv::KeyPoint > & keypoints() const
Definition: SensorData.h:270
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Definition: util2d.cpp:1814
void setGPS(const GPS &gps)
Definition: SensorData.h:286
void reproject(float x, float y, float z, float &u, float &v) const
#define LOGE(...)
void poseReceived(const Transform &pose)
void post(UEvent *event, bool async=true) const
bool isRunning() const
Definition: UThread.cpp:245
#define UASSERT(condition)
#define LOGD(...)
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:236
virtual void mainLoopBegin()
Transform deviceTColorCamera_
Definition: CameraMobile.h:133
cv::Mat depthRaw() const
Definition: SensorData.h:210
CameraMobile(bool smoothing=false)
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
std::string prettyPrint() const
Definition: Transform.cpp:316
EnvSensors lastEnvSensors_
Definition: CameraMobile.h:151
static const rtabmap::Transform opengl_world_T_rtabmap_world(0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f)
270 degree rotation.
Definition: util.h:208
static const float bilateralFilteringSigmaS
Definition: CameraMobile.h:73
void start()
Definition: UTimer.cpp:87
virtual void capturePoseOnly()
Definition: CameraMobile.h:126
180 degree rotation.
Definition: util.h:205
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
void setEnvSensors(const EnvSensors &sensors)
Definition: SensorData.h:292
#define LOGI(...)
bool isNull() const
Definition: Transform.cpp:107
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
#define UDEBUG(...)
static const rtabmap::Transform opticalRotation
Definition: CameraMobile.h:76
static const float bilateralFilteringSigmaR
Definition: CameraMobile.h:74
90 degree rotation.
Definition: util.h:202
ULogger class and convenient macros.
double stamp() const
Definition: SensorData.h:176
static double now()
Definition: UTimer.cpp:80
void setStamp(double stamp)
Definition: SensorData.h:177
model
Definition: trace.py:4
RegistrationInfo reg
Definition: OdometryInfo.h:97
void setGroundTruth(const Transform &pose)
Definition: SensorData.h:279
int imageWidth() const
Definition: CameraModel.h:120
static const rtabmap::Transform opticalRotationInv
Definition: CameraMobile.h:77
bool inFrame(int u, int v) const
bool isKilled() const
Definition: UThread.cpp:255
virtual void close()
bool isValid() const
Definition: SensorData.h:156
Transform odomPose
Definition: CameraInfo.h:69
static LaserScan backwardCompatibility(const cv::Mat &oldScanFormat, int maxPoints=0, int maxRange=0, const Transform &localTransform=Transform::getIdentity())
Definition: LaserScan.cpp:125
bool isValidForProjection() const
Definition: CameraModel.h:87
Transform translation() const
Definition: Transform.cpp:203
glm::mat4 projectionMatrix_
Definition: CameraMobile.h:139
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
Definition: SensorData.cpp:801
void setData(const SensorData &data, const Transform &pose, const glm::mat4 &viewMatrix, const glm::mat4 &projectionMatrix, const float *texCoord)
void setGPS(const GPS &gps)
Transform inverse() const
Definition: Transform.cpp:178
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)


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