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>
340 void acquire(std::vector<vpColVector> &pointcloud);
342 void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
343 void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
348 std::vector<vpColVector> &pointcloud);
352 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
354 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
358 void acquire(
vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
360 std::vector<vpColVector> &pointcloud);
362 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
363 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
364 unsigned char *
const data_infrared2 = NULL,
const rs::stream &stream_color = rs::stream::color,
365 const rs::stream &stream_depth = rs::stream::depth,
366 const rs::stream &stream_infrared = rs::stream::infrared,
367 const rs::stream &stream_infrared2 = rs::stream::infrared2);
370 void acquire(
vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
372 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
374 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
376 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
377 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
378 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 = NULL,
379 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
380 const rs::stream &stream_infrared = rs::stream::infrared,
381 const rs::stream &stream_infrared2 = rs::stream::infrared2);
382 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
383 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
384 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 = NULL,
385 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
386 const rs::stream &stream_infrared = rs::stream::infrared,
387 const rs::stream &stream_infrared2 = rs::stream::infrared2);
393 const rs::stream &stream,
398 rs::extrinsics getExtrinsics(
const rs::stream &from,
const rs::stream &to)
const;
399 rs::intrinsics getIntrinsics(
const rs::stream &stream)
const;
415 void setDeviceBySerialNumber(
const std::string &serial_no);
417 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense &rs);
426 : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
430 vpRsStreamParams(
const int streamWidth,
const int streamHeight,
const rs::format &streamFormat,
431 const int streamFramerate)
432 : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
433 m_streamFramerate(streamFramerate)
438 void setEnableStream(
const rs::stream &stream,
bool status);
445 void setStreamSettings(
const rs::stream &stream,
const rs::preset &preset);
446 void setStreamSettings(
const rs::stream &stream,
const vpRsStreamParams ¶ms);
Generic class defining intrinsic camera parameters.
vpCameraParametersProjType
@ perspectiveProjWithDistortion
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.