34#ifndef _vpRealSense2_h_
35#define _vpRealSense2_h_
37#include <visp3/core/vpConfig.h>
39#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
41#include <librealsense2/rs.hpp>
42#include <librealsense2/rsutil.h>
44#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
45#include <pcl/common/common_headers.h>
48#include <visp3/core/vpCameraParameters.h>
49#include <visp3/core/vpImage.h>
317 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
318 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
319 rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
320 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
321 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared1,
322 unsigned char *
const data_infrared2, rs2::align *
const align_to,
double *ts =
nullptr);
323#if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
329 unsigned int *tracker_confidence =
nullptr,
double *ts =
nullptr);
332#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
333 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
334 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
335 unsigned char *
const data_infrared =
nullptr, rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
336 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
337 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
338 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
339 double *ts =
nullptr);
341 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
342 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
343 unsigned char *
const data_infrared =
nullptr, rs2::align *
const align_to =
nullptr,
double *ts =
nullptr);
344 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
345 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
346 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
347 double *ts =
nullptr);
353 const rs2_stream &stream,
355 int index = -1)
const;
359#if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
365 rs2_intrinsics
getIntrinsics(
const rs2_stream &stream,
int index = -1)
const;
376#if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
386 std::string getProductLine();
388 std::string getSensorInfo();
390 vpHomogeneousMatrix getTransformation(
const rs2_stream &from,
const rs2_stream &to,
int from_index = -1)
const;
392 bool open(
const rs2::config &cfg = rs2::config());
393 bool open(
const rs2::config &cfg, std::function<
void(rs2::frame)> &callback);
395 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense2 &rs);
423 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
424#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
425 void getPointcloud(
const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
426 void getPointcloud(
const rs2::depth_frame &depth_frame,
const rs2::frame &color_frame,
427 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.
Definition of the vpImage class member functions.
Implementation of a rotation vector as quaternion angle minimal representation.
void setInvalidDepthValue(float value)
void setMaxZ(const float maxZ)
void getNativeFrameData(const rs2::frame &frame, unsigned char *const data)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
vpQuaternionVector m_quat
rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index=-1) const
rs2::pointcloud m_pointcloud
void getIMUAcceleration(vpColVector *imu_acc, double *ts)
void getPointcloud(const rs2::depth_frame &depth_frame, std::vector< vpColVector > &pointcloud)
void getColorFrame(const rs2::frame &frame, vpImage< vpRGBa > &color)
void getIMUVelocity(vpColVector *imu_vel, double *ts)
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
vpTranslationVector m_pos
std::string m_product_line
void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts)
void getGreyFrame(const rs2::frame &frame, vpImage< unsigned char > &grey)
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.