36 #ifndef __vpRealSense2_h_ 37 #define __vpRealSense2_h_ 39 #include <visp3/core/vpConfig.h> 41 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) 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> 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);
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);
302 const rs2_stream &stream,
305 rs2_intrinsics getIntrinsics(
const rs2_stream &stream)
const;
314 inline float getMaxZ()
const {
return m_max_Z; }
324 void open(
const rs2::config &cfg = rs2::config());
326 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense2 &rs);
335 inline void setMaxZ(
const float maxZ) { m_max_Z = maxZ; }
351 void getNativeFrameData(
const rs2::frame &frame,
unsigned char *
const data);
352 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
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);
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
void setMaxZ(const float maxZ)
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setInvalidDepthValue(const float value)
rs2_intrinsics m_depthIntrinsics
float getInvalidDepthValue() const
rs2_intrinsics m_colorIntrinsics
rs2::pipeline_profile m_pipelineProfile
vpCameraParametersProjType
Generic class defining intrinsic camera parameters.
rs2_extrinsics m_depth2ColorExtrinsics
rs2::pointcloud m_pointcloud
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
float m_invalidDepthValue