36 #ifndef _vpRealSense2_h_
37 #define _vpRealSense2_h_
39 #include <visp3/core/vpConfig.h>
41 #if defined(VISP_HAVE_REALSENSE2)
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>
295 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
296 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
297 rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
298 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
299 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared1,
300 unsigned char *
const data_infrared2, rs2::align *
const align_to,
double *ts =
nullptr);
301 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
307 unsigned int *tracker_confidence =
nullptr,
double *ts =
nullptr);
311 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
312 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
313 unsigned char *
const data_infrared =
nullptr, rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
314 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
315 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
316 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
317 double *ts =
nullptr);
319 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
320 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
321 unsigned char *
const data_infrared =
nullptr, 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, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
324 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
325 double *ts =
nullptr);
331 const rs2_stream &stream,
333 int index = -1)
const;
335 float getDepthScale();
337 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
338 void getIMUAcceleration(
vpColVector *imu_acc,
double *ts);
340 void getIMUVelocity(
vpColVector *imu_vel,
double *ts);
343 rs2_intrinsics getIntrinsics(
const rs2_stream &stream,
int index = -1)
const;
352 inline float getMaxZ()
const {
return m_max_Z; }
354 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
364 std::string getProductLine();
366 vpHomogeneousMatrix getTransformation(
const rs2_stream &from,
const rs2_stream &to,
int from_index = -1)
const;
368 bool open(
const rs2::config &cfg = rs2::config());
369 bool open(
const rs2::config &cfg, std::function<
void(rs2::frame)> &callback);
371 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense2 &rs);
380 inline void setMaxZ(
const float maxZ) { m_max_Z = maxZ; }
398 void getNativeFrameData(
const rs2::frame &frame,
unsigned char *
const data);
399 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
401 void getPointcloud(
const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
402 void getPointcloud(
const rs2::depth_frame &depth_frame,
const rs2::frame &color_frame,
403 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.