36 #ifndef _vpRealSense_h_
37 #define _vpRealSense_h_
42 #include <visp3/core/vpCameraParameters.h>
43 #include <visp3/core/vpColVector.h>
44 #include <visp3/core/vpConfig.h>
45 #include <visp3/core/vpException.h>
46 #include <visp3/core/vpHomogeneousMatrix.h>
47 #include <visp3/core/vpImage.h>
49 #if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
51 #include <librealsense/rs.hpp>
53 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
54 #include <pcl/common/projection_matrix.h>
55 #include <pcl/point_types.h>
366 void acquire(std::vector<vpColVector> &pointcloud);
367 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
368 void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
369 void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
374 std::vector<vpColVector> &pointcloud);
375 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
378 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
380 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
384 void acquire(
vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
386 std::vector<vpColVector> &pointcloud);
388 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
389 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
390 unsigned char *
const data_infrared2 =
nullptr,
const rs::stream &stream_color = rs::stream::color,
391 const rs::stream &stream_depth = rs::stream::depth,
392 const rs::stream &stream_infrared = rs::stream::infrared,
393 const rs::stream &stream_infrared2 = rs::stream::infrared2);
395 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
396 void acquire(
vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
398 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
400 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
402 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
403 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
404 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 =
nullptr,
405 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
406 const rs::stream &stream_infrared = rs::stream::infrared,
407 const rs::stream &stream_infrared2 = rs::stream::infrared2);
408 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
409 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
410 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 =
nullptr,
411 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
412 const rs::stream &stream_infrared = rs::stream::infrared,
413 const rs::stream &stream_infrared2 = rs::stream::infrared2);
419 const rs::stream &stream,
424 rs::extrinsics getExtrinsics(
const rs::stream &from,
const rs::stream &to)
const;
425 rs::intrinsics getIntrinsics(
const rs::stream &stream)
const;
441 void setDeviceBySerialNumber(
const std::string &serial_no);
443 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense &rs);
453 : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
456 vpRsStreamParams(
const int streamWidth,
const int streamHeight,
const rs::format &streamFormat,
457 const int streamFramerate)
458 : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
459 m_streamFramerate(streamFramerate)
463 void setEnableStream(
const rs::stream &stream,
bool status);
470 void setStreamSettings(
const rs::stream &stream,
const rs::preset &preset);
471 void setStreamSettings(
const rs::stream &stream,
const vpRsStreamParams ¶ms);
Generic class defining intrinsic camera parameters.
vpCameraParametersProjType
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of an homogeneous matrix and operations on such kind of matrices.
int getNumDevices() const
Get number of devices that are detected.
void setInvalidDepthValue(float value)
std::map< rs::stream, bool > m_enableStreams
rs::device * getHandler() const
Get access to device handler.
float getInvalidDepthValue() const
std::map< rs::stream, bool > m_useStreamPresets
std::string getSerialNumber() const
std::map< rs::stream, rs::intrinsics > m_intrinsics
std::map< rs::stream, rs::preset > m_streamPresets
float m_invalidDepthValue
std::map< rs::stream, vpRsStreamParams > m_streamParams
float m_max_Z
Maximal Z depth in meter.