Visual Servoing Platform  version 3.1.0
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 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  * RealSense SDK wrapper.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #ifndef __vpRealSense_h_
40 #define __vpRealSense_h_
41 
42 #include <map>
43 #include <stdint.h>
44 
45 #include <visp3/core/vpCameraParameters.h>
46 #include <visp3/core/vpColVector.h>
47 #include <visp3/core/vpConfig.h>
48 #include <visp3/core/vpException.h>
49 #include <visp3/core/vpHomogeneousMatrix.h>
50 #include <visp3/core/vpImage.h>
51 
52 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY)
53 
54 #include <librealsense/rs.hpp>
55 
56 #ifdef VISP_HAVE_PCL
57 #include <pcl/common/projection_matrix.h>
58 #include <pcl/point_types.h>
59 #endif
60 
333 class VISP_EXPORT vpRealSense
334 {
335 public:
336  vpRealSense();
337  virtual ~vpRealSense();
338 
339  void acquire(std::vector<vpColVector> &pointcloud);
340 #ifdef VISP_HAVE_PCL
341  void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
342  void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
343 #endif
344  void acquire(vpImage<unsigned char> &grey); // tested
345  void acquire(vpImage<unsigned char> &grey, std::vector<vpColVector> &pointcloud);
346  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
347  std::vector<vpColVector> &pointcloud);
348 #ifdef VISP_HAVE_PCL
349  void acquire(vpImage<unsigned char> &grey, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
350  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
351  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
352  void acquire(vpImage<unsigned char> &grey, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
353  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
354 #endif
355 
356  void acquire(vpImage<vpRGBa> &color); // tested
357  void acquire(vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
358  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
359  std::vector<vpColVector> &pointcloud);
360 
361  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
362  std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
363  unsigned char *const data_infrared2 = NULL, const rs::stream &stream_color = rs::stream::color,
364  const rs::stream &stream_depth = rs::stream::depth,
365  const rs::stream &stream_infrared = rs::stream::infrared,
366  const rs::stream &stream_infrared2 = rs::stream::infrared2);
367 
368 #ifdef VISP_HAVE_PCL
369  void acquire(vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
370  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
371  pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
372  void acquire(vpImage<vpRGBa> &color, vpImage<uint16_t> &infrared, vpImage<uint16_t> &depth,
373  pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
374 
375  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
376  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
377  unsigned char *const data_infrared, unsigned char *const data_infrared2 = NULL,
378  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
379  const rs::stream &stream_infrared = rs::stream::infrared,
380  const rs::stream &stream_infrared2 = rs::stream::infrared2);
381  void acquire(unsigned char *const data_image, unsigned char *const data_depth,
382  std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
383  unsigned char *const data_infrared, unsigned char *const data_infrared2 = NULL,
384  const rs::stream &stream_color = rs::stream::color, const rs::stream &stream_depth = rs::stream::depth,
385  const rs::stream &stream_infrared = rs::stream::infrared,
386  const rs::stream &stream_infrared2 = rs::stream::infrared2);
387 #endif
388 
389  void close();
390 
391  vpCameraParameters getCameraParameters(
392  const rs::stream &stream,
395  rs::device *getHandler() const { return m_device; }
396 
397  rs::extrinsics getExtrinsics(const rs::stream &from, const rs::stream &to) const;
398  rs::intrinsics getIntrinsics(const rs::stream &stream) const;
399 
403  inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
404 
406  int getNumDevices() const { return m_context.get_device_count(); }
409  std::string getSerialNumber() const { return m_serial_no; }
410  vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const;
411 
412  void open();
413 
414  void setDeviceBySerialNumber(const std::string &serial_no);
415 
416  friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense &rs);
417 
421  rs::format m_streamFormat;
423 
425  : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
426  {
427  }
428 
429  vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat,
430  const int streamFramerate)
431  : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
432  m_streamFramerate(streamFramerate)
433  {
434  }
435  };
436 
437  void setEnableStream(const rs::stream &stream, const bool status);
438 
442  inline void setInvalidDepthValue(const float value) { m_invalidDepthValue = value; }
443 
444  void setStreamSettings(const rs::stream &stream, const rs::preset &preset);
445  void setStreamSettings(const rs::stream &stream, const vpRsStreamParams &params);
446 
447 protected:
448  rs::context m_context;
449  rs::device *m_device;
451  std::string m_serial_no;
452  std::map<rs::stream, rs::intrinsics> m_intrinsics;
453  float m_max_Z;
454  std::map<rs::stream, bool> m_enableStreams;
455  std::map<rs::stream, bool> m_useStreamPresets;
456  std::map<rs::stream, rs::preset> m_streamPresets;
457  std::map<rs::stream, vpRsStreamParams> m_streamParams;
459 
460  void initStream();
461 };
462 
463 #endif
464 #endif
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:395
Implementation of an homogeneous matrix and operations on such kind of matrices.
int m_num_devices
Definition: vpRealSense.h:450
std::string m_serial_no
Definition: vpRealSense.h:451
std::string getSerialNumber() const
Definition: vpRealSense.h:409
int getNumDevices() const
Get number of devices that are detected.
Definition: vpRealSense.h:406
std::map< rs::stream, vpRsStreamParams > m_streamParams
Definition: vpRealSense.h:457
std::map< rs::stream, bool > m_useStreamPresets
Definition: vpRealSense.h:455
void setInvalidDepthValue(const float value)
Definition: vpRealSense.h:442
Generic class defining intrinsic camera parameters.
rs::device * m_device
Definition: vpRealSense.h:449
std::map< rs::stream, rs::preset > m_streamPresets
Definition: vpRealSense.h:456
rs::context m_context
Definition: vpRealSense.h:448
float m_invalidDepthValue
Definition: vpRealSense.h:458
std::map< rs::stream, rs::intrinsics > m_intrinsics
Definition: vpRealSense.h:452
float getInvalidDepthValue() const
Definition: vpRealSense.h:403
std::map< rs::stream, bool > m_enableStreams
Definition: vpRealSense.h:454
vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate)
Definition: vpRealSense.h:429
float m_max_Z
Maximal Z depth in meter.
Definition: vpRealSense.h:453