Visual Servoing Platform  version 3.5.0 under development (2022-02-15)
vpRealSense2.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  * 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 #ifdef VISP_HAVE_PCL
47 #include <pcl/common/common_headers.h>
48 #endif
49 
50 #include <visp3/core/vpCameraParameters.h>
51 #include <visp3/core/vpImage.h>
52 
286 class VISP_EXPORT vpRealSense2
287 {
288 public:
289  vpRealSense2();
290  virtual ~vpRealSense2();
291 
292  void acquire(vpImage<unsigned char> &grey, double *ts=NULL);
293  void acquire(vpImage<vpRGBa> &color, double *ts=NULL);
294  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
295  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
296  rs2::align *const align_to = NULL, double *ts=NULL);
297  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
298  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared1,
299  unsigned char *const data_infrared2, rs2::align *const align_to, double *ts=NULL);
300 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
301  void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, double *ts = NULL);
302  void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, vpHomogeneousMatrix *cMw,
303  vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence = NULL, double *ts = NULL);
304  void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, vpHomogeneousMatrix *cMw,
305  vpColVector *odo_vel, vpColVector *odo_acc, vpColVector *imu_vel, vpColVector *imu_acc,
306  unsigned int *tracker_confidence = NULL, double *ts = NULL);
307 #endif
308 
309 #ifdef VISP_HAVE_PCL
310  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
311  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
312  unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL, double *ts=NULL);
313  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
314  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
315  unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, double *ts=NULL);
316 
317  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
318  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
319  unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL, double *ts=NULL);
320  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
321  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
322  unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, double *ts=NULL);
323 #endif
324 
325  void close();
326 
327  vpCameraParameters getCameraParameters( const rs2_stream &stream,
329  int index = -1) const;
330 
331  float getDepthScale();
332 
333 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
334  void getIMUAcceleration(vpColVector *imu_acc, double *ts);
335  void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts);
336  void getIMUVelocity(vpColVector *imu_vel, double *ts);
337 #endif
338 
339  rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index = -1) const;
340 
344  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
345 
348  inline float getMaxZ() const { return m_max_Z; }
349 
350 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
351  unsigned int getOdometryData(vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, double *ts = NULL);
352 #endif
353 
355  rs2::pipeline &getPipeline() { return m_pipe; }
356 
358  rs2::pipeline_profile &getPipelineProfile() { return m_pipelineProfile; }
359 
360  std::string getProductLine();
361 
362  vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index = -1) const;
363 
364  bool open(const rs2::config &cfg = rs2::config());
365  bool open(const rs2::config &cfg, std::function<void(rs2::frame)> &callback);
366 
367  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs);
368 
372  inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
373 
376  inline void setMaxZ(const float maxZ) { m_max_Z = maxZ; }
377 
378 protected:
381  float m_max_Z;
382  rs2::pipeline m_pipe;
383  rs2::pipeline_profile m_pipelineProfile;
384  rs2::pointcloud m_pointcloud;
385  rs2::points m_points;
389  std::string m_product_line;
390  bool m_init;
391 
392  void getColorFrame(const rs2::frame &frame, vpImage<vpRGBa> &color);
393  void getGreyFrame(const rs2::frame &frame, vpImage<unsigned char> &grey);
394  void getNativeFrameData(const rs2::frame &frame, unsigned char *const data);
395  void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
396 #ifdef VISP_HAVE_PCL
397  void getPointcloud(const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
398  void getPointcloud(const rs2::depth_frame &depth_frame, const rs2::frame &color_frame,
399  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
400 #endif
401 };
402 
403 #endif
404 #endif
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:358
vpQuaternionVector m_quat
Definition: vpRealSense2.h:387
void setMaxZ(const float maxZ)
Definition: vpRealSense2.h:376
Implementation of an homogeneous matrix and operations on such kind of matrices.
float m_depthScale
Definition: vpRealSense2.h:379
float getInvalidDepthValue() const
Definition: vpRealSense2.h:344
Implementation of a rotation matrix and operations on such kind of matrices.
void setInvalidDepthValue(float value)
Definition: vpRealSense2.h:372
float getMaxZ() const
Definition: vpRealSense2.h:348
rs2::pipeline_profile m_pipelineProfile
Definition: vpRealSense2.h:383
Generic class defining intrinsic camera parameters.
Implementation of a rotation vector as quaternion angle minimal representation.
rs2::pointcloud m_pointcloud
Definition: vpRealSense2.h:384
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:355
rs2::pipeline m_pipe
Definition: vpRealSense2.h:382
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
rs2::points m_points
Definition: vpRealSense2.h:385
vpTranslationVector m_pos
Definition: vpRealSense2.h:386
std::string m_product_line
Definition: vpRealSense2.h:389
float m_invalidDepthValue
Definition: vpRealSense2.h:380
Class that consider the case of a translation vector.
vpRotationMatrix m_rot
Definition: vpRealSense2.h:388