YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
realsense2Driver Class Reference

#include </home/runner/work/yarp-documentation/yarp-documentation/yarp/opt-modules/yarp-device-realsense2/src/devices/realsense2/realsense2Driver.h>

+ Inheritance diagram for realsense2Driver:

Public Member Functions

 realsense2Driver ()
 
 ~realsense2Driver () override=default
 
bool open (yarp::os::Searchable &config) override
 Open the DeviceDriver.
 
bool close () override
 Close the DeviceDriver.
 
int getRgbHeight () override
 Return the height of each frame.
 
int getRgbWidth () override
 Return the width of each frame.
 
bool getRgbSupportedConfigurations (yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
 Get the possible configurations of the camera.
 
bool getRgbResolution (int &width, int &height) override
 Get the resolution of the rgb image from the camera.
 
bool setRgbResolution (int width, int height) override
 Set the resolution of the rgb image from the camera.
 
bool getRgbFOV (double &horizontalFov, double &verticalFov) override
 Get the field of view (FOV) of the rgb camera.
 
bool setRgbFOV (double horizontalFov, double verticalFov) override
 Set the field of view (FOV) of the rgb camera.
 
bool getRgbMirroring (bool &mirror) override
 Get the mirroring setting of the sensor.
 
bool setRgbMirroring (bool mirror) override
 Set the mirroring setting of the sensor.
 
bool getRgbIntrinsicParam (Property &intrinsic) override
 Get the intrinsic parameters of the rgb camera.
 
int getDepthHeight () override
 Return the height of each frame.
 
int getDepthWidth () override
 Return the height of each frame.
 
bool setDepthResolution (int width, int height) override
 Set the resolution of the depth image from the camera.
 
bool getDepthFOV (double &horizontalFov, double &verticalFov) override
 Get the field of view (FOV) of the depth camera.
 
bool setDepthFOV (double horizontalFov, double verticalFov) override
 Set the field of view (FOV) of the depth camera.
 
bool getDepthIntrinsicParam (Property &intrinsic) override
 Get the intrinsic parameters of the depth camera.
 
double getDepthAccuracy () override
 Get the minimum detectable variation in distance [meter].
 
bool setDepthAccuracy (double accuracy) override
 Set the minimum detectable variation in distance [meter] when possible.
 
bool getDepthClipPlanes (double &nearPlane, double &farPlane) override
 Get the clipping planes of the sensor.
 
bool setDepthClipPlanes (double nearPlane, double farPlane) override
 Set the clipping planes of the sensor.
 
bool getDepthMirroring (bool &mirror) override
 Get the mirroring setting of the sensor.
 
bool setDepthMirroring (bool mirror) override
 Set the mirroring setting of the sensor.
 
bool getExtrinsicParam (yarp::sig::Matrix &extrinsic) override
 Get the extrinsic parameters from the device.
 
bool getRgbImage (FlexImage &rgbImage, Stamp *timeStamp=nullptr) override
 Get the rgb frame from the device.
 
bool getDepthImage (depthImage &depthImage, Stamp *timeStamp=nullptr) override
 
bool getImages (FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
 
RGBDSensor_status getSensorStatus () override
 Get the surrent status of the sensor, using enum type.
 
std::string getLastErrorMsg (Stamp *timeStamp=NULL) override
 Return an error message in case of error.
 
bool getCameraDescription (CameraDescriptor *camera) override
 Get a basic description of the camera hw.
 
bool hasFeature (int feature, bool *hasFeature) override
 Check if camera has the requested feature (saturation, brightness ... )
 
bool setFeature (int feature, double value) override
 Set the requested feature to a value (saturation, brightness ... )
 
bool getFeature (int feature, double *value) override
 Get the current value for the requested feature.
 
bool setFeature (int feature, double value1, double value2) override
 Set the requested feature to a value using 2 params (like white balance)
 
bool getFeature (int feature, double *value1, double *value2) override
 Get the current value for the requested feature.
 
bool hasOnOff (int feature, bool *HasOnOff) override
 Check if the camera has the ability to turn on/off the requested feature.
 
bool setActive (int feature, bool onoff) override
 Set the requested feature on or off.
 
bool getActive (int feature, bool *isActive) override
 Get the current status of the feature, on or off.
 
bool hasAuto (int feature, bool *hasAuto) override
 Check if the requested feature has the 'auto' mode.
 
bool hasManual (int feature, bool *hasManual) override
 Check if the requested feature has the 'manual' mode.
 
bool hasOnePush (int feature, bool *hasOnePush) override
 Check if the requested feature has the 'onePush' mode.
 
bool setMode (int feature, FeatureMode mode) override
 Set the requested mode for the feature.
 
bool getMode (int feature, FeatureMode *mode) override
 Get the current mode for the feature.
 
bool setOnePush (int feature) override
 Set the requested feature to a value (saturation, brightness ... )
 
bool getImage (yarp::sig::ImageOf< yarp::sig::PixelMono > &image) override
 Get an image from the frame grabber.
 
int height () const override
 Return the height of each frame.
 
int width () const override
 Return the width of each frame.
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
 DeviceDriver ()
 
 DeviceDriver (const DeviceDriver &other)=delete
 
 DeviceDriver (DeviceDriver &&other) noexcept=delete
 
DeviceDriveroperator= (const DeviceDriver &other)=delete
 
DeviceDriveroperator= (DeviceDriver &&other) noexcept=delete
 
virtual ~DeviceDriver ()
 
virtual std::string id () const
 Return the id assigned to the PolyDriver.
 
virtual void setId (const std::string &id)
 Set the id for this device.
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver.
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others.
 
- Public Member Functions inherited from yarp::dev::IFrameGrabberControls
virtual ~IFrameGrabberControls ()
 Destructor.
 
std::string busType2String (BusType type)
 
FeatureMode toFeatureMode (bool _auto)
 
- Public Member Functions inherited from yarp::dev::IFrameGrabberOf< yarp::sig::ImageOf< yarp::sig::PixelMono > >
virtual bool getImageCrop (cropType_id_t cropType, yarp::sig::VectorOf< std::pair< int, int > > vertices, yarp::sig::ImageOf< yarp::sig::PixelMono > &image)
 Get a crop of the image from the frame grabber.
 
- Public Member Functions inherited from yarp::dev::IFrameGrabberImageBase
virtual ~IFrameGrabberImageBase ()
 Destructor.
 
- Public Member Functions inherited from yarp::dev::IRGBDSensor
virtual ~IRGBDSensor ()
 
virtual bool getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr)=0
 Get the depth frame from the device.
 
virtual bool getImages (yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr)=0
 Get the both the color and depth frame in a single call.
 
- Public Member Functions inherited from yarp::dev::IRgbVisualParams
virtual ~IRgbVisualParams ()
 
- Public Member Functions inherited from yarp::dev::IDepthVisualParams
virtual ~IDepthVisualParams ()
 

Protected Member Functions

bool initializeRealsenseDevice ()
 
bool setParams ()
 
bool getImage (FlexImage &Frame, Stamp *timeStamp, rs2::frameset &sourceFrame)
 
bool getImage (depthImage &Frame, Stamp *timeStamp, const rs2::frameset &sourceFrame)
 
void updateTransformations ()
 
bool pipelineStartup ()
 
bool pipelineShutdown ()
 
bool pipelineRestart ()
 
bool setFramerate (const int _fps)
 
void fallback ()
 

Protected Attributes

std::mutex m_mutex
 
rs2::context m_ctx
 
rs2::config m_cfg
 
rs2::pipeline m_pipeline
 
rs2::pipeline_profile m_profile
 
rs2::device m_device
 
std::vector< rs2::sensor > m_sensors
 
rs2::sensor * m_depth_sensor
 
rs2::sensor * m_color_sensor
 
rs2_intrinsics m_depth_intrin {}
 
rs2_intrinsics m_color_intrin {}
 
rs2_intrinsics m_infrared_intrin {}
 
rs2_extrinsics m_depth_to_color {}
 
rs2_extrinsics m_color_to_depth {}
 
rs2_stream m_alignment_stream {RS2_STREAM_COLOR}
 
bool m_depthQuantizationEnabled {false}
 
int m_depthDecimalNum {0}
 
yarp::os::Stamp m_rgb_stamp
 
yarp::os::Stamp m_depth_stamp
 
std::string m_lastError
 
yarp::dev::RGBDSensorParamParser m_paramParser
 
bool m_verbose
 
bool m_initialized
 
bool m_stereoMode
 
bool m_needAlignment
 
int m_fps
 
float m_scale
 
bool m_rotateImage180 {false}
 
std::vector< cameraFeature_id_tm_supportedFeatures
 

Additional Inherited Members

- Public Types inherited from yarp::dev::IRGBDSensor
enum  RGBDSensor_status {
  RGBD_SENSOR_NOT_READY = 0 ,
  RGBD_SENSOR_OK_STANDBY = 1 ,
  RGBD_SENSOR_OK_IN_USE = 2 ,
  RGB_SENSOR_ERROR = 3 ,
  DEPTH_SENSOR_ERROR = 4 ,
  RGBD_SENSOR_GENERIC_ERROR = 5 ,
  RGBD_SENSOR_TIMEOUT = 6
}
 

Detailed Description

Definition at line 29 of file realsense2Driver.h.

Constructor & Destructor Documentation

◆ realsense2Driver()

realsense2Driver::realsense2Driver ( )

Definition at line 432 of file realsense2Driver.cpp.

◆ ~realsense2Driver()

realsense2Driver::~realsense2Driver ( )
overridedefault

Member Function Documentation

◆ close()

bool realsense2Driver::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Reimplemented in realsense2withIMUDriver.

Definition at line 855 of file realsense2Driver.cpp.

◆ fallback()

void realsense2Driver::fallback ( )
protected

Definition at line 521 of file realsense2Driver.cpp.

◆ getActive()

bool realsense2Driver::getActive ( int  feature,
bool isActive 
)
overridevirtual

Get the current status of the feature, on or off.

Parameters
featurethe identifier of the feature to check
isActiveflag true if the feature is active, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1444 of file realsense2Driver.cpp.

◆ getCameraDescription()

bool realsense2Driver::getCameraDescription ( CameraDescriptor camera)
overridevirtual

Get a basic description of the camera hw.

This is mainly used to determine the HW bus type in order to choose the corresponding interface for advanced controls.

Parameters
devicereturns an identifier for the bus
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1224 of file realsense2Driver.cpp.

◆ getDepthAccuracy()

double realsense2Driver::getDepthAccuracy ( )
overridevirtual

Get the minimum detectable variation in distance [meter].

Returns
the sensor resolution in meters.

Implements yarp::dev::IRGBDSensor.

Definition at line 1010 of file realsense2Driver.cpp.

◆ getDepthClipPlanes()

bool realsense2Driver::getDepthClipPlanes ( double nearPlane,
double farPlane 
)
overridevirtual

Get the clipping planes of the sensor.

Parameters
nearPlaneminimum distance at which the sensor start measuring. Object closer than this distance will not be detected.
farPlanemaximum distance beyond which the sensor stop measuring. Object farther than this distance will not be detected.
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 1020 of file realsense2Driver.cpp.

◆ getDepthFOV()

bool realsense2Driver::getDepthFOV ( double horizontalFov,
double verticalFov 
)
overridevirtual

Get the field of view (FOV) of the depth camera.

Parameters
horizontalFovwill return the value of the horizontal fov in degrees
verticalFovwill return the value of the vertical fov in degrees
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 996 of file realsense2Driver.cpp.

◆ getDepthHeight()

int realsense2Driver::getDepthHeight ( )
overridevirtual

Return the height of each frame.

Returns
depth image height

Implements yarp::dev::IRGBDSensor.

Definition at line 986 of file realsense2Driver.cpp.

◆ getDepthImage()

bool realsense2Driver::getDepthImage ( depthImage depthImage,
Stamp timeStamp = nullptr 
)
override

Definition at line 1084 of file realsense2Driver.cpp.

◆ getDepthIntrinsicParam()

bool realsense2Driver::getDepthIntrinsicParam ( Property intrinsic)
overridevirtual

Get the intrinsic parameters of the depth camera.

Parameters
intrinsicreturn a Property containing intrinsic parameters of the optical model of the camera.
Returns
true if success

The yarp::os::Property describing the intrinsic parameters is expected to be in the form:

Parameter name SubParameter Type Units Default Value Required Description Notes
physFocalLength - double m - Yes Physical focal length of the lens in meters
focalLengthX - double pixel - Yes Horizontal component of the focal length as a multiple of pixel width
focalLengthY - double pixel - Yes Vertical component of the focal length as a multiple of pixel height
principalPointX - double pixel - Yes X coordinate of the principal point
principalPointY - double pixel - Yes Y coordinate of the principal point
rectificationMatrix - 4x4 double matrix - - Yes Matrix that describes the lens' distortion
distortionModel - string - - Yes Reference to group of parameters describing the distortion model of the camera, example 'cameraDistortionModelGroup' This is another group's name to be searched for in the config file
cameraDistortionModelGroup
name string - - Yes Name of the distortion model, see notes right now only 'plumb_bob' is supported
k1 double - - Yes Radial distortion coefficient of the lens
k2 double - - Yes Radial distortion coefficient of the lens
k3 double - - Yes Radial distortion coefficient of the lens
t1 double - - Yes Tangential distortion of the lens
t2 double - - Yes Tangential distortion of the lens

Implements yarp::dev::IRGBDSensor.

Definition at line 1005 of file realsense2Driver.cpp.

◆ getDepthMirroring()

bool realsense2Driver::getDepthMirroring ( bool mirror)
overridevirtual

Get the mirroring setting of the sensor.

Parameters
mirrortrue if image is mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IDepthVisualParams.

Definition at line 1045 of file realsense2Driver.cpp.

◆ getDepthWidth()

int realsense2Driver::getDepthWidth ( )
overridevirtual

Return the height of each frame.

Returns
depth image height

Implements yarp::dev::IRGBDSensor.

Definition at line 991 of file realsense2Driver.cpp.

◆ getExtrinsicParam()

bool realsense2Driver::getExtrinsicParam ( yarp::sig::Matrix extrinsic)
overridevirtual

Get the extrinsic parameters from the device.

Parameters
extrinsicreturn a rototranslation matrix describing the position of the depth optical frame with respect to the rgb frame
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 1057 of file realsense2Driver.cpp.

◆ getFeature() [1/2]

bool realsense2Driver::getFeature ( int  feature,
double value 
)
overridevirtual

Get the current value for the requested feature.

Parameters
featurethe identifier of the feature to read
valuepointer to current value of the feature, from 0 to 1 expressed as a percentage
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1322 of file realsense2Driver.cpp.

◆ getFeature() [2/2]

bool realsense2Driver::getFeature ( int  feature,
double value1,
double value2 
)
overridevirtual

Get the current value for the requested feature.

Parameters
featurethe identifier of the feaature to read
value1returns the current value of the feature, from 0 to 1 expressed as a percentage
value2returns the current value of the feature, from 0 to 1 expressed as a percentage
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1389 of file realsense2Driver.cpp.

◆ getImage() [1/3]

bool realsense2Driver::getImage ( depthImage Frame,
Stamp timeStamp,
const rs2::frameset &  sourceFrame 
)
protected

Definition at line 1146 of file realsense2Driver.cpp.

◆ getImage() [2/3]

bool realsense2Driver::getImage ( FlexImage Frame,
Stamp timeStamp,
rs2::frameset &  sourceFrame 
)
protected

Definition at line 1106 of file realsense2Driver.cpp.

◆ getImage() [3/3]

bool realsense2Driver::getImage ( yarp::sig::ImageOf< yarp::sig::PixelMono > &  image)
overridevirtual

Get an image from the frame grabber.

Parameters
imagethe image to be filled
Returns
true/false upon success/failure

Implements yarp::dev::IFrameGrabberOf< yarp::sig::ImageOf< yarp::sig::PixelMono > >.

Definition at line 1633 of file realsense2Driver.cpp.

◆ getImages()

bool realsense2Driver::getImages ( FlexImage colorFrame,
depthImage depthFrame,
Stamp colorStamp = NULL,
Stamp depthStamp = NULL 
)
override

Definition at line 1192 of file realsense2Driver.cpp.

◆ getLastErrorMsg()

std::string realsense2Driver::getLastErrorMsg ( Stamp timeStamp = NULL)
overridevirtual

Return an error message in case of error.

For debugging purpose and user notification. Error message will be reset after any successful command

Returns
A string explaining the last error occurred.

Implements yarp::dev::IRGBDSensor.

Definition at line 1219 of file realsense2Driver.cpp.

◆ getMode()

bool realsense2Driver::getMode ( int  feature,
FeatureMode mode 
)
overridevirtual

Get the current mode for the feature.

Parameters
featurethe identifier of the feature to change
hasAutoflag true if the feature is has 'auto' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1576 of file realsense2Driver.cpp.

◆ getRgbFOV()

bool realsense2Driver::getRgbFOV ( double horizontalFov,
double verticalFov 
)
overridevirtual

Get the field of view (FOV) of the rgb camera.

Parameters
horizontalFovwill return the value of the horizontal fov in degrees
verticalFovwill return the value of the vertical fov in degrees
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 960 of file realsense2Driver.cpp.

◆ getRgbHeight()

int realsense2Driver::getRgbHeight ( )
overridevirtual

Return the height of each frame.

Returns
rgb image height

Implements yarp::dev::IRGBDSensor.

Definition at line 861 of file realsense2Driver.cpp.

◆ getRgbImage()

bool realsense2Driver::getRgbImage ( FlexImage rgbImage,
Stamp timeStamp = nullptr 
)
overridevirtual

Get the rgb frame from the device.

The pixel type of the source image will usually be set as a VOCAB_PIXEL_RGB, but the user can call the function with the pixel type of his/her choice. The conversion if possible, will be done automatically on client side (TO BO VERIFIED). Note: this will consume CPU power because it will not use GPU optimization. Use VOCAB_PIXEL_RGB for best performances.

Parameters
rgbImagethe image to be filled.
timeStamptime in which the image was acquired. Optional, ignored if nullptr.
Returns
True on success

Implements yarp::dev::IRGBDSensor.

Definition at line 1062 of file realsense2Driver.cpp.

◆ getRgbIntrinsicParam()

bool realsense2Driver::getRgbIntrinsicParam ( Property intrinsic)
overridevirtual

Get the intrinsic parameters of the rgb camera.

Parameters
intrinsicreturn a Property containing intrinsic parameters of the optical model of the camera.
Returns
true if success

The yarp::os::Property describing the intrinsic parameters is expected to be in the form:

Parameter name SubParameter Type Units Default Value Required Description Notes
physFocalLength - double m - Yes Physical focal length of the lens in meters
focalLengthX - double pixel - Yes Horizontal component of the focal length as a multiple of pixel width
focalLengthY - double pixel - Yes Vertical component of the focal length as a multiple of pixel height
principalPointX - double pixel - Yes X coordinate of the principal point
principalPointY - double pixel - Yes Y coordinate of the principal point
rectificationMatrix - 4x4 double matrix - - Yes Matrix that describes the lens' distortion
distortionModel - string - - Yes Reference to group of parameters describing the distortion model of the camera, example 'cameraDistortionModelGroup' This is another group's name to be searched for in the config file
cameraDistortionModelGroup
name string - - Yes Name of the distortion model, see notes right now only 'plumb_bob' is supported
k1 double - - Yes Radial distortion coefficient of the lens
k2 double - - Yes Radial distortion coefficient of the lens
k3 double - - Yes Radial distortion coefficient of the lens
t1 double - - Yes Tangential distortion of the lens
t2 double - - Yes Tangential distortion of the lens

Implements yarp::dev::IRGBDSensor.

Definition at line 981 of file realsense2Driver.cpp.

◆ getRgbMirroring()

bool realsense2Driver::getRgbMirroring ( bool mirror)
overridevirtual

Get the mirroring setting of the sensor.

Parameters
mirrortrue if image is mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IRgbVisualParams.

Definition at line 969 of file realsense2Driver.cpp.

◆ getRgbResolution()

bool realsense2Driver::getRgbResolution ( int width,
int height 
)
overridevirtual

Get the resolution of the rgb image from the camera.

Parameters
widthimage width
heightimage height
Returns
true on success

Reimplemented from yarp::dev::IRGBDSensor.

Definition at line 877 of file realsense2Driver.cpp.

◆ getRgbSupportedConfigurations()

bool realsense2Driver::getRgbSupportedConfigurations ( yarp::sig::VectorOf< yarp::dev::CameraConfig > &  configurations)
overridevirtual

Get the possible configurations of the camera.

Parameters
configurationslist of camera supported configurations as CameraConfig type
Returns
true on success

Reimplemented from yarp::dev::IRGBDSensor.

Definition at line 871 of file realsense2Driver.cpp.

◆ getRgbWidth()

int realsense2Driver::getRgbWidth ( )
overridevirtual

Return the width of each frame.

Returns
rgb image width

Implements yarp::dev::IRGBDSensor.

Definition at line 866 of file realsense2Driver.cpp.

◆ getSensorStatus()

IRGBDSensor::RGBDSensor_status realsense2Driver::getSensorStatus ( )
overridevirtual

Get the surrent status of the sensor, using enum type.

Returns
an enum representing the status of the robot or an error code if any error is present

Implements yarp::dev::IRGBDSensor.

Definition at line 1214 of file realsense2Driver.cpp.

◆ hasAuto()

bool realsense2Driver::hasAuto ( int  feature,
bool hasAuto 
)
overridevirtual

Check if the requested feature has the 'auto' mode.

Parameters
featurethe identifier of the feature to check
hasAutoflag true if the feature is has 'auto' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1476 of file realsense2Driver.cpp.

◆ hasFeature()

bool realsense2Driver::hasFeature ( int  feature,
bool hasFeature 
)
overridevirtual

Check if camera has the requested feature (saturation, brightness ... )

Parameters
featurethe identifier of the feature to check
hasFeatureflag value: true if the feature is present, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1231 of file realsense2Driver.cpp.

◆ hasManual()

bool realsense2Driver::hasManual ( int  feature,
bool hasManual 
)
overridevirtual

Check if the requested feature has the 'manual' mode.

Parameters
featurethe identifier of the feature to check
hasAutoflag true if the feature is has 'manual' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1495 of file realsense2Driver.cpp.

◆ hasOnePush()

bool realsense2Driver::hasOnePush ( int  feature,
bool hasOnePush 
)
overridevirtual

Check if the requested feature has the 'onePush' mode.

Parameters
featurethe identifier of the feature to check
hasAutoflag true if the feature is has 'onePush' mode, false otherwise
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1515 of file realsense2Driver.cpp.

◆ hasOnOff()

bool realsense2Driver::hasOnOff ( int  feature,
bool HasOnOff 
)
overridevirtual

Check if the camera has the ability to turn on/off the requested feature.

Parameters
featurethe identifier of the feature to change
hasOnOffflag true if this feature can be turned on/off, false otherwise.
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1395 of file realsense2Driver.cpp.

◆ height()

int realsense2Driver::height ( ) const
overridevirtual

Return the height of each frame.

Returns
image height

Implements yarp::dev::IFrameGrabberImageBase.

Definition at line 1673 of file realsense2Driver.cpp.

◆ initializeRealsenseDevice()

bool realsense2Driver::initializeRealsenseDevice ( )
inlineprotected

Definition at line 530 of file realsense2Driver.cpp.

◆ open()

bool realsense2Driver::open ( yarp::os::Searchable config)
overridevirtual

Open the DeviceDriver.

Parameters
configis a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device).
Returns
true/false upon success/failure

Reimplemented from yarp::dev::DeviceDriver.

Reimplemented in realsense2withIMUDriver.

Definition at line 809 of file realsense2Driver.cpp.

◆ pipelineRestart()

bool realsense2Driver::pipelineRestart ( )
protected

Definition at line 483 of file realsense2Driver.cpp.

◆ pipelineShutdown()

bool realsense2Driver::pipelineShutdown ( )
protected

Definition at line 468 of file realsense2Driver.cpp.

◆ pipelineStartup()

bool realsense2Driver::pipelineStartup ( )
protected

Definition at line 453 of file realsense2Driver.cpp.

◆ setActive()

bool realsense2Driver::setActive ( int  feature,
bool  onoff 
)
overridevirtual

Set the requested feature on or off.

Parameters
featurethe identifier of the feature to change
onofftrue to activate, off to deactivate the feature
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1414 of file realsense2Driver.cpp.

◆ setDepthAccuracy()

bool realsense2Driver::setDepthAccuracy ( double  accuracy)
overridevirtual

Set the minimum detectable variation in distance [meter] when possible.

Parameters
thedesired resolution in meters.
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 950 of file realsense2Driver.cpp.

◆ setDepthClipPlanes()

bool realsense2Driver::setDepthClipPlanes ( double  nearPlane,
double  farPlane 
)
overridevirtual

Set the clipping planes of the sensor.

Parameters
nearPlaneminimum distance at which the sensor start measuring. Object closer than this distance will not be detected.
farPlanemaximum distance beyond which the sensor stop measuring. Object farther than this distance will not be detected.
Returns
true if success

Implements yarp::dev::IRGBDSensor.

Definition at line 1034 of file realsense2Driver.cpp.

◆ setDepthFOV()

bool realsense2Driver::setDepthFOV ( double  horizontalFov,
double  verticalFov 
)
overridevirtual

Set the field of view (FOV) of the depth camera.

Parameters
horizontalFovwill set the value of the horizontal fov in degrees
verticalFovwill set the value of the vertical fov in degrees
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 944 of file realsense2Driver.cpp.

◆ setDepthMirroring()

bool realsense2Driver::setDepthMirroring ( bool  mirror)
overridevirtual

Set the mirroring setting of the sensor.

Parameters
mirrortrue if image should be mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IDepthVisualParams.

Definition at line 1051 of file realsense2Driver.cpp.

◆ setDepthResolution()

bool realsense2Driver::setDepthResolution ( int  width,
int  height 
)
overridevirtual

Set the resolution of the depth image from the camera.

Parameters
widthimage width
heightimage height
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 884 of file realsense2Driver.cpp.

◆ setFeature() [1/2]

bool realsense2Driver::setFeature ( int  feature,
double  value 
)
overridevirtual

Set the requested feature to a value (saturation, brightness ... )

Parameters
featurethe identifier of the feature to change
valuenew value of the feature, range from 0 to 1 expressed as a percentage
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1245 of file realsense2Driver.cpp.

◆ setFeature() [2/2]

bool realsense2Driver::setFeature ( int  feature,
double  value1,
double  value2 
)
overridevirtual

Set the requested feature to a value using 2 params (like white balance)

Parameters
featurethe identifier of the feature to change
value1first param, from 0 to 1 expressed as a percentage
value2second param, from 0 to 1 expressed as a percentage
Returns
returns true if success, false otherwise (e.g. the interface is not implemented)

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1383 of file realsense2Driver.cpp.

◆ setFramerate()

bool realsense2Driver::setFramerate ( const int  _fps)
protected

Definition at line 493 of file realsense2Driver.cpp.

◆ setMode()

bool realsense2Driver::setMode ( int  feature,
FeatureMode  mode 
)
overridevirtual

Set the requested mode for the feature.

Parameters
featurethe identifier of the feature to change
auto_onofftrue to activate 'auto' mode, false to activate 'manual' mode
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1527 of file realsense2Driver.cpp.

◆ setOnePush()

bool realsense2Driver::setOnePush ( int  feature)
overridevirtual

Set the requested feature to a value (saturation, brightness ... )

Parameters
featurethe identifier of the feature to change
valuenew value of the feature, from 0 to 1 as a percentage of param range
Returns
returns true on success, false on failure.

Implements yarp::dev::IFrameGrabberControls.

Definition at line 1612 of file realsense2Driver.cpp.

◆ setParams()

bool realsense2Driver::setParams ( )
inlineprotected

Definition at line 680 of file realsense2Driver.cpp.

◆ setRgbFOV()

bool realsense2Driver::setRgbFOV ( double  horizontalFov,
double  verticalFov 
)
overridevirtual

Set the field of view (FOV) of the rgb camera.

Parameters
horizontalFovwill set the value of the horizontal fov in degrees
verticalFovwill set the value of the vertical fov in degrees
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 938 of file realsense2Driver.cpp.

◆ setRgbMirroring()

bool realsense2Driver::setRgbMirroring ( bool  mirror)
overridevirtual

Set the mirroring setting of the sensor.

Parameters
mirrortrue if image should be mirrored, false otherwise
Returns
true if success

Implements yarp::dev::IRgbVisualParams.

Definition at line 975 of file realsense2Driver.cpp.

◆ setRgbResolution()

bool realsense2Driver::setRgbResolution ( int  width,
int  height 
)
overridevirtual

Set the resolution of the rgb image from the camera.

Parameters
widthimage width
heightimage height
Returns
true on success

Implements yarp::dev::IRGBDSensor.

Definition at line 904 of file realsense2Driver.cpp.

◆ updateTransformations()

void realsense2Driver::updateTransformations ( )
protected

Definition at line 661 of file realsense2Driver.cpp.

◆ width()

int realsense2Driver::width ( ) const
overridevirtual

Return the width of each frame.

Returns
image width

Implements yarp::dev::IFrameGrabberImageBase.

Definition at line 1678 of file realsense2Driver.cpp.

Member Data Documentation

◆ m_alignment_stream

rs2_stream realsense2Driver::m_alignment_stream {RS2_STREAM_COLOR}
protected

Definition at line 133 of file realsense2Driver.h.

◆ m_cfg

rs2::config realsense2Driver::m_cfg
protected

Definition at line 124 of file realsense2Driver.h.

◆ m_color_intrin

rs2_intrinsics realsense2Driver::m_color_intrin {}
protected

Definition at line 131 of file realsense2Driver.h.

◆ m_color_sensor

rs2::sensor* realsense2Driver::m_color_sensor
protected

Definition at line 130 of file realsense2Driver.h.

◆ m_color_to_depth

rs2_extrinsics realsense2Driver::m_color_to_depth {}
protected

Definition at line 132 of file realsense2Driver.h.

◆ m_ctx

rs2::context realsense2Driver::m_ctx
protected

Definition at line 123 of file realsense2Driver.h.

◆ m_depth_intrin

rs2_intrinsics realsense2Driver::m_depth_intrin {}
protected

Definition at line 131 of file realsense2Driver.h.

◆ m_depth_sensor

rs2::sensor* realsense2Driver::m_depth_sensor
protected

Definition at line 129 of file realsense2Driver.h.

◆ m_depth_stamp

yarp::os::Stamp realsense2Driver::m_depth_stamp
protected

Definition at line 141 of file realsense2Driver.h.

◆ m_depth_to_color

rs2_extrinsics realsense2Driver::m_depth_to_color {}
protected

Definition at line 132 of file realsense2Driver.h.

◆ m_depthDecimalNum

int realsense2Driver::m_depthDecimalNum {0}
protected

Definition at line 138 of file realsense2Driver.h.

◆ m_depthQuantizationEnabled

bool realsense2Driver::m_depthQuantizationEnabled {false}
protected

Definition at line 137 of file realsense2Driver.h.

◆ m_device

rs2::device realsense2Driver::m_device
protected

Definition at line 127 of file realsense2Driver.h.

◆ m_fps

int realsense2Driver::m_fps
protected

Definition at line 148 of file realsense2Driver.h.

◆ m_infrared_intrin

rs2_intrinsics realsense2Driver::m_infrared_intrin {}
protected

Definition at line 131 of file realsense2Driver.h.

◆ m_initialized

bool realsense2Driver::m_initialized
protected

Definition at line 145 of file realsense2Driver.h.

◆ m_lastError

std::string realsense2Driver::m_lastError
mutableprotected

Definition at line 142 of file realsense2Driver.h.

◆ m_mutex

std::mutex realsense2Driver::m_mutex
mutableprotected

Definition at line 122 of file realsense2Driver.h.

◆ m_needAlignment

bool realsense2Driver::m_needAlignment
protected

Definition at line 147 of file realsense2Driver.h.

◆ m_paramParser

yarp::dev::RGBDSensorParamParser realsense2Driver::m_paramParser
protected

Definition at line 143 of file realsense2Driver.h.

◆ m_pipeline

rs2::pipeline realsense2Driver::m_pipeline
protected

Definition at line 125 of file realsense2Driver.h.

◆ m_profile

rs2::pipeline_profile realsense2Driver::m_profile
protected

Definition at line 126 of file realsense2Driver.h.

◆ m_rgb_stamp

yarp::os::Stamp realsense2Driver::m_rgb_stamp
protected

Definition at line 140 of file realsense2Driver.h.

◆ m_rotateImage180

bool realsense2Driver::m_rotateImage180 {false}
protected

Definition at line 150 of file realsense2Driver.h.

◆ m_scale

float realsense2Driver::m_scale
protected

Definition at line 149 of file realsense2Driver.h.

◆ m_sensors

std::vector<rs2::sensor> realsense2Driver::m_sensors
protected

Definition at line 128 of file realsense2Driver.h.

◆ m_stereoMode

bool realsense2Driver::m_stereoMode
protected

Definition at line 146 of file realsense2Driver.h.

◆ m_supportedFeatures

std::vector<cameraFeature_id_t> realsense2Driver::m_supportedFeatures
protected

Definition at line 151 of file realsense2Driver.h.

◆ m_verbose

bool realsense2Driver::m_verbose
protected

Definition at line 144 of file realsense2Driver.h.


The documentation for this class was generated from the following files: