36 #ifndef _vpRealSense2_h_
37 #define _vpRealSense2_h_
39 #include <visp3/core/vpConfig.h>
41 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
43 #include <librealsense2/rs.hpp>
44 #include <librealsense2/rsutil.h>
47 #include <pcl/common/common_headers.h>
50 #include <visp3/core/vpCameraParameters.h>
51 #include <visp3/core/vpImage.h>
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);
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);
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);
316 const rs2_stream &stream,
319 float getDepthScale();
321 rs2_intrinsics getIntrinsics(
const rs2_stream &stream)
const;
330 inline float getMaxZ()
const {
return m_max_Z; }
340 void open(
const rs2::config &cfg = rs2::config());
342 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense2 &rs);
351 inline void setMaxZ(
const float maxZ) { m_max_Z = maxZ; }
364 void getNativeFrameData(
const rs2::frame &frame,
unsigned char *
const data);
365 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
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);