Visual Servoing Platform  version 3.6.1 under development (2024-12-03)
vpRealSense.h
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 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 https://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 *****************************************************************************/
35 
36 #ifndef _vpRealSense_h_
37 #define _vpRealSense_h_
38 
39 #include <map>
40 #include <stdint.h>
41 
42 #include <visp3/core/vpCameraParameters.h>
43 #include <visp3/core/vpColVector.h>
44 #include <visp3/core/vpConfig.h>
45 #include <visp3/core/vpException.h>
46 #include <visp3/core/vpHomogeneousMatrix.h>
47 #include <visp3/core/vpImage.h>
48 
49 #if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
50 
51 #include <librealsense/rs.hpp>
52 
53 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
54 #include <pcl/common/projection_matrix.h>
55 #include <pcl/point_types.h>
56 #endif
57 
58 BEGIN_VISP_NAMESPACE
360 class VISP_EXPORT vpRealSense
361 {
362 public:
363  vpRealSense();
364  virtual ~vpRealSense();
365 
366  void acquire(std::vector<vpColVector> &pointcloud);
367 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
368  void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
369  void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
370 #endif
371  void acquire(vpImage<unsigned char> &grey); // tested
372  void acquire(vpImage<unsigned char> &grey, std::vector<vpColVector> &pointcloud);
373  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
374  std::vector<vpColVector> &pointcloud);
375 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
376  void acquire(vpImage<unsigned char> &grey, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
377  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
378  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
379  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
380  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
381 #endif
382 
383  void acquire(vpImage<vpRGBa> &color); // tested
384  void acquire(vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
385  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
386  std::vector<vpColVector> &pointcloud);
387 
388  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
389  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
390  unsigned char *const data_infrared2 = nullptr, const rs::stream &stream_color = rs::stream::color,
391  const rs::stream &stream_depth = rs::stream::depth,
392  const rs::stream &stream_infrared = rs::stream::infrared,
393  const rs::stream &stream_infrared2 = rs::stream::infrared2);
394 
395 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
396  void acquire(vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
397  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
398  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
399  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
400  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
401 
402  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
403  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
404  unsigned char *const data_infrared, unsigned char *const data_infrared2 = nullptr,
405  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
406  const rs::stream &stream_infrared = rs::stream::infrared,
407  const rs::stream &stream_infrared2 = rs::stream::infrared2);
408  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
409  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
410  unsigned char *const data_infrared, unsigned char *const data_infrared2 = nullptr,
411  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
412  const rs::stream &stream_infrared = rs::stream::infrared,
413  const rs::stream &stream_infrared2 = rs::stream::infrared2);
414 #endif
415 
416  void close();
417 
418  vpCameraParameters getCameraParameters(
419  const rs::stream &stream,
422  rs::device *getHandler() const { return m_device; }
423 
424  rs::extrinsics getExtrinsics(const rs::stream &from, const rs::stream &to) const;
425  rs::intrinsics getIntrinsics(const rs::stream &stream) const;
426 
430  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
431 
433  int getNumDevices() const { return m_context.get_device_count(); }
436  std::string getSerialNumber() const { return m_serial_no; }
437  vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const;
438 
439  void open();
440 
441  void setDeviceBySerialNumber(const std::string &serial_no);
442 
443  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense &rs);
444 
446  {
449  rs::format m_streamFormat;
451 
453  : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
454  { }
455 
456  vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat,
457  const int streamFramerate)
458  : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
459  m_streamFramerate(streamFramerate)
460  { }
461  };
462 
463  void setEnableStream(const rs::stream &stream, bool status);
464 
468  inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
469 
470  void setStreamSettings(const rs::stream &stream, const rs::preset &preset);
471  void setStreamSettings(const rs::stream &stream, const vpRsStreamParams &params);
472 
473 protected:
474  rs::context m_context;
475  rs::device *m_device;
477  std::string m_serial_no;
478  std::map<rs::stream, rs::intrinsics> m_intrinsics;
479  float m_max_Z;
480  std::map<rs::stream, bool> m_enableStreams;
481  std::map<rs::stream, bool> m_useStreamPresets;
482  std::map<rs::stream, rs::preset> m_streamPresets;
483  std::map<rs::stream, vpRsStreamParams> m_streamParams;
485 
486  void initStream();
487 };
488 END_VISP_NAMESPACE
489 #endif
490 #endif
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::string m_serial_no
Definition: vpRealSense.h:477
int getNumDevices() const
Get number of devices that are detected.
Definition: vpRealSense.h:433
void setInvalidDepthValue(float value)
Definition: vpRealSense.h:468
std::map< rs::stream, bool > m_enableStreams
Definition: vpRealSense.h:480
rs::device * m_device
Definition: vpRealSense.h:475
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:422
float getInvalidDepthValue() const
Definition: vpRealSense.h:430
int m_num_devices
Definition: vpRealSense.h:476
std::map< rs::stream, bool > m_useStreamPresets
Definition: vpRealSense.h:481
std::string getSerialNumber() const
Definition: vpRealSense.h:436
std::map< rs::stream, rs::intrinsics > m_intrinsics
Definition: vpRealSense.h:478
rs::context m_context
Definition: vpRealSense.h:474
std::map< rs::stream, rs::preset > m_streamPresets
Definition: vpRealSense.h:482
float m_invalidDepthValue
Definition: vpRealSense.h:484
std::map< rs::stream, vpRsStreamParams > m_streamParams
Definition: vpRealSense.h:483
float m_max_Z
Maximal Z depth in meter.
Definition: vpRealSense.h:479
vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate)
Definition: vpRealSense.h:456