39 #ifndef _vpRealSense_h_ 40 #define _vpRealSense_h_ 45 #include <visp3/core/vpCameraParameters.h> 46 #include <visp3/core/vpColVector.h> 47 #include <visp3/core/vpConfig.h> 48 #include <visp3/core/vpException.h> 49 #include <visp3/core/vpHomogeneousMatrix.h> 50 #include <visp3/core/vpImage.h> 52 #if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) 54 #include <librealsense/rs.hpp> 57 #include <pcl/common/projection_matrix.h> 58 #include <pcl/point_types.h> 339 void acquire(std::vector<vpColVector> &pointcloud);
341 void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
342 void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
347 std::vector<vpColVector> &pointcloud);
351 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
353 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
357 void acquire(
vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
359 std::vector<vpColVector> &pointcloud);
361 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
362 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
363 unsigned char *
const data_infrared2 = NULL,
const rs::stream &stream_color = rs::stream::color,
364 const rs::stream &stream_depth = rs::stream::depth,
365 const rs::stream &stream_infrared = rs::stream::infrared,
366 const rs::stream &stream_infrared2 = rs::stream::infrared2);
369 void acquire(
vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
371 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
373 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
375 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
376 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
377 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 = NULL,
378 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
379 const rs::stream &stream_infrared = rs::stream::infrared,
380 const rs::stream &stream_infrared2 = rs::stream::infrared2);
381 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
382 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
383 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 = NULL,
384 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
385 const rs::stream &stream_infrared = rs::stream::infrared,
386 const rs::stream &stream_infrared2 = rs::stream::infrared2);
392 const rs::stream &stream,
397 rs::extrinsics getExtrinsics(
const rs::stream &from,
const rs::stream &to)
const;
398 rs::intrinsics getIntrinsics(
const rs::stream &stream)
const;
414 void setDeviceBySerialNumber(
const std::string &serial_no);
416 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense &rs);
425 : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
429 vpRsStreamParams(
const int streamWidth,
const int streamHeight,
const rs::format &streamFormat,
430 const int streamFramerate)
431 : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
432 m_streamFramerate(streamFramerate)
437 void setEnableStream(
const rs::stream &stream,
bool status);
444 void setStreamSettings(
const rs::stream &stream,
const rs::preset &preset);
445 void setStreamSettings(
const rs::stream &stream,
const vpRsStreamParams ¶ms);
rs::device * getHandler() const
Get access to device handler.
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::string getSerialNumber() const
int getNumDevices() const
Get number of devices that are detected.
std::map< rs::stream, vpRsStreamParams > m_streamParams
std::map< rs::stream, bool > m_useStreamPresets
vpCameraParametersProjType
Generic class defining intrinsic camera parameters.
std::map< rs::stream, rs::preset > m_streamPresets
float m_invalidDepthValue
std::map< rs::stream, rs::intrinsics > m_intrinsics
float getInvalidDepthValue() const
std::map< rs::stream, bool > m_enableStreams
void setInvalidDepthValue(float value)
float m_max_Z
Maximal Z depth in meter.