Visual Servoing Platform  version 3.1.0
vpRealSense2.h
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 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) && defined(VISP_HAVE_CPP11_COMPATIBILITY)
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 
278 class VISP_EXPORT vpRealSense2
279 {
280 public:
281  vpRealSense2();
282  virtual ~vpRealSense2();
283 
284  void acquire(vpImage<unsigned char> &grey);
285  void acquire(vpImage<vpRGBa> &color);
286  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
287  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
288  rs2::align *const align_to = NULL);
289 
290 #ifdef VISP_HAVE_PCL
291  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
292  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
293  unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL);
294  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
295  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
296  unsigned char *const data_infrared = NULL, rs2::align *const align_to = NULL);
297 #endif
298 
299  void close();
300 
301  vpCameraParameters getCameraParameters(
302  const rs2_stream &stream,
304 
305  rs2_intrinsics getIntrinsics(const rs2_stream &stream) const;
306 
310  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
311 
314  inline float getMaxZ() const { return m_max_Z; }
315 
317  rs2::pipeline &getPipeline() { return m_pipe; }
318 
320  rs2::pipeline_profile &getPipelineProfile() { return m_pipelineProfile; }
321 
322  vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const;
323 
324  void open(const rs2::config &cfg = rs2::config());
325 
326  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs);
327 
331  inline void setInvalidDepthValue(const float value) { m_invalidDepthValue = value; }
332 
335  inline void setMaxZ(const float maxZ) { m_max_Z = maxZ; }
336 
337 protected:
338  rs2_intrinsics m_colorIntrinsics;
339  rs2_extrinsics m_depth2ColorExtrinsics;
340  rs2_intrinsics m_depthIntrinsics;
343  float m_max_Z;
344  rs2::pipeline m_pipe;
345  rs2::pipeline_profile m_pipelineProfile;
346  rs2::pointcloud m_pointcloud;
347  rs2::points m_points;
348 
349  void getColorFrame(const rs2::frame &frame, vpImage<vpRGBa> &color);
350  void getGreyFrame(const rs2::frame &frame, vpImage<unsigned char> &grey);
351  void getNativeFrameData(const rs2::frame &frame, unsigned char *const data);
352  void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
353 #ifdef VISP_HAVE_PCL
354  void getPointcloud(const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
355  void getPointcloud(const rs2::depth_frame &depth_frame, const rs2::frame &color_frame,
356  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
357 #endif
358 };
359 
360 #endif
361 #endif
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:320
void setMaxZ(const float maxZ)
Definition: vpRealSense2.h:335
Implementation of an homogeneous matrix and operations on such kind of matrices.
float m_depthScale
Definition: vpRealSense2.h:341
void setInvalidDepthValue(const float value)
Definition: vpRealSense2.h:331
rs2_intrinsics m_depthIntrinsics
Definition: vpRealSense2.h:340
float getInvalidDepthValue() const
Definition: vpRealSense2.h:310
rs2_intrinsics m_colorIntrinsics
Definition: vpRealSense2.h:338
float getMaxZ() const
Definition: vpRealSense2.h:314
rs2::pipeline_profile m_pipelineProfile
Definition: vpRealSense2.h:345
Generic class defining intrinsic camera parameters.
rs2_extrinsics m_depth2ColorExtrinsics
Definition: vpRealSense2.h:339
rs2::pointcloud m_pointcloud
Definition: vpRealSense2.h:346
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:317
rs2::pipeline m_pipe
Definition: vpRealSense2.h:344
rs2::points m_points
Definition: vpRealSense2.h:347
float m_invalidDepthValue
Definition: vpRealSense2.h:342