YARP
Yet Another Robot Platform
realsense2Driver.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #ifndef REALSENSE2_DRIVER_H
10 #define REALSENSE2_DRIVER_H
11 
12 #include <iostream>
13 #include <cstring>
14 #include <map>
15 #include <mutex>
16 
17 #include <yarp/dev/DeviceDriver.h>
19 #include <yarp/os/PeriodicThread.h>
20 #include <yarp/sig/all.h>
21 #include <yarp/sig/Matrix.h>
22 #include <yarp/os/Stamp.h>
23 #include <yarp/dev/IRGBDSensor.h>
25 #include <librealsense2/rs.hpp>
26 
27 
126 {
127 private:
129  typedef yarp::os::Stamp Stamp;
132 
133 public:
135  ~realsense2Driver() override = default;
136 
137  // DeviceDriver
138  bool open(yarp::os::Searchable& config) override;
139  bool close() override;
140 
141  // IRGBDSensor
142  int getRgbHeight() override;
143  int getRgbWidth() override;
145  bool getRgbResolution(int &width, int &height) override;
146  bool setRgbResolution(int width, int height) override;
147  bool getRgbFOV(double& horizontalFov, double& verticalFov) override;
148  bool setRgbFOV(double horizontalFov, double verticalFov) override;
149  bool getRgbMirroring(bool& mirror) override;
150  bool setRgbMirroring(bool mirror) override;
151 
152  bool getRgbIntrinsicParam(Property& intrinsic) override;
153  int getDepthHeight() override;
154  int getDepthWidth() override;
155  bool setDepthResolution(int width, int height) override;
156  bool getDepthFOV(double& horizontalFov, double& verticalFov) override;
157  bool setDepthFOV(double horizontalFov, double verticalFov) override;
158  bool getDepthIntrinsicParam(Property& intrinsic) override;
159  double getDepthAccuracy() override;
160  bool setDepthAccuracy(double accuracy) override;
161  bool getDepthClipPlanes(double& nearPlane, double& farPlane) override;
162  bool setDepthClipPlanes(double nearPlane, double farPlane) override;
163  bool getDepthMirroring(bool& mirror) override;
164  bool setDepthMirroring(bool mirror) override;
165 
166 
167  bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override;
168  bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = nullptr) override;
169  bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = nullptr) override;
170  bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp=NULL, Stamp* depthStamp=NULL) override;
171 
173  std::string getLastErrorMsg(Stamp* timeStamp = NULL) override;
174 
175  //IFrameGrabberControls
176  bool getCameraDescription(CameraDescriptor *camera) override;
177  bool hasFeature(int feature, bool* hasFeature) override;
178  bool setFeature(int feature, double value) override;
179  bool getFeature(int feature, double* value) override;
180  bool setFeature(int feature, double value1, double value2) override;
181  bool getFeature(int feature, double* value1, double* value2) override;
182  bool hasOnOff( int feature, bool* HasOnOff) override;
183  bool setActive( int feature, bool onoff) override;
184  bool getActive( int feature, bool* isActive) override;
185  bool hasAuto( int feature, bool* hasAuto) override;
186  bool hasManual( int feature, bool* hasManual) override;
187  bool hasOnePush(int feature, bool* hasOnePush) override;
188  bool setMode( int feature, FeatureMode mode) override;
189  bool getMode( int feature, FeatureMode *mode) override;
190  bool setOnePush(int feature) override;
191 
192  //IFrameGrabberImageRaw
194  int height() const override;
195  int width() const override;
196 
197 protected:
198  //method
199  inline bool initializeRealsenseDevice();
200  inline bool setParams();
201 
202  bool getImage(FlexImage& Frame, Stamp* timeStamp, rs2::frameset& sourceFrame);
203  bool getImage(depthImage& Frame, Stamp* timeStamp, const rs2::frameset& sourceFrame);
204  void updateTransformations();
205  bool pipelineStartup();
206  bool pipelineShutdown();
207  bool pipelineRestart();
208  bool setFramerate(const int _fps);
209  void fallback();
210 
211 
212  // realsense classes
213  mutable std::mutex m_mutex;
214  rs2::context m_ctx;
215  rs2::config m_cfg;
216  rs2::pipeline m_pipeline;
217  rs2::pipeline_profile m_profile;
218  rs2::device m_device;
219  std::vector<rs2::sensor> m_sensors;
220  rs2::sensor* m_depth_sensor;
221  rs2::sensor* m_color_sensor;
223  rs2_extrinsics m_depth_to_color{}, m_color_to_depth{};
224  rs2_stream m_alignment_stream{RS2_STREAM_COLOR};
225 
226 
229  std::string m_lastError;
231  bool m_verbose;
235  int m_fps;
236  float m_scale;
237  std::vector<cameraFeature_id_t> m_supportedFeatures;
238 };
239 #endif
define common interfaces to discover remote camera capabilities
contains the definition of a Matrix type
realsense2 : driver for realsense2 compatible devices.
yarp::os::Stamp m_depth_stamp
rs2::pipeline m_pipeline
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
rs2_intrinsics m_infrared_intrin
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool hasManual(int feature, bool *hasManual) override
Check if the requested feature has the 'manual' mode.
rs2_intrinsics m_color_intrin
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=nullptr) override
rs2::sensor * m_depth_sensor
bool getActive(int feature, bool *isActive) override
Get the current status of the feature, on or off.
std::vector< cameraFeature_id_t > m_supportedFeatures
bool close() override
Close the DeviceDriver.
bool setFramerate(const int _fps)
bool hasAuto(int feature, bool *hasAuto) override
Check if the requested feature has the 'auto' mode.
int height() const override
Return the height of each frame.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ...
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
rs2::pipeline_profile m_profile
rs2_intrinsics m_depth_intrin
rs2_stream m_alignment_stream
int getDepthHeight() override
Return the height of each frame.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
rs2_extrinsics m_depth_to_color
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool hasOnOff(int feature, bool *HasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
~realsense2Driver() override=default
bool hasOnePush(int feature, bool *hasOnePush) override
Check if the requested feature has the 'onePush' mode.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
int getDepthWidth() override
Return the height of each frame.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
rs2::context m_ctx
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ...
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ...
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
rs2::sensor * m_color_sensor
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
rs2_extrinsics m_color_to_depth
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
yarp::os::Stamp m_rgb_stamp
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
int getRgbHeight() override
Return the height of each frame.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool getImage(yarp::sig::ImageOf< yarp::sig::PixelMono > &image) override
Get a raw image from the frame grabber.
int width() const override
Return the width of each frame.
int getRgbWidth() override
Return the width of each frame.
yarp::dev::RGBDSensorParamParser m_paramParser
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
std::vector< rs2::sensor > m_sensors
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
std::string m_lastError
rs2::device m_device
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
Control interface for frame grabber devices.
Read a YARP-format image from a device.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:56
The RGBDSensorParamParser class.
A class for storing options and configuration information.
Definition: Property.h:37
A base class for nested structures that can be searched.
Definition: Searchable.h:69
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
Image class with user control of representation details.
Definition: Image.h:403
A class for a Matrix.
Definition: Matrix.h:46
constexpr char accuracy[]