Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpRealSense.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
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * RealSense SDK wrapper.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #ifndef __vpRealSense_h_
39 #define __vpRealSense_h_
40 
41 #include <stdint.h>
42 #include <map>
43 
44 #include <visp3/core/vpCameraParameters.h>
45 #include <visp3/core/vpColVector.h>
46 #include <visp3/core/vpConfig.h>
47 #include <visp3/core/vpException.h>
48 #include <visp3/core/vpHomogeneousMatrix.h>
49 #include <visp3/core/vpImage.h>
50 
51 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY)
52 
53 #include <librealsense/rs.hpp>
54 
55 #ifdef VISP_HAVE_PCL
56 # include <pcl/point_types.h>
57 # include <pcl/common/projection_matrix.h>
58 #endif
59 
308 class VISP_EXPORT vpRealSense
309 {
310 public:
311  vpRealSense();
312  virtual ~vpRealSense();
313 
314  void acquire(std::vector<vpColVector> &pointcloud);
315 #ifdef VISP_HAVE_PCL
316  void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
317  void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
318 #endif
319  void acquire(vpImage<unsigned char> &grey); // tested
320  void acquire(vpImage<unsigned char> &grey, std::vector<vpColVector> &pointcloud);
321  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth, std::vector<vpColVector> &pointcloud);
322 #ifdef VISP_HAVE_PCL
323  void acquire(vpImage<unsigned char> &grey, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
324  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
325  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
326 #endif
327 
328  void acquire(vpImage<vpRGBa> &color); // tested
329  void acquire(vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
330  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth, std::vector<vpColVector> &pointcloud);
331 
332  void acquire(unsigned char * const data_image, unsigned char * const data_depth, std::vector<vpColVector> * const data_pointCloud, unsigned char * const data_infrared,
333  unsigned char * const data_infrared2=NULL, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth,
334  const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2);
335 
336 #ifdef VISP_HAVE_PCL
337  void acquire(vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
338  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
339  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
340 
341  void acquire(unsigned char * const data_image, unsigned char * const data_depth, std::vector<vpColVector> * const data_pointCloud,
342  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud, unsigned char * const data_infrared, unsigned char * const data_infrared2=NULL,
343  const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared,
344  const rs::stream &stream_infrared2=rs::stream::infrared2);
345  void acquire(unsigned char * const data_image, unsigned char * const data_depth, std::vector<vpColVector> * const data_pointCloud,
346  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud, unsigned char * const data_infrared, unsigned char * const data_infrared2=NULL,
347  const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth,
348  const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2);
349 #endif
350 
351  void close();
352 
355  rs::device *getHandler() const {
356  return m_device;
357  }
358 
359  rs::extrinsics getExtrinsics(const rs::stream &from, const rs::stream &to) const;
360  rs::intrinsics getIntrinsics(const rs::stream &stream) const;
361 
364  inline float getInvalidDepthValue() const {
365  return m_invalidDepthValue;
366  }
367 
369  int getNumDevices() const {
370  return m_context.get_device_count();
371  }
374  std::string getSerialNumber() const {
375  return m_serial_no;
376  }
377  vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const;
378 
379  void open();
380 
381  void setDeviceBySerialNumber(const std::string &serial_no);
382 
383  friend VISP_EXPORT std::ostream & operator<< (std::ostream &os, const vpRealSense &rs);
384 
385 
389  rs::format m_streamFormat;
391 
392  vpRsStreamParams() : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30) {
393  }
394 
395  vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate)
396  : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat), m_streamFramerate(streamFramerate) {
397  }
398  };
399 
400  void setEnableStream(const rs::stream &stream, const bool status);
401 
404  inline void setInvalidDepthValue(const float value) {
405  m_invalidDepthValue = value;
406  }
407 
408  void setStreamSettings(const rs::stream &stream, const rs::preset &preset);
409  void setStreamSettings(const rs::stream &stream, const vpRsStreamParams &params);
410 
411 protected:
412  rs::context m_context;
413  rs::device *m_device;
415  std::string m_serial_no;
416  std::map <rs::stream, rs::intrinsics> m_intrinsics;
417  float m_max_Z;
418  std::map<rs::stream, bool> m_enableStreams;
419  std::map<rs::stream, bool> m_useStreamPresets;
420  std::map<rs::stream, rs::preset> m_streamPresets;
421  std::map<rs::stream, vpRsStreamParams> m_streamParams;
423 
424  void initStream();
425 };
426 
427 #endif
428 #endif
429 
Implementation of an homogeneous matrix and operations on such kind of matrices.
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:355
int m_num_devices
Definition: vpRealSense.h:414
float getInvalidDepthValue() const
Definition: vpRealSense.h:364
std::string m_serial_no
Definition: vpRealSense.h:415
int getNumDevices() const
Get number of devices that are detected.
Definition: vpRealSense.h:369
std::map< rs::stream, vpRsStreamParams > m_streamParams
Definition: vpRealSense.h:421
std::map< rs::stream, bool > m_useStreamPresets
Definition: vpRealSense.h:419
void setInvalidDepthValue(const float value)
Definition: vpRealSense.h:404
Generic class defining intrinsic camera parameters.
rs::device * m_device
Definition: vpRealSense.h:413
std::map< rs::stream, rs::preset > m_streamPresets
Definition: vpRealSense.h:420
Perspective projection with distortion model.
rs::context m_context
Definition: vpRealSense.h:412
float m_invalidDepthValue
Definition: vpRealSense.h:422
std::map< rs::stream, rs::intrinsics > m_intrinsics
Definition: vpRealSense.h:416
std::map< rs::stream, bool > m_enableStreams
Definition: vpRealSense.h:418
vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate)
Definition: vpRealSense.h:395
std::string getSerialNumber() const
Definition: vpRealSense.h:374
float m_max_Z
Maximal Z depth in meter.
Definition: vpRealSense.h:417