Visual Servoing Platform  version 3.5.1 under development (2023-03-14)
vpRealSense.h
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * RealSense SDK wrapper.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #ifndef _vpRealSense_h_
40 #define _vpRealSense_h_
41 
42 #include <map>
43 #include <stdint.h>
44 
45 #include <visp3/core/vpCameraParameters.h>
46 #include <visp3/core/vpColVector.h>
47 #include <visp3/core/vpConfig.h>
48 #include <visp3/core/vpException.h>
49 #include <visp3/core/vpHomogeneousMatrix.h>
50 #include <visp3/core/vpImage.h>
51 
52 #if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
53 
54 #include <librealsense/rs.hpp>
55 
56 #ifdef VISP_HAVE_PCL
57 #include <pcl/common/projection_matrix.h>
58 #include <pcl/point_types.h>
59 #endif
60 
334 class VISP_EXPORT vpRealSense
335 {
336 public:
337  vpRealSense();
338  virtual ~vpRealSense();
339 
340  void acquire(std::vector<vpColVector> &pointcloud);
341 #ifdef VISP_HAVE_PCL
342  void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
343  void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
344 #endif
345  void acquire(vpImage<unsigned char> &grey); // tested
346  void acquire(vpImage<unsigned char> &grey, std::vector<vpColVector> &pointcloud);
347  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
348  std::vector<vpColVector> &pointcloud);
349 #ifdef VISP_HAVE_PCL
350  void acquire(vpImage<unsigned char> &grey, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
351  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
352  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
353  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
354  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
355 #endif
356 
357  void acquire(vpImage<vpRGBa> &color); // tested
358  void acquire(vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
359  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
360  std::vector<vpColVector> &pointcloud);
361 
362  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
363  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
364  unsigned char *const data_infrared2 = NULL, const rs::stream &stream_color = rs::stream::color,
365  const rs::stream &stream_depth = rs::stream::depth,
366  const rs::stream &stream_infrared = rs::stream::infrared,
367  const rs::stream &stream_infrared2 = rs::stream::infrared2);
368 
369 #ifdef VISP_HAVE_PCL
370  void acquire(vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
371  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
372  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
373  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
374  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
375 
376  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
377  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
378  unsigned char *const data_infrared, unsigned char *const data_infrared2 = NULL,
379  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
380  const rs::stream &stream_infrared = rs::stream::infrared,
381  const rs::stream &stream_infrared2 = rs::stream::infrared2);
382  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
383  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
384  unsigned char *const data_infrared, unsigned char *const data_infrared2 = NULL,
385  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
386  const rs::stream &stream_infrared = rs::stream::infrared,
387  const rs::stream &stream_infrared2 = rs::stream::infrared2);
388 #endif
389 
390  void close();
391 
392  vpCameraParameters getCameraParameters(
393  const rs::stream &stream,
396  rs::device *getHandler() const { return m_device; }
397 
398  rs::extrinsics getExtrinsics(const rs::stream &from, const rs::stream &to) const;
399  rs::intrinsics getIntrinsics(const rs::stream &stream) const;
400 
404  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
405 
407  int getNumDevices() const { return m_context.get_device_count(); }
410  std::string getSerialNumber() const { return m_serial_no; }
411  vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const;
412 
413  void open();
414 
415  void setDeviceBySerialNumber(const std::string &serial_no);
416 
417  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense &rs);
418 
422  rs::format m_streamFormat;
424 
426  : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
427  {
428  }
429 
430  vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat,
431  const int streamFramerate)
432  : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
433  m_streamFramerate(streamFramerate)
434  {
435  }
436  };
437 
438  void setEnableStream(const rs::stream &stream, bool status);
439 
443  inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
444 
445  void setStreamSettings(const rs::stream &stream, const rs::preset &preset);
446  void setStreamSettings(const rs::stream &stream, const vpRsStreamParams &params);
447 
448 protected:
449  rs::context m_context;
450  rs::device *m_device;
452  std::string m_serial_no;
453  std::map<rs::stream, rs::intrinsics> m_intrinsics;
454  float m_max_Z;
455  std::map<rs::stream, bool> m_enableStreams;
456  std::map<rs::stream, bool> m_useStreamPresets;
457  std::map<rs::stream, rs::preset> m_streamPresets;
458  std::map<rs::stream, vpRsStreamParams> m_streamParams;
460 
461  void initStream();
462 };
463 
464 #endif
465 #endif
Generic class defining intrinsic camera parameters.
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::string m_serial_no
Definition: vpRealSense.h:452
int getNumDevices() const
Get number of devices that are detected.
Definition: vpRealSense.h:407
void setInvalidDepthValue(float value)
Definition: vpRealSense.h:443
std::map< rs::stream, bool > m_enableStreams
Definition: vpRealSense.h:455
rs::device * m_device
Definition: vpRealSense.h:450
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:396
float getInvalidDepthValue() const
Definition: vpRealSense.h:404
int m_num_devices
Definition: vpRealSense.h:451
std::map< rs::stream, bool > m_useStreamPresets
Definition: vpRealSense.h:456
std::string getSerialNumber() const
Definition: vpRealSense.h:410
std::map< rs::stream, rs::intrinsics > m_intrinsics
Definition: vpRealSense.h:453
rs::context m_context
Definition: vpRealSense.h:449
std::map< rs::stream, rs::preset > m_streamPresets
Definition: vpRealSense.h:457
float m_invalidDepthValue
Definition: vpRealSense.h:459
std::map< rs::stream, vpRsStreamParams > m_streamParams
Definition: vpRealSense.h:458
float m_max_Z
Maximal Z depth in meter.
Definition: vpRealSense.h:454
vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate)
Definition: vpRealSense.h:430