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>
54 #include <pcl/common/projection_matrix.h>
55 #include <pcl/point_types.h>
337 void acquire(std::vector<vpColVector> &pointcloud);
339 void acquire(pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
340 void acquire(pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
345 std::vector<vpColVector> &pointcloud);
349 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
351 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
355 void acquire(
vpImage<vpRGBa> &color, std::vector<vpColVector> &pointcloud);
357 std::vector<vpColVector> &pointcloud);
359 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
360 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
361 unsigned char *
const data_infrared2 = NULL,
const rs::stream &stream_color = rs::stream::color,
362 const rs::stream &stream_depth = rs::stream::depth,
363 const rs::stream &stream_infrared = rs::stream::infrared,
364 const rs::stream &stream_infrared2 = rs::stream::infrared2);
367 void acquire(
vpImage<vpRGBa> &color, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
369 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
371 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
373 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
374 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
375 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 = NULL,
376 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
377 const rs::stream &stream_infrared = rs::stream::infrared,
378 const rs::stream &stream_infrared2 = rs::stream::infrared2);
379 void acquire(
unsigned char *
const data_image,
unsigned char *
const data_depth,
380 std::vector<vpColVector> *
const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
381 unsigned char *
const data_infrared,
unsigned char *
const data_infrared2 = NULL,
382 const rs::stream &stream_color = rs::stream::color,
const rs::stream &stream_depth = rs::stream::depth,
383 const rs::stream &stream_infrared = rs::stream::infrared,
384 const rs::stream &stream_infrared2 = rs::stream::infrared2);
390 const rs::stream &stream,
395 rs::extrinsics getExtrinsics(
const rs::stream &from,
const rs::stream &to)
const;
396 rs::intrinsics getIntrinsics(
const rs::stream &stream)
const;
412 void setDeviceBySerialNumber(
const std::string &serial_no);
414 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os,
const vpRealSense &rs);
423 : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30)
427 vpRsStreamParams(
const int streamWidth,
const int streamHeight,
const rs::format &streamFormat,
428 const int streamFramerate)
429 : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat),
430 m_streamFramerate(streamFramerate)
435 void setEnableStream(
const rs::stream &stream,
bool status);
442 void setStreamSettings(
const rs::stream &stream,
const rs::preset &preset);
443 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.