38 #ifndef __vpRealSense_h_
39 #define __vpRealSense_h_
44 #include <visp3/core/vpCameraParameters.h>
45 #include <visp3/core/vpColVector.h>
46 #include <visp3/core/vpConfig.h>
47 #include <visp3/core/vpException.h>
48 #include <visp3/core/vpHomogeneousMatrix.h>
49 #include <visp3/core/vpImage.h>
51 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY)
53 #include <librealsense/rs.hpp>
56 # include <pcl/point_types.h>
57 # include <pcl/common/projection_matrix.h>
314 void acquire(std::vector<vpColVector> &pointcloud);
316 void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
317 void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
329 void acquire(
vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
332 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth, std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
333 unsigned char *
const data_infrared2=NULL,
const rs::stream &stream_color=rs::stream::color,
const rs::stream &stream_depth=rs::stream::depth,
334 const rs::stream &stream_infrared=rs::stream::infrared,
const rs::stream &stream_infrared2=rs::stream::infrared2);
337 void acquire(
vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
341 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth, std::vector<vpColVector> *
const data_pointCloud,
342 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
unsigned char *
const data_infrared,
unsigned char *
const data_infrared2=NULL,
343 const rs::stream &stream_color=rs::stream::color,
const rs::stream &stream_depth=rs::stream::depth,
const rs::stream &stream_infrared=rs::stream::infrared,
344 const rs::stream &stream_infrared2=rs::stream::infrared2);
345 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth, std::vector<vpColVector> *
const data_pointCloud,
346 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
unsigned char *
const data_infrared,
unsigned char *
const data_infrared2=NULL,
347 const rs::stream &stream_color=rs::stream::color,
const rs::stream &stream_depth=rs::stream::depth,
348 const rs::stream &stream_infrared=rs::stream::infrared,
const rs::stream &stream_infrared2=rs::stream::infrared2);
359 rs::extrinsics getExtrinsics(
const rs::stream &from,
const rs::stream &to)
const;
360 rs::intrinsics getIntrinsics(
const rs::stream &stream)
const;
365 return m_invalidDepthValue;
370 return m_context.get_device_count();
381 void setDeviceBySerialNumber(
const std::string &serial_no);
383 friend VISP_EXPORT std::ostream & operator<< (std::ostream &os,
const vpRealSense &rs);
392 vpRsStreamParams() : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30) {
395 vpRsStreamParams(
const int streamWidth,
const int streamHeight,
const rs::format &streamFormat,
const int streamFramerate)
396 : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat), m_streamFramerate(streamFramerate) {
400 void setEnableStream(
const rs::stream &stream,
const bool status);
405 m_invalidDepthValue = value;
408 void setStreamSettings(
const rs::stream &stream,
const rs::preset &preset);
409 void setStreamSettings(
const rs::stream &stream,
const vpRsStreamParams ¶ms);
Implementation of an homogeneous matrix and operations on such kind of matrices.
rs::device * getHandler() const
Get access to device handler.
float getInvalidDepthValue() 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
void setInvalidDepthValue(const float value)
vpCameraParametersProjType
Generic class defining intrinsic camera parameters.
std::map< rs::stream, rs::preset > m_streamPresets
Perspective projection with distortion model.
float m_invalidDepthValue
std::map< rs::stream, rs::intrinsics > m_intrinsics
std::map< rs::stream, bool > m_enableStreams
std::string getSerialNumber() const
float m_max_Z
Maximal Z depth in meter.