Visual Servoing Platform  version 3.6.1 under development (2024-11-14)
vpRealSense2.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  * librealSense2 interface.
33  *
34 *****************************************************************************/
35 
36 #ifndef _vpRealSense2_h_
37 #define _vpRealSense2_h_
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
42 
43 #include <librealsense2/rs.hpp>
44 #include <librealsense2/rsutil.h>
45 
46 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
47 #include <pcl/common/common_headers.h>
48 #endif
49 
50 #include <visp3/core/vpCameraParameters.h>
51 #include <visp3/core/vpImage.h>
52 
53 BEGIN_VISP_NAMESPACE
311 class VISP_EXPORT vpRealSense2
312 {
313 public:
314  vpRealSense2();
315  virtual ~vpRealSense2();
316 
317  void acquire(vpImage<unsigned char> &grey, double *ts = nullptr);
318  void acquire(vpImage<vpRGBa> &color, double *ts = nullptr);
319  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
320  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
321  rs2::align *const align_to = nullptr, double *ts = nullptr);
322  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
323  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared1,
324  unsigned char *const data_infrared2, rs2::align *const align_to, double *ts = nullptr);
325 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
326  void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, double *ts = nullptr);
327  void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, vpHomogeneousMatrix *cMw,
328  vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence = nullptr, double *ts = nullptr);
329  void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, vpHomogeneousMatrix *cMw,
330  vpColVector *odo_vel, vpColVector *odo_acc, vpColVector *imu_vel, vpColVector *imu_acc,
331  unsigned int *tracker_confidence = nullptr, double *ts = nullptr);
332 #endif
333 
334 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
335  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
336  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
337  unsigned char *const data_infrared = nullptr, rs2::align *const align_to = nullptr, double *ts = nullptr);
338  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
339  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
340  unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to,
341  double *ts = nullptr);
342 
343  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
344  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
345  unsigned char *const data_infrared = nullptr, rs2::align *const align_to = nullptr, double *ts = nullptr);
346  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
347  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
348  unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to,
349  double *ts = nullptr);
350 #endif
351 
352  void close();
353 
354  vpCameraParameters getCameraParameters(
355  const rs2_stream &stream,
357  int index = -1) const;
358 
359  float getDepthScale();
360 
361 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
362  void getIMUAcceleration(vpColVector *imu_acc, double *ts);
363  void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts);
364  void getIMUVelocity(vpColVector *imu_vel, double *ts);
365 #endif
366 
367  rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index = -1) const;
368 
372  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
373 
376  inline float getMaxZ() const { return m_max_Z; }
377 
378 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
379  unsigned int getOdometryData(vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, double *ts = nullptr);
380 #endif
381 
383  rs2::pipeline &getPipeline() { return m_pipe; }
384 
386  rs2::pipeline_profile &getPipelineProfile() { return m_pipelineProfile; }
387 
388  std::string getProductLine();
389 
390  std::string getSensorInfo();
391 
392  vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index = -1) const;
393 
394  bool open(const rs2::config &cfg = rs2::config());
395  bool open(const rs2::config &cfg, std::function<void(rs2::frame)> &callback);
396 
397  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs);
398 
402  inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
403 
406  inline void setMaxZ(const float maxZ) { m_max_Z = maxZ; }
407 
408 protected:
411  float m_max_Z;
412  rs2::pipeline m_pipe;
413  rs2::pipeline_profile m_pipelineProfile;
414  rs2::pointcloud m_pointcloud;
415  rs2::points m_points;
419  std::string m_product_line;
420  bool m_init;
421 
422  void getColorFrame(const rs2::frame &frame, vpImage<vpRGBa> &color);
423  void getGreyFrame(const rs2::frame &frame, vpImage<unsigned char> &grey);
424  void getNativeFrameData(const rs2::frame &frame, unsigned char *const data);
425  void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
426 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
427  void getPointcloud(const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
428  void getPointcloud(const rs2::depth_frame &depth_frame, const rs2::frame &color_frame,
429  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
430 #endif
431 };
432 END_VISP_NAMESPACE
433 #endif
434 #endif
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
Implementation of an homogeneous matrix and operations on such kind of matrices.
Implementation of a rotation vector as quaternion angle minimal representation.
void setInvalidDepthValue(float value)
Definition: vpRealSense2.h:402
void setMaxZ(const float maxZ)
Definition: vpRealSense2.h:406
vpQuaternionVector m_quat
Definition: vpRealSense2.h:417
rs2::pipeline m_pipe
Definition: vpRealSense2.h:412
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:386
vpRotationMatrix m_rot
Definition: vpRealSense2.h:418
rs2::pointcloud m_pointcloud
Definition: vpRealSense2.h:414
float m_depthScale
Definition: vpRealSense2.h:409
vpTranslationVector m_pos
Definition: vpRealSense2.h:416
std::string m_product_line
Definition: vpRealSense2.h:419
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:383
rs2::points m_points
Definition: vpRealSense2.h:415
float getInvalidDepthValue() const
Definition: vpRealSense2.h:372
float m_invalidDepthValue
Definition: vpRealSense2.h:410
rs2::pipeline_profile m_pipelineProfile
Definition: vpRealSense2.h:413
float getMaxZ() const
Definition: vpRealSense2.h:376
Implementation of a rotation matrix and operations on such kind of matrices.
Class that consider the case of a translation vector.