Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
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 
282 class VISP_EXPORT vpRealSense2
283 {
284 public:
285  vpRealSense2();
286  virtual ~vpRealSense2();
287 
288  void acquire(vpImage<unsigned char> &grey);
289  void acquire(vpImage<vpRGBa> &color);
290  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
291  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
292  rs2::align *const align_to = NULL);
293  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
294  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared1,
295  unsigned char *const data_infrared2, rs2::align *const align_to);
296 
297 #ifdef VISP_HAVE_PCL
298  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
299  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
300  unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL);
301  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
302  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
303  unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to);
304 
305  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
306  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
307  unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL);
308  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
309  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
310  unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to);
311 #endif
312 
313  void close();
314 
315  vpCameraParameters getCameraParameters(
316  const rs2_stream &stream,
318 
319  float getDepthScale();
320 
321  rs2_intrinsics getIntrinsics(const rs2_stream &stream) const;
322 
326  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
327 
330  inline float getMaxZ() const { return m_max_Z; }
331 
333  rs2::pipeline &getPipeline() { return m_pipe; }
334 
336  rs2::pipeline_profile &getPipelineProfile() { return m_pipelineProfile; }
337 
338  vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const;
339 
340  void open(const rs2::config &cfg = rs2::config());
341 
342  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs);
343 
347  inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
348 
351  inline void setMaxZ(const float maxZ) { m_max_Z = maxZ; }
352 
353 protected:
356  float m_max_Z;
357  rs2::pipeline m_pipe;
358  rs2::pipeline_profile m_pipelineProfile;
359  rs2::pointcloud m_pointcloud;
360  rs2::points m_points;
361 
362  void getColorFrame(const rs2::frame &frame, vpImage<vpRGBa> &color);
363  void getGreyFrame(const rs2::frame &frame, vpImage<unsigned char> &grey);
364  void getNativeFrameData(const rs2::frame &frame, unsigned char *const data);
365  void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
366 #ifdef VISP_HAVE_PCL
367  void getPointcloud(const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
368  void getPointcloud(const rs2::depth_frame &depth_frame, const rs2::frame &color_frame,
369  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
370 #endif
371 };
372 
373 #endif
374 #endif
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:336
void setMaxZ(const float maxZ)
Definition: vpRealSense2.h:351
Implementation of an homogeneous matrix and operations on such kind of matrices.
float m_depthScale
Definition: vpRealSense2.h:354
float getInvalidDepthValue() const
Definition: vpRealSense2.h:326
void setInvalidDepthValue(float value)
Definition: vpRealSense2.h:347
float getMaxZ() const
Definition: vpRealSense2.h:330
rs2::pipeline_profile m_pipelineProfile
Definition: vpRealSense2.h:358
Generic class defining intrinsic camera parameters.
rs2::pointcloud m_pointcloud
Definition: vpRealSense2.h:359
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:333
rs2::pipeline m_pipe
Definition: vpRealSense2.h:357
rs2::points m_points
Definition: vpRealSense2.h:360
float m_invalidDepthValue
Definition: vpRealSense2.h:355