Visual Servoing Platform  version 3.6.1 under development (2024-06-12)
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 
332 class VISP_EXPORT vpRealSense
333 {
334 public:
335  vpRealSense();
336  virtual ~vpRealSense();
337 
338  void acquire(std::vector<vpColVector> &pointcloud);
339 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
340  void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
341  void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
342 #endif
343  void acquire(vpImage<unsigned char> &grey); // tested
344  void acquire(vpImage<unsigned char> &grey, std::vector<vpColVector> &pointcloud);
345  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
346  std::vector<vpColVector> &pointcloud);
347 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
348  void acquire(vpImage<unsigned char> &grey, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
349  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
350  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::PointXYZRGB>::Ptr &pointcloud);
353 #endif
354 
355  void acquire(vpImage<vpRGBa> &color); // tested
356  void acquire(vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
357  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
358  std::vector<vpColVector> &pointcloud);
359 
360  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
361  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
362  unsigned char *const data_infrared2 = nullptr, const rs::stream &stream_color = rs::stream::color,
363  const rs::stream &stream_depth = rs::stream::depth,
364  const rs::stream &stream_infrared = rs::stream::infrared,
365  const rs::stream &stream_infrared2 = rs::stream::infrared2);
366 
367 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
368  void acquire(vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
369  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
370  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
371  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
372  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
373 
374  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
375  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
376  unsigned char *const data_infrared, unsigned char *const data_infrared2 = nullptr,
377  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
378  const rs::stream &stream_infrared = rs::stream::infrared,
379  const rs::stream &stream_infrared2 = rs::stream::infrared2);
380  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
381  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
382  unsigned char *const data_infrared, unsigned char *const data_infrared2 = nullptr,
383  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
384  const rs::stream &stream_infrared = rs::stream::infrared,
385  const rs::stream &stream_infrared2 = rs::stream::infrared2);
386 #endif
387 
388  void close();
389 
390  vpCameraParameters getCameraParameters(
391  const rs::stream &stream,
394  rs::device *getHandler() const { return m_device; }
395 
396  rs::extrinsics getExtrinsics(const rs::stream &from, const rs::stream &to) const;
397  rs::intrinsics getIntrinsics(const rs::stream &stream) const;
398 
402  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
403 
405  int getNumDevices() const { return m_context.get_device_count(); }
408  std::string getSerialNumber() const { return m_serial_no; }
409  vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const;
410 
411  void open();
412 
413  void setDeviceBySerialNumber(const std::string &serial_no);
414 
415  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense &rs);
416 
418  {
421  rs::format m_streamFormat;
423 
425  : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
426  { }
427 
428  vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat,
429  const int streamFramerate)
430  : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
431  m_streamFramerate(streamFramerate)
432  { }
433  };
434 
435  void setEnableStream(const rs::stream &stream, bool status);
436 
440  inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
441 
442  void setStreamSettings(const rs::stream &stream, const rs::preset &preset);
443  void setStreamSettings(const rs::stream &stream, const vpRsStreamParams &params);
444 
445 protected:
446  rs::context m_context;
447  rs::device *m_device;
449  std::string m_serial_no;
450  std::map<rs::stream, rs::intrinsics> m_intrinsics;
451  float m_max_Z;
452  std::map<rs::stream, bool> m_enableStreams;
453  std::map<rs::stream, bool> m_useStreamPresets;
454  std::map<rs::stream, rs::preset> m_streamPresets;
455  std::map<rs::stream, vpRsStreamParams> m_streamParams;
457 
458  void initStream();
459 };
461 #endif
462 #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:449
int getNumDevices() const
Get number of devices that are detected.
Definition: vpRealSense.h:405
void setInvalidDepthValue(float value)
Definition: vpRealSense.h:440
std::map< rs::stream, bool > m_enableStreams
Definition: vpRealSense.h:452
rs::device * m_device
Definition: vpRealSense.h:447
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:394
float getInvalidDepthValue() const
Definition: vpRealSense.h:402
int m_num_devices
Definition: vpRealSense.h:448
std::map< rs::stream, bool > m_useStreamPresets
Definition: vpRealSense.h:453
std::string getSerialNumber() const
Definition: vpRealSense.h:408
std::map< rs::stream, rs::intrinsics > m_intrinsics
Definition: vpRealSense.h:450
rs::context m_context
Definition: vpRealSense.h:446
std::map< rs::stream, rs::preset > m_streamPresets
Definition: vpRealSense.h:454
float m_invalidDepthValue
Definition: vpRealSense.h:456
std::map< rs::stream, vpRsStreamParams > m_streamParams
Definition: vpRealSense.h:455
float m_max_Z
Maximal Z depth in meter.
Definition: vpRealSense.h:451
vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate)
Definition: vpRealSense.h:428