tools/CameraRGBD/main.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 
30 #include "rtabmap/core/util2d.h"
31 #include "rtabmap/core/util3d.h"
34 #include "rtabmap/utilite/UMath.h"
35 #include "rtabmap/utilite/UFile.h"
38 #include <opencv2/highgui/highgui.hpp>
39 #include <opencv2/imgproc/imgproc.hpp>
40 #include <opencv2/imgproc/types_c.h>
41 #if CV_MAJOR_VERSION >= 3
42 #include <opencv2/videoio/videoio_c.h>
43 #endif
44 #include <pcl/visualization/cloud_viewer.h>
45 #include <stdio.h>
46 #include <signal.h>
47 
48 void showUsage()
49 {
50  printf("\nUsage:\n"
51  "rtabmap-rgbd_camera [options] driver\n"
52  " driver Driver number to use: 0=OpenNI-PCL (Kinect)\n"
53  " 1=OpenNI2 (Kinect and Xtion PRO Live)\n"
54  " 2=Freenect (Kinect)\n"
55  " 3=OpenNI-CV (Kinect)\n"
56  " 4=OpenNI-CV-ASUS (Xtion PRO Live)\n"
57  " 5=Freenect2 (Kinect v2)\n"
58  " 6=DC1394 (Bumblebee2)\n"
59  " 7=FlyCapture2 (Bumblebee2)\n"
60  " 8=ZED stereo\n"
61  " 9=RealSense\n"
62  " 10=Kinect for Windows 2 SDK\n"
63  " 11=RealSense2\n"
64  " 12=Kinect for Azure SDK\n"
65  " 13=MYNT EYE S\n"
66  " 14=ZED Open Capture\n"
67  " 15=depthai-core\n"
68  " 16=XVSDK (SeerSense)\n"
69  " Options:\n"
70  " -rate #.# Input rate Hz (default 0=inf)\n"
71  " -device # Device ID (number or string)\n"
72  " -save_stereo \"path\" Save stereo images in a folder or a video file (side by side *.avi).\n"
73  " -fourcc \"XXXX\" Four characters FourCC code (default is \"MJPG\") used\n"
74  " when saving stereo images to a video file.\n"
75  " See http://www.fourcc.org/codecs.php for more codes.\n");
76  exit(1);
77 }
78 
79 // catch ctrl-c
80 bool running = true;
81 void sighandler(int sig)
82 {
83  printf("\nSignal %d caught...\n", sig);
84  running = false;
85 }
86 
87 int main(int argc, char * argv[])
88 {
91  //ULogger::setPrintTime(false);
92  //ULogger::setPrintWhere(false);
93 
94  int driver = 0;
95  std::string stereoSavePath;
96  float rate = 0.0f;
97  std::string fourcc = "MJPG";
98  std::string deviceId;
99  if(argc < 2)
100  {
101  showUsage();
102  }
103  else
104  {
105  for(int i=1; i<argc; ++i)
106  {
107  if(strcmp(argv[i], "-rate") == 0)
108  {
109  ++i;
110  if(i < argc)
111  {
112  rate = uStr2Float(argv[i]);
113  if(rate < 0.0f)
114  {
115  showUsage();
116  }
117  }
118  else
119  {
120  showUsage();
121  }
122  continue;
123  }
124  if (strcmp(argv[i], "-device") == 0)
125  {
126  ++i;
127  if (i < argc)
128  {
129  deviceId = argv[i];
130  }
131  else
132  {
133  showUsage();
134  }
135  continue;
136  }
137  if(strcmp(argv[i], "-save_stereo") == 0)
138  {
139  ++i;
140  if(i < argc)
141  {
142  stereoSavePath = argv[i];
143  }
144  else
145  {
146  showUsage();
147  }
148  continue;
149  }
150  if(strcmp(argv[i], "-fourcc") == 0)
151  {
152  ++i;
153  if(i < argc)
154  {
155  fourcc = argv[i];
156  if(fourcc.size() != 4)
157  {
158  UERROR("fourcc should be 4 characters.");
159  showUsage();
160  }
161  }
162  else
163  {
164  showUsage();
165  }
166  continue;
167  }
168  if(strcmp(argv[i], "--help") == 0 || strcmp(argv[i], "-help") == 0)
169  {
170  showUsage();
171  }
172  else if(i< argc-1)
173  {
174  printf("Unrecognized option \"%s\"", argv[i]);
175  showUsage();
176  }
177 
178  // last
179  driver = atoi(argv[i]);
180  if(driver < 0 || driver > 15)
181  {
182  UERROR("driver should be between 0 and 15.");
183  showUsage();
184  }
185  }
186  }
187  UINFO("Using driver %d (device=%s)", driver, deviceId.empty()?"0": deviceId.c_str());
188 
189  rtabmap::Camera * camera = 0;
190  if(driver < 6)
191  {
192  if(!stereoSavePath.empty())
193  {
194  UWARN("-save_stereo option cannot be used with RGB-D drivers.");
195  stereoSavePath.clear();
196  }
197 
198  if(driver == 0)
199  {
200  camera = new rtabmap::CameraOpenni(deviceId);
201  }
202  else if(driver == 1)
203  {
205  {
206  UERROR("Not built with OpenNI2 support...");
207  exit(-1);
208  }
209  camera = new rtabmap::CameraOpenNI2(deviceId);
210  }
211  else if(driver == 2)
212  {
214  {
215  UERROR("Not built with Freenect support...");
216  exit(-1);
217  }
218  camera = new rtabmap::CameraFreenect(deviceId.empty()?0:uStr2Int(deviceId));
219  }
220  else if(driver == 3)
221  {
223  {
224  UERROR("Not built with OpenNI from OpenCV support...");
225  exit(-1);
226  }
227  camera = new rtabmap::CameraOpenNICV(false);
228  }
229  else if(driver == 4)
230  {
232  {
233  UERROR("Not built with OpenNI from OpenCV support...");
234  exit(-1);
235  }
236  camera = new rtabmap::CameraOpenNICV(true);
237  }
238  else if(driver == 5)
239  {
241  {
242  UERROR("Not built with Freenect2 support...");
243  exit(-1);
244  }
246  }
247  }
248  else if(driver == 6)
249  {
251  {
252  UERROR("Not built with DC1394 support...");
253  exit(-1);
254  }
256  }
257  else if(driver == 7)
258  {
260  {
261  UERROR("Not built with FlyCapture2/Triclops support...");
262  exit(-1);
263  }
265  }
266  else if(driver == 8)
267  {
269  {
270  UERROR("Not built with ZED sdk support...");
271  exit(-1);
272  }
273  camera = new rtabmap::CameraStereoZed(deviceId.empty()?0:uStr2Int(deviceId));
274  }
275  else if (driver == 9)
276  {
278  {
279  UERROR("Not built with RealSense support...");
280  exit(-1);
281  }
282  camera = new rtabmap::CameraRealSense(deviceId.empty()?0:uStr2Int(deviceId));
283  }
284  else if (driver == 10)
285  {
287  {
288  UERROR("Not built with Kinect for Windows 2 SDK support...");
289  exit(-1);
290  }
291  camera = new rtabmap::CameraK4W2(deviceId.empty()?0:uStr2Int(deviceId));
292  }
293  else if (driver == 11)
294  {
296  {
297  UERROR("Not built with RealSense2 SDK support...");
298  exit(-1);
299  }
300  camera = new rtabmap::CameraRealSense2(deviceId);
301  }
302  else if (driver == 12)
303  {
305  {
306  UERROR("Not built with Kinect for Azure SDK support...");
307  exit(-1);
308  }
309  camera = new rtabmap::CameraK4A(1);
310  }
311  else if (driver == 13)
312  {
314  {
315  UERROR("Not built with Mynt Eye S support...");
316  exit(-1);
317  }
318  camera = new rtabmap::CameraMyntEye(deviceId);
319  }
320  else if (driver == 14)
321  {
323  {
324  UERROR("Not built with Zed Open Capture support...");
325  exit(-1);
326  }
327  camera = new rtabmap::CameraStereoZedOC(deviceId.empty()?-1:uStr2Int(deviceId));
328  }
329  else if (driver == 15)
330  {
332  {
333  UERROR("Not built with depthai-core support...");
334  exit(-1);
335  }
336  camera = new rtabmap::CameraDepthAI(deviceId);
337  }
338  else if (driver == 16)
339  {
341  {
342  UERROR("Not built with XVisio SDK support...");
343  exit(-1);
344  }
346  }
347  else
348  {
349  UFATAL("");
350  }
351 
352  if(!camera->init())
353  {
354  printf("Camera init failed! Please select another driver (see \"--help\").\n");
355  delete camera;
356  exit(1);
357  }
358 
359  rtabmap::SensorData data = camera->takeData();
360  if (data.imageRaw().empty())
361  {
362  printf("Cloud not get frame from the camera!\n");
363  delete camera;
364  exit(1);
365  }
366  if(data.imageRaw().cols % data.depthOrRightRaw().cols != 0 || data.imageRaw().rows % data.depthOrRightRaw().rows != 0)
367  {
368  UWARN("RGB (%d/%d) and depth (%d/%d) frames are not the same size! The registered cloud cannot be shown.",
369  data.imageRaw().cols, data.imageRaw().rows, data.depthOrRightRaw().cols, data.depthOrRightRaw().rows);
370  }
371  pcl::visualization::CloudViewer * viewer = 0;
372  if((data.stereoCameraModels().empty() || data.stereoCameraModels()[0].isValidForProjection()) &&
373  (data.cameraModels().empty() || !data.cameraModels()[0].isValidForProjection()))
374  {
375  UWARN("Camera not calibrated! The registered cloud cannot be shown.");
376  }
377  else
378  {
379  viewer = new pcl::visualization::CloudViewer("cloud");
380  }
381 
382  cv::VideoWriter videoWriter;
383  UDirectory dir;
384  if(!stereoSavePath.empty() &&
385  !data.imageRaw().empty() &&
386  !data.rightRaw().empty())
387  {
388  if(UFile::getExtension(stereoSavePath).compare("avi") == 0)
389  {
390  if(data.imageRaw().size() == data.rightRaw().size())
391  {
392  if(rate <= 0)
393  {
394  UERROR("You should set the input rate when saving stereo images to a video file.");
395  showUsage();
396  }
397  cv::Size targetSize = data.imageRaw().size();
398  targetSize.width *= 2;
399  UASSERT(fourcc.size() == 4);
400  videoWriter.open(
401  stereoSavePath,
402  CV_FOURCC(fourcc.at(0), fourcc.at(1), fourcc.at(2), fourcc.at(3)),
403  rate,
404  targetSize,
405  data.imageRaw().channels() == 3);
406  }
407  else
408  {
409  UERROR("Images not the same size, cannot save stereo images to the video file.");
410  }
411  }
412  else if(UDirectory::exists(stereoSavePath))
413  {
414  UDirectory::makeDir(stereoSavePath+"/"+"left");
415  UDirectory::makeDir(stereoSavePath+"/"+"right");
416  }
417  else
418  {
419  UERROR("Directory \"%s\" doesn't exist.", stereoSavePath.c_str());
420  stereoSavePath.clear();
421  }
422  }
423 
424  // to catch the ctrl-c
425  signal(SIGABRT, &sighandler);
426  signal(SIGTERM, &sighandler);
427  signal(SIGINT, &sighandler);
428 
429  int id=1;
430  while(!data.imageRaw().empty() && (viewer==0 || !viewer->wasStopped()) && running)
431  {
432  cv::Mat rgb = data.imageRaw();
433  if(!data.depthRaw().empty() && (data.depthRaw().type() == CV_16UC1 || data.depthRaw().type() == CV_32FC1))
434  {
435  // depth
436  cv::Mat depth = data.depthRaw();
437  if(depth.type() == CV_32FC1)
438  {
439  depth = rtabmap::util2d::cvtDepthFromFloat(depth);
440  }
441 
442  if(!rgb.empty() && rgb.cols % depth.cols == 0 && rgb.rows % depth.rows == 0 &&
443  data.cameraModels().size() &&
444  data.cameraModels()[0].isValidForProjection())
445  {
446  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = rtabmap::util3d::cloudFromDepthRGB(
447  rgb, depth,
448  data.cameraModels()[0]);
449  cloud = rtabmap::util3d::transformPointCloud(cloud, rtabmap::Transform::opengl_T_rtabmap()*data.cameraModels()[0].localTransform());
450  if(viewer)
451  viewer->showCloud(cloud, "cloud");
452  }
453  else if(!depth.empty() &&
454  data.cameraModels().size() &&
455  data.cameraModels()[0].isValidForProjection())
456  {
457  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = rtabmap::util3d::cloudFromDepth(
458  depth,
459  data.cameraModels()[0]);
460  cloud = rtabmap::util3d::transformPointCloud(cloud, rtabmap::Transform::opengl_T_rtabmap()*data.cameraModels()[0].localTransform());
461  viewer->showCloud(cloud, "cloud");
462  }
463 
464  cv::Mat tmp;
465  unsigned short min=0, max = 2048;
466  uMinMax((unsigned short*)depth.data, depth.rows*depth.cols, min, max);
467  depth.convertTo(tmp, CV_8UC1, 255.0/max);
468 
469  cv::imshow("Video", rgb); // show frame
470  cv::imshow("Depth", tmp);
471  }
472  else if(!data.rightRaw().empty())
473  {
474  // stereo
475  cv::Mat right = data.rightRaw();
476  cv::imshow("Left", rgb); // show frame
477  cv::imshow("Right", right);
478 
479  if(rgb.cols == right.cols && rgb.rows == right.rows && data.stereoCameraModels().size()==1 && data.stereoCameraModels()[0].isValidForProjection())
480  {
481  if(right.channels() == 3)
482  {
483  cv::cvtColor(right, right, CV_BGR2GRAY);
484  }
485  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = rtabmap::util3d::cloudFromStereoImages(
486  rgb, right,
487  data.stereoCameraModels()[0]);
488  cloud = rtabmap::util3d::transformPointCloud(cloud, rtabmap::Transform::opengl_T_rtabmap()*data.stereoCameraModels()[0].localTransform());
489  if(viewer)
490  viewer->showCloud(cloud, "cloud");
491  }
492  }
493 
494  int c = cv::waitKey(10); // wait 10 ms or for key stroke
495  if(c == 27)
496  break; // if ESC, break and quit
497 
498  if(videoWriter.isOpened())
499  {
500  cv::Mat left = data.imageRaw();
501  cv::Mat right = data.rightRaw();
502  if(left.size() == right.size())
503  {
504  cv::Size targetSize = left.size();
505  targetSize.width *= 2;
506  cv::Mat targetImage(targetSize, left.type());
507  if(right.type() != left.type())
508  {
509  cv::Mat tmp;
510  cv::cvtColor(right, tmp, left.channels()==3?CV_GRAY2BGR:CV_BGR2GRAY);
511  right = tmp;
512  }
513  UASSERT(left.type() == right.type());
514 
515  cv::Mat roiA(targetImage, cv::Rect( 0, 0, left.size().width, left.size().height ));
516  left.copyTo(roiA);
517  cv::Mat roiB( targetImage, cvRect( left.size().width, 0, left.size().width, left.size().height ) );
518  right.copyTo(roiB);
519 
520  videoWriter.write(targetImage);
521  printf("Saved frame %d to \"%s\"\n", id, stereoSavePath.c_str());
522  }
523  else
524  {
525  UERROR("Left and right images are not the same size!?");
526  }
527  }
528  else if(!stereoSavePath.empty())
529  {
530  cv::imwrite(stereoSavePath+"/"+"left/"+uNumber2Str(id) + ".jpg", data.imageRaw());
531  cv::imwrite(stereoSavePath+"/"+"right/"+uNumber2Str(id) + ".jpg", data.rightRaw());
532  printf("Saved frames %d to \"%s/left\" and \"%s/right\" directories\n", id, stereoSavePath.c_str(), stereoSavePath.c_str());
533  }
534  ++id;
535  data = camera->takeData();
536  }
537  printf("Closing...\n");
538  if(viewer)
539  {
540  delete viewer;
541  }
542  cv::destroyWindow("Video");
543  cv::destroyWindow("Depth");
544  delete camera;
545  return 0;
546 }
rtabmap::SensorData
Definition: SensorData.h:51
glm::min
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
rtabmap::util3d::cloudFromDepthRGB
RTABMAP_DEPRECATED pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudFromDepthRGB(const cv::Mat &imageRgb, const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
Definition: util3d.cpp:416
compare
bool compare
UINFO
#define UINFO(...)
rtabmap::CameraDepthAI
Definition: CameraDepthAI.h:44
rtabmap::CameraStereoFlyCapture2::available
static bool available()
Definition: CameraStereoFlyCapture2.cpp:68
UDirectory::makeDir
static bool makeDir(const std::string &dirPath)
Definition: UDirectory.cpp:333
rtabmap::CameraFreenect::available
static bool available()
Definition: CameraFreenect.cpp:284
rtabmap::CameraRealSense::available
static bool available()
Definition: CameraRealSense.cpp:47
rtabmap::CameraStereoDC1394::available
static bool available()
Definition: CameraStereoDC1394.cpp:317
rtabmap::CameraK4W2::available
static bool available()
Definition: CameraK4W2.cpp:53
rtabmap::util3d::cloudFromStereoImages
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT cloudFromStereoImages(const cv::Mat &imageLeft, const cv::Mat &imageRight, const StereoCameraModel &model, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &parameters=ParametersMap())
Definition: util3d.cpp:814
c
Scalar Scalar * c
UDirectory.h
ULogger::kTypeConsole
@ kTypeConsole
Definition: ULogger.h:244
rtabmap::Transform::opengl_T_rtabmap
static Transform opengl_T_rtabmap()
Definition: Transform.h:149
ULogger::setLevel
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
sighandler
void sighandler(int sig)
Definition: tools/CameraRGBD/main.cpp:81
rtabmap::CameraMyntEye
Definition: CameraMyntEye.h:47
CameraRGBD.h
CameraStereo.h
util3d.h
rtabmap::CameraStereoZedOC::available
static bool available()
Definition: CameraStereoZedOC.cpp:499
rtabmap::CameraFreenect2::available
static bool available()
Definition: CameraFreenect2.cpp:45
UMath.h
Basic mathematics functions.
rtabmap::CameraK4A
Definition: CameraK4A.h:43
rtabmap::CameraFreenect
Definition: CameraFreenect.h:44
UFATAL
#define UFATAL(...)
rtabmap::util3d::transformPointCloud
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
Definition: util3d_transforms.cpp:107
data
int data[]
rtabmap::CameraFreenect2
Definition: CameraFreenect2.h:46
util3d_transforms.h
rtabmap::CameraOpenNI2
Definition: CameraOpenNI2.h:42
uNumber2Str
std::string UTILITE_EXPORT uNumber2Str(unsigned int number)
Definition: UConversion.cpp:91
rtabmap::CameraDepthAI::available
static bool available()
Definition: CameraDepthAI.cpp:39
rtabmap::CameraSeerSense::available
static bool available()
Definition: CameraSeerSense.cpp:6
UConversion.h
Some conversion functions.
rtabmap::CameraRealSense2
Definition: CameraRealSense2.h:54
UFile::getExtension
std::string getExtension()
Definition: UFile.h:140
rtabmap::CameraFreenect2::kTypeColor2DepthSD
@ kTypeColor2DepthSD
Definition: CameraFreenect2.h:53
rtabmap::CameraStereoZedOC
Definition: CameraStereoZedOC.h:47
main
int main(int argc, char *argv[])
Definition: tools/CameraRGBD/main.cpp:87
glm::max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
ULogger::kInfo
@ kInfo
Definition: ULogger.h:252
UASSERT
#define UASSERT(condition)
rtabmap_netvlad.argv
argv
Definition: rtabmap_netvlad.py:15
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
rtabmap::CameraStereoZed::available
static bool available()
Definition: CameraStereoZed.cpp:235
rtabmap::Camera
Definition: Camera.h:43
UWARN
#define UWARN(...)
rtabmap::CameraOpenNICV
Definition: CameraOpenNICV.h:36
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
rtabmap::CameraStereoDC1394
Definition: CameraStereoDC1394.h:39
ULogger.h
ULogger class and convenient macros.
uMinMax
void uMinMax(const T *v, unsigned int size, T &min, T &max, unsigned int &indexMin, unsigned int &indexMax)
Definition: UMath.h:224
rtabmap::CameraStereoZed
Definition: CameraStereoZed.h:43
rtabmap::CameraOpenNICV::available
static bool available()
Definition: CameraOpenNICV.cpp:36
util2d.h
rtabmap::util2d::cvtDepthFromFloat
cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat &depth32F)
Definition: util2d.cpp:892
UDirectory::exists
static bool exists(const std::string &dirPath)
Definition: UDirectory.cpp:249
rtabmap::CameraMyntEye::available
static bool available()
Definition: CameraMyntEye.cpp:506
uStr2Int
int UTILITE_EXPORT uStr2Int(const std::string &str)
Definition: UConversion.cpp:125
rtabmap::CameraStereoFlyCapture2
Definition: CameraStereoFlyCapture2.h:41
rtabmap::CameraRealSense2::available
static bool available()
Definition: CameraRealSense2.cpp:45
rtabmap::CameraK4A::available
static bool available()
Definition: CameraK4A.cpp:42
camera
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
id
id
showUsage
void showUsage()
Definition: tools/CameraRGBD/main.cpp:48
rtabmap::CameraRealSense
Definition: CameraRealSense.h:49
rtabmap::CameraOpenNI2::available
static bool available()
Definition: CameraOpenNI2.cpp:42
rtabmap::util3d::cloudFromDepth
RTABMAP_DEPRECATED pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT cloudFromDepth(const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0)
Definition: util3d.cpp:266
uStr2Float
float UTILITE_EXPORT uStr2Float(const std::string &str)
Definition: UConversion.cpp:138
UFile.h
UDirectory
Definition: UDirectory.h:34
UERROR
#define UERROR(...)
i
int i
rtabmap::CameraOpenni
Definition: CameraOpenni.h:55
rtabmap::CameraK4W2
Definition: CameraK4W2.h:44
rtabmap::CameraSeerSense
Definition: CameraSeerSense.h:14
running
bool running
Definition: tools/CameraRGBD/main.cpp:80


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:12