Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRealSense2.h
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * librealSense2 interface.
32 */
33
34#ifndef _vpRealSense2_h_
35#define _vpRealSense2_h_
36
37#include <visp3/core/vpConfig.h>
38
39#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
40
41#include <librealsense2/rs.hpp>
42#include <librealsense2/rsutil.h>
43
44#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
45#include <pcl/common/common_headers.h>
46#endif
47
48#include <visp3/core/vpCameraParameters.h>
49#include <visp3/core/vpImage.h>
50
309class VISP_EXPORT vpRealSense2
310{
311public:
312 vpRealSense2();
313 virtual ~vpRealSense2();
314
315 void acquire(vpImage<unsigned char> &grey, double *ts = nullptr);
316 void acquire(vpImage<vpRGBa> &color, double *ts = nullptr);
317 void acquire(unsigned char *const data_image, unsigned char *const data_depth,
318 std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared,
319 rs2::align *const align_to = nullptr, double *ts = nullptr);
320 void acquire(unsigned char *const data_image, unsigned char *const data_depth,
321 std::vector<vpColVector> *const data_pointCloud, unsigned char *const data_infrared1,
322 unsigned char *const data_infrared2, rs2::align *const align_to, double *ts = nullptr);
323#if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
324 void acquire(vpImage<unsigned char> *left, vpImage<unsigned char> *right, double *ts = nullptr);
326 vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence = nullptr, double *ts = nullptr);
328 vpColVector *odo_vel, vpColVector *odo_acc, vpColVector *imu_vel, vpColVector *imu_acc,
329 unsigned int *tracker_confidence = nullptr, double *ts = nullptr);
330#endif
331
332#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
333 void acquire(unsigned char *const data_image, unsigned char *const data_depth,
334 std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
335 unsigned char *const data_infrared = nullptr, rs2::align *const align_to = nullptr, double *ts = nullptr);
336 void acquire(unsigned char *const data_image, unsigned char *const data_depth,
337 std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
338 unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to,
339 double *ts = nullptr);
340
341 void acquire(unsigned char *const data_image, unsigned char *const data_depth,
342 std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
343 unsigned char *const data_infrared = nullptr, rs2::align *const align_to = nullptr, double *ts = nullptr);
344 void acquire(unsigned char *const data_image, unsigned char *const data_depth,
345 std::vector<vpColVector> *const data_pointCloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
346 unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to,
347 double *ts = nullptr);
348#endif
349
350 void close();
351
353 const rs2_stream &stream,
355 int index = -1) const;
356
357 float getDepthScale();
358
359#if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
360 void getIMUAcceleration(vpColVector *imu_acc, double *ts);
361 void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts);
362 void getIMUVelocity(vpColVector *imu_vel, double *ts);
363#endif
364
365 rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index = -1) const;
366
370 inline float getInvalidDepthValue() const { return m_invalidDepthValue; }
371
374 inline float getMaxZ() const { return m_max_Z; }
375
376#if (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))
377 unsigned int getOdometryData(vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, double *ts = nullptr);
378#endif
379
381 rs2::pipeline &getPipeline() { return m_pipe; }
382
384 rs2::pipeline_profile &getPipelineProfile() { return m_pipelineProfile; }
385
386 std::string getProductLine();
387
388 std::string getSensorInfo();
389
390 vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index = -1) const;
391
392 bool open(const rs2::config &cfg = rs2::config());
393 bool open(const rs2::config &cfg, std::function<void(rs2::frame)> &callback);
394
395 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs);
396
400 inline void setInvalidDepthValue(float value) { m_invalidDepthValue = value; }
401
404 inline void setMaxZ(const float maxZ) { m_max_Z = maxZ; }
405
406protected:
409 float m_max_Z;
410 rs2::pipeline m_pipe;
411 rs2::pipeline_profile m_pipelineProfile;
412 rs2::pointcloud m_pointcloud;
413 rs2::points m_points;
417 std::string m_product_line;
418 bool m_init;
419
420 void getColorFrame(const rs2::frame &frame, vpImage<vpRGBa> &color);
421 void getGreyFrame(const rs2::frame &frame, vpImage<unsigned char> &grey);
422 void getNativeFrameData(const rs2::frame &frame, unsigned char *const data);
423 void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud);
424#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
425 void getPointcloud(const rs2::depth_frame &depth_frame, pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud);
426 void getPointcloud(const rs2::depth_frame &depth_frame, const rs2::frame &color_frame,
427 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud);
428#endif
429};
430END_VISP_NAMESPACE
431#endif
432#endif
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
Implementation of an homogeneous matrix and operations on such kind of matrices.
Definition of the vpImage class member functions.
Definition vpImage.h:131
Implementation of a rotation vector as quaternion angle minimal representation.
void setInvalidDepthValue(float value)
void setMaxZ(const float maxZ)
void getNativeFrameData(const rs2::frame &frame, unsigned char *const data)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
vpQuaternionVector m_quat
rs2::pipeline m_pipe
rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index=-1) const
vpRotationMatrix m_rot
float getDepthScale()
rs2::pointcloud m_pointcloud
void getIMUAcceleration(vpColVector *imu_acc, double *ts)
void getPointcloud(const rs2::depth_frame &depth_frame, std::vector< vpColVector > &pointcloud)
void getColorFrame(const rs2::frame &frame, vpImage< vpRGBa > &color)
void getIMUVelocity(vpColVector *imu_vel, double *ts)
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
vpTranslationVector m_pos
std::string m_product_line
void getIMUData(vpColVector *imu_vel, vpColVector *imu_acc, double *ts)
void getGreyFrame(const rs2::frame &frame, vpImage< unsigned char > &grey)
rs2::points m_points
float getInvalidDepthValue() const
float m_invalidDepthValue
rs2::pipeline_profile m_pipelineProfile
float getMaxZ() const
Implementation of a rotation matrix and operations on such kind of matrices.
Class that consider the case of a translation vector.