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>
46 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
47 #include <pcl/common/common_headers.h>
50 #include <visp3/core/vpCameraParameters.h>
51 #include <visp3/core/vpImage.h>
319 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
320 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
321 rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
322 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
323 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared1,
324 unsigned char *
const data_infrared2, rs2::align *
const align_to,
double *ts =
nullptr);
325 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
331 unsigned int *tracker_confidence =
nullptr,
double *ts =
nullptr);
334 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
335 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
336 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
337 unsigned char *
const data_infrared =
nullptr, rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
338 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
339 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
340 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
341 double *ts =
nullptr);
343 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
344 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
345 unsigned char *
const data_infrared =
nullptr, rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
346 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
347 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
348 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
349 double *ts =
nullptr);
355 const rs2_stream &stream,
357 int index = -1)
const;
359 float getDepthScale();
361 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
362 void getIMUAcceleration(
vpColVector *imu_acc,
double *ts);
364 void getIMUVelocity(
vpColVector *imu_vel,
double *ts);
367 rs2_intrinsics getIntrinsics(
const rs2_stream &stream,
int index = -1)
const;
376 inline float getMaxZ()
const {
return m_max_Z; }
378 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
388 std::string getProductLine();
390 std::string getSensorInfo();
392 vpHomogeneousMatrix getTransformation(
const rs2_stream &from,
const rs2_stream &to,
int from_index = -1)
const;
394 bool open(
const rs2::config &cfg = rs2::config());
395 bool open(
const rs2::config &cfg, std::function<
void(rs2::frame)> &callback);
397 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense2 &rs);
406 inline void setMaxZ(
const float maxZ) { m_max_Z = maxZ; }
424 void getNativeFrameData(
const rs2::frame &frame,
unsigned char *
const data);
425 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
426 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
427 void getPointcloud(
const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
428 void getPointcloud(
const rs2::depth_frame &depth_frame,
const rs2::frame &color_frame,
429 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
Generic class defining intrinsic camera parameters.
vpCameraParametersProjType
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
Implementation of an homogeneous matrix and operations on such kind of matrices.
Implementation of a rotation vector as quaternion angle minimal representation.
void setInvalidDepthValue(float value)
void setMaxZ(const float maxZ)
vpQuaternionVector m_quat
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
rs2::pointcloud m_pointcloud
vpTranslationVector m_pos
std::string m_product_line
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
float getInvalidDepthValue() const
float m_invalidDepthValue
rs2::pipeline_profile m_pipelineProfile
Implementation of a rotation matrix and operations on such kind of matrices.
Class that consider the case of a translation vector.