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> 294 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
295 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
296 rs2::align *
const align_to = NULL,
double *ts=NULL);
297 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
298 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared1,
299 unsigned char *
const data_infrared2, rs2::align *
const align_to,
double *ts=NULL);
300 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) 306 unsigned int *tracker_confidence = NULL,
double *ts = NULL);
310 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
311 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
312 unsigned char *
const data_infrared = NULL, rs2::align *
const align_to = NULL,
double *ts=NULL);
313 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
314 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
315 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
double *ts=NULL);
317 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
318 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
319 unsigned char *
const data_infrared = NULL, rs2::align *
const align_to = NULL,
double *ts=NULL);
320 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
321 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
322 unsigned char *
const data_infrared1,
unsigned char *
const data_infrared2, rs2::align *
const align_to,
double *ts=NULL);
329 int index = -1)
const;
331 float getDepthScale();
333 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) 334 void getIMUAcceleration(
vpColVector *imu_acc,
double *ts);
336 void getIMUVelocity(
vpColVector *imu_vel,
double *ts);
339 rs2_intrinsics getIntrinsics(
const rs2_stream &stream,
int index = -1)
const;
348 inline float getMaxZ()
const {
return m_max_Z; }
350 #if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) 360 std::string getProductLine();
362 vpHomogeneousMatrix getTransformation(
const rs2_stream &from,
const rs2_stream &to,
int from_index = -1)
const;
364 bool open(
const rs2::config &cfg = rs2::config());
365 bool open(
const rs2::config &cfg, std::function<
void(rs2::frame)> &callback);
367 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense2 &rs);
376 inline void setMaxZ(
const float maxZ) { m_max_Z = maxZ; }
394 void getNativeFrameData(
const rs2::frame &frame,
unsigned char *
const data);
395 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
397 void getPointcloud(
const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
398 void getPointcloud(
const rs2::depth_frame &depth_frame,
const rs2::frame &color_frame,
399 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
vpQuaternionVector m_quat
void setMaxZ(const float maxZ)
Implementation of an homogeneous matrix and operations on such kind of matrices.
float getInvalidDepthValue() const
Implementation of a rotation matrix and operations on such kind of matrices.
void setInvalidDepthValue(float value)
rs2::pipeline_profile m_pipelineProfile
vpCameraParametersProjType
Generic class defining intrinsic camera parameters.
Implementation of a rotation vector as quaternion angle minimal representation.
rs2::pointcloud m_pointcloud
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Implementation of column vector and the associated operations.
vpTranslationVector m_pos
std::string m_product_line
float m_invalidDepthValue
Class that consider the case of a translation vector.