realsense2
: driver for realsense2 compatible devices.
More...
#include <realsense2/realsense2Driver.h>
realsense2
: driver for realsense2 compatible devices.
@ingroup dev_impl_media
This device driver exposes the IRGBDSensor and IFrameGrabberControls interfaces to read the images and operate on the available settings. See the documentation for more details about each interface.
This device is paired with its server called RGBDSensorWrapper to stream the images and perform remote operations.
The configuration file is subdivided into 2 major sections called "SETTINGS" and "HW_DESCRIPTION".
The "SETTINGS" section is meant for read/write parameters, meaning parameters which can be get and set by the device. A common case of setting is the image resolution in pixel. This setting will be read by the device and it'll be applied in the startup phase. If the setting fails, the device will terminate the execution with a error message.
The "HW_DESCRIPTION" section is meant for read only parameters which describe the hardware property of the device and cannot be provided by the device through software API. A common case is the 'Field Of View' property, which may or may not be supported by the physical device. When a property is present in the HW_DESCRIPTION group, the YARP RGBDSensorClient will report this value when asked for and setting will be disabled. This group can also be used to by-pass realsense2 API in case some functionality is not correctly working with the current device. For example the 'clipPlanes' property may return incorrect values or values using non-standard measurement unit. In this case using the HW_DESCRIPTION, a user can override the value got from OpenNI2 API with a custom value.
YARP device name |
---|
realsense2 |
Parameters used by this device are:
Parameter name | SubParameter | Type | Read / write | Units | Default Value | Required | Description | Notes |
---|---|---|---|---|---|---|---|---|
stereoMode | - | bool | Read / write | false | No(see notes) | Flag for using the realsense as stereo camera | This option is to use it with yarp::dev::ServerGrabber as network wrapper. The stereo images provided are raw images(yarp::sig::PixelMono) and note that not all the realsense devices have the stereo streams. | |
verbose | - | bool | Read / write | false | No | Flag for enabling debug prints | ||
SETTINGS | - | group | Read / write | - | - | Yes | Initial setting of the device. | Properties must be read/writable in order for setting to work |
rgbResolution | int, int | Read / write | pixels | - | Yes | Size of rgb image in pixels | 2 values expected as height, width | |
depthResolution | int, int | Read / write | pixels | - | Yes | Size of depth image in pixels | Values are height, width | |
accuracy | double | Read / write | meters | - | No | Accuracy of the device, as the depth measurement error at 1 meter distance | Note that only few realsense devices allows to set it | |
framerate | int | Read / Write | fps | 30 | No | Framerate of the sensor | ||
enableEmitter | bool | Read / Write | - | true | No | Flag for enabling the IR emitter(if supported by the sensor) | ||
needAlignment | bool | Read / Write | - | true | No | Flag for enabling the alignment of the depth frame over the rgb frame | This option is deprecated, please use alignmentFrame instead. | |
alignmentFrame | string | Read / Write | - | RGB | No | This parameter specifies the frame to which the frames RGB and Depth will be aligned. | The accepted values are RGB, Depth, None. This operation could be heavy, set it to None to increase the fps. | |
HW_DESCRIPTION | - | group | - | - | Yes | Hardware description of device property. | Read only property. Setting will be disabled | |
clipPlanes | double, double | Read / write | meters | - | No | Minimum and maximum distance at which an object is seen by the depth sensor | parameter introduced mainly for simulated sensors, it can be used to set the clip planes if Openni gives wrong values |
Configuration file using .ini format, for using as RGBD device:
Configuration file using .ini format, for using as stereo camera:
Definition at line 121 of file realsense2Driver.h.
Public Member Functions | |
realsense2Driver () | |
~realsense2Driver () override=default | |
bool | open (yarp::os::Searchable &config) override |
Open the DeviceDriver. More... | |
bool | close () override |
Close the DeviceDriver. More... | |
int | getRgbHeight () override |
Return the height of each frame. More... | |
int | getRgbWidth () override |
Return the width of each frame. More... | |
bool | getRgbSupportedConfigurations (yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override |
Get the possible configurations of the camera. More... | |
bool | getRgbResolution (int &width, int &height) override |
Get the resolution of the rgb image from the camera. More... | |
bool | setRgbResolution (int width, int height) override |
Set the resolution of the rgb image from the camera. More... | |
bool | getRgbFOV (double &horizontalFov, double &verticalFov) override |
Get the field of view (FOV) of the rgb camera. More... | |
bool | setRgbFOV (double horizontalFov, double verticalFov) override |
Set the field of view (FOV) of the rgb camera. More... | |
bool | getRgbMirroring (bool &mirror) override |
Get the mirroring setting of the sensor. More... | |
bool | setRgbMirroring (bool mirror) override |
Set the mirroring setting of the sensor. More... | |
bool | getRgbIntrinsicParam (Property &intrinsic) override |
Get the intrinsic parameters of the rgb camera. More... | |
int | getDepthHeight () override |
Return the height of each frame. More... | |
int | getDepthWidth () override |
Return the height of each frame. More... | |
bool | setDepthResolution (int width, int height) override |
Set the resolution of the depth image from the camera. More... | |
bool | getDepthFOV (double &horizontalFov, double &verticalFov) override |
Get the field of view (FOV) of the depth camera. More... | |
bool | setDepthFOV (double horizontalFov, double verticalFov) override |
Set the field of view (FOV) of the depth camera. More... | |
bool | getDepthIntrinsicParam (Property &intrinsic) override |
Get the intrinsic parameters of the depth camera. More... | |
double | getDepthAccuracy () override |
Get the minimum detectable variation in distance [meter]. More... | |
bool | setDepthAccuracy (double accuracy) override |
Set the minimum detectable variation in distance [meter] when possible. More... | |
bool | getDepthClipPlanes (double &nearPlane, double &farPlane) override |
Get the clipping planes of the sensor. More... | |
bool | setDepthClipPlanes (double nearPlane, double farPlane) override |
Set the clipping planes of the sensor. More... | |
bool | getDepthMirroring (bool &mirror) override |
Get the mirroring setting of the sensor. More... | |
bool | setDepthMirroring (bool mirror) override |
Set the mirroring setting of the sensor. More... | |
bool | getExtrinsicParam (yarp::sig::Matrix &extrinsic) override |
Get the extrinsic parameters from the device. More... | |
bool | getRgbImage (FlexImage &rgbImage, Stamp *timeStamp=nullptr) override |
Get the rgb frame from the device. More... | |
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. More... | |
std::string | getLastErrorMsg (Stamp *timeStamp=NULL) override |
Return an error message in case of error. More... | |
bool | getCameraDescription (CameraDescriptor *camera) override |
Get a basic description of the camera hw. More... | |
bool | hasFeature (int feature, bool *hasFeature) override |
Check if camera has the requested feature (saturation, brightness ... More... | |
bool | setFeature (int feature, double value) override |
Set the requested feature to a value (saturation, brightness ... More... | |
bool | getFeature (int feature, double *value) override |
Get the current value for the requested feature. More... | |
bool | setFeature (int feature, double value1, double value2) override |
Set the requested feature to a value using 2 params (like white balance) More... | |
bool | getFeature (int feature, double *value1, double *value2) override |
Get the current value for the requested feature. More... | |
bool | hasOnOff (int feature, bool *HasOnOff) override |
Check if the camera has the ability to turn on/off the requested feature. More... | |
bool | setActive (int feature, bool onoff) override |
Set the requested feature on or off. More... | |
bool | getActive (int feature, bool *isActive) override |
Get the current status of the feature, on or off. More... | |
bool | hasAuto (int feature, bool *hasAuto) override |
Check if the requested feature has the 'auto' mode. More... | |
bool | hasManual (int feature, bool *hasManual) override |
Check if the requested feature has the 'manual' mode. More... | |
bool | hasOnePush (int feature, bool *hasOnePush) override |
Check if the requested feature has the 'onePush' mode. More... | |
bool | setMode (int feature, FeatureMode mode) override |
Set the requested mode for the feature. More... | |
bool | getMode (int feature, FeatureMode *mode) override |
Get the current mode for the feature. More... | |
bool | setOnePush (int feature) override |
Set the requested feature to a value (saturation, brightness ... More... | |
bool | getImage (yarp::sig::ImageOf< yarp::sig::PixelMono > &image) override |
Get a raw image from the frame grabber. More... | |
int | height () const override |
Return the height of each frame. More... | |
int | width () const override |
Return the width of each frame. More... | |
![]() | |
~DeviceDriver () override=default | |
Destructor. More... | |
template<class T > | |
bool | view (T *&x) |
Get an interface to the device driver. More... | |
virtual DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. More... | |
![]() | |
virtual | ~IConfig () |
Destructor. More... | |
virtual bool | configure (Searchable &config) |
Change online parameters. More... | |
![]() | |
virtual | ~IFrameGrabberControls () |
Destructor. More... | |
virtual bool | setBrightness (double v) |
Set the brightness. More... | |
virtual bool | setExposure (double v) |
Set the exposure. More... | |
virtual bool | setSharpness (double v) |
Set the sharpness. More... | |
virtual bool | setWhiteBalance (double blue, double red) |
Set the white balance for the frame grabber. More... | |
virtual bool | setHue (double v) |
Set the hue. More... | |
virtual bool | setSaturation (double v) |
Set the saturation. More... | |
virtual bool | setGamma (double v) |
Set the gamma. More... | |
virtual bool | setShutter (double v) |
Set the shutter parameter. More... | |
virtual bool | setGain (double v) |
Set the gain. More... | |
virtual bool | setIris (double v) |
Set the iris. More... | |
virtual double | getBrightness () |
Read the brightness parameter. More... | |
virtual double | getExposure () |
Read the exposure parameter. More... | |
virtual double | getSharpness () |
Read the sharpness parameter. More... | |
virtual bool | getWhiteBalance (double &blue, double &red) |
Read the white balance parameters. More... | |
virtual double | getHue () |
Read the hue parameter. More... | |
virtual double | getSaturation () |
Read the saturation parameter. More... | |
virtual double | getGamma () |
Read the gamma parameter. More... | |
virtual double | getShutter () |
Read the shutter parameter. More... | |
virtual double | getGain () |
Read the gain parameter. More... | |
virtual double | getIris () |
Read the iris parameter. More... | |
cameraFeature_id_t | featureVOCABEnum (int vocab) |
int | featureEnum2Vocab (cameraFeature_id_t _enum) |
std::string | busType2String (BusType type) |
FeatureMode | toFeatureMode (bool _auto) |
![]() | |
virtual | ~IFrameGrabberImageRaw () |
Destructor. More... | |
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 rgb image from the frame grabber, if required demosaicking/color reconstruction is applied. More... | |
![]() | |
virtual | ~IRGBDSensor () |
virtual bool | getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=NULL)=0 |
Get the depth frame from the device. More... | |
virtual bool | getImages (yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=NULL, yarp::os::Stamp *depthStamp=NULL)=0 |
Get the both the color and depth frame in a single call. More... | |
![]() | |
virtual | ~IRgbVisualParams () |
![]() | |
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} |
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 |
std::vector< cameraFeature_id_t > | m_supportedFeatures |
Additional Inherited Members | |
![]() | |
enum | RGBDSensor_status { RGBD_SENSOR_NOT_READY = 0 , RGBD_SENSOR_OK_STANBY = 1 , RGBD_SENSOR_OK_IN_USE = 2 , RGB_SENSOR_ERROR = 3 , DEPTH_SENSOR_ERROR = 4 , RGBD_SENSOR_GENERIC_ERROR = 5 , RGBD_SENSOR_TIMEOUT = 6 } |
realsense2Driver::realsense2Driver | ( | ) |
Definition at line 421 of file realsense2Driver.cpp.
|
overridedefault |
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Reimplemented in realsense2withIMUDriver.
Definition at line 779 of file realsense2Driver.cpp.
|
protected |
Definition at line 510 of file realsense2Driver.cpp.
|
overridevirtual |
Get the current status of the feature, on or off.
feature | the identifier of the feature to check |
isActive | flag true if the feature is active, false otherwise |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1322 of file realsense2Driver.cpp.
|
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.
device | returns an identifier for the bus |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1102 of file realsense2Driver.cpp.
|
overridevirtual |
Get the minimum detectable variation in distance [meter].
Implements yarp::dev::IRGBDSensor.
Definition at line 938 of file realsense2Driver.cpp.
|
overridevirtual |
Get the clipping planes of the sensor.
nearPlane | minimum distance at which the sensor start measuring. Object closer than this distance will not be detected. |
farPlane | maximum distance beyond which the sensor stop measuring. Object farther than this distance will not be detected. |
Implements yarp::dev::IRGBDSensor.
Definition at line 948 of file realsense2Driver.cpp.
|
overridevirtual |
Get the field of view (FOV) of the depth camera.
horizontalFov | will return the value of the horizontal fov in degrees |
verticalFov | will return the value of the vertical fov in degrees |
Implements yarp::dev::IRGBDSensor.
Definition at line 924 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 914 of file realsense2Driver.cpp.
|
override |
Definition at line 1002 of file realsense2Driver.cpp.
|
overridevirtual |
Get the intrinsic parameters of the depth camera.
intrinsic | return a Property containing intrinsic parameters of the optical model of the camera. |
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 | |
retificationMatrix | - | 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 933 of file realsense2Driver.cpp.
|
overridevirtual |
Get the mirroring setting of the sensor.
mirror | true if image is mirrored, false otherwise |
Implements yarp::dev::IDepthVisualParams.
Definition at line 973 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 919 of file realsense2Driver.cpp.
|
overridevirtual |
Get the extrinsic parameters from the device.
extrinsic | return a rototranslation matrix describing the position of the depth optical frame with respect to the rgb frame |
Implements yarp::dev::IRGBDSensor.
Definition at line 985 of file realsense2Driver.cpp.
|
overridevirtual |
Get the current value for the requested feature.
feature | the identifier of the feature to read |
value | pointer to current value of the feature, from 0 to 1 expressed as a percentage |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1200 of file realsense2Driver.cpp.
|
overridevirtual |
Get the current value for the requested feature.
feature | the identifier of the feaature to read |
value1 | returns the current value of the feature, from 0 to 1 expressed as a percentage |
value2 | returns the current value of the feature, from 0 to 1 expressed as a percentage |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1267 of file realsense2Driver.cpp.
|
protected |
Definition at line 1046 of file realsense2Driver.cpp.
|
protected |
Definition at line 1014 of file realsense2Driver.cpp.
|
overridevirtual |
Get a raw image from the frame grabber.
image | the image to be filled |
Implements yarp::dev::IFrameGrabberImageRaw.
Definition at line 1511 of file realsense2Driver.cpp.
|
override |
Definition at line 1080 of file realsense2Driver.cpp.
|
overridevirtual |
Return an error message in case of error.
For debugging purpose and user notification. Error message will be reset after any successful command
Implements yarp::dev::IRGBDSensor.
Definition at line 1097 of file realsense2Driver.cpp.
|
overridevirtual |
Get the current mode for the feature.
feature | the identifier of the feature to change |
hasAuto | flag true if the feature is has 'auto' mode, false otherwise |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1454 of file realsense2Driver.cpp.
|
overridevirtual |
Get the field of view (FOV) of the rgb camera.
horizontalFov | will return the value of the horizontal fov in degrees |
verticalFov | will return the value of the vertical fov in degrees |
Implements yarp::dev::IRGBDSensor.
Definition at line 888 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 785 of file realsense2Driver.cpp.
|
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.
rgbImage | the image to be filled. |
timeStamp | time in which the image was acquired. Optional, ignored if nullptr. |
Implements yarp::dev::IRGBDSensor.
Definition at line 990 of file realsense2Driver.cpp.
|
overridevirtual |
Get the intrinsic parameters of the rgb camera.
intrinsic | return a Property containing intrinsic parameters of the optical model of the camera. |
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 | |
retificationMatrix | - | 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 909 of file realsense2Driver.cpp.
|
overridevirtual |
Get the mirroring setting of the sensor.
mirror | true if image is mirrored, false otherwise |
Implements yarp::dev::IRgbVisualParams.
Definition at line 897 of file realsense2Driver.cpp.
|
overridevirtual |
Get the resolution of the rgb image from the camera.
width | image width |
height | image height |
Reimplemented from yarp::dev::IRGBDSensor.
Definition at line 801 of file realsense2Driver.cpp.
|
overridevirtual |
Get the possible configurations of the camera.
configurations | list of camera supported configurations as CameraConfig type |
Reimplemented from yarp::dev::IRGBDSensor.
Definition at line 795 of file realsense2Driver.cpp.
|
overridevirtual |
Return the width of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 790 of file realsense2Driver.cpp.
|
overridevirtual |
Get the surrent status of the sensor, using enum type.
Implements yarp::dev::IRGBDSensor.
Definition at line 1092 of file realsense2Driver.cpp.
|
overridevirtual |
Check if the requested feature has the 'auto' mode.
feature | the identifier of the feature to check |
hasAuto | flag true if the feature is has 'auto' mode, false otherwise |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1354 of file realsense2Driver.cpp.
|
overridevirtual |
Check if camera has the requested feature (saturation, brightness ...
)
feature | the identifier of the feature to check |
hasFeature | flag value: true if the feature is present, false otherwise |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1109 of file realsense2Driver.cpp.
|
overridevirtual |
Check if the requested feature has the 'manual' mode.
feature | the identifier of the feature to check |
hasAuto | flag true if the feature is has 'manual' mode, false otherwise |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1373 of file realsense2Driver.cpp.
|
overridevirtual |
Check if the requested feature has the 'onePush' mode.
feature | the identifier of the feature to check |
hasAuto | flag true if the feature is has 'onePush' mode, false otherwise |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1393 of file realsense2Driver.cpp.
|
overridevirtual |
Check if the camera has the ability to turn on/off the requested feature.
feature | the identifier of the feature to change |
hasOnOff | flag true if this feature can be turned on/off, false otherwise. |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1273 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IFrameGrabberImageRaw.
Definition at line 1541 of file realsense2Driver.cpp.
|
inlineprotected |
Definition at line 519 of file realsense2Driver.cpp.
|
overridevirtual |
Open the DeviceDriver.
config | is 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). |
Reimplemented from yarp::dev::DeviceDriver.
Reimplemented in realsense2withIMUDriver.
Definition at line 748 of file realsense2Driver.cpp.
|
protected |
Definition at line 472 of file realsense2Driver.cpp.
|
protected |
Definition at line 457 of file realsense2Driver.cpp.
|
protected |
Definition at line 442 of file realsense2Driver.cpp.
|
overridevirtual |
Set the requested feature on or off.
feature | the identifier of the feature to change |
onoff | true to activate, off to deactivate the feature |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1292 of file realsense2Driver.cpp.
|
overridevirtual |
Set the minimum detectable variation in distance [meter] when possible.
the | desired resolution in meters. |
Implements yarp::dev::IRGBDSensor.
Definition at line 878 of file realsense2Driver.cpp.
|
overridevirtual |
Set the clipping planes of the sensor.
nearPlane | minimum distance at which the sensor start measuring. Object closer than this distance will not be detected. |
farPlane | maximum distance beyond which the sensor stop measuring. Object farther than this distance will not be detected. |
Implements yarp::dev::IRGBDSensor.
Definition at line 962 of file realsense2Driver.cpp.
|
overridevirtual |
Set the field of view (FOV) of the depth camera.
horizontalFov | will set the value of the horizontal fov in degrees |
verticalFov | will set the value of the vertical fov in degrees |
Implements yarp::dev::IRGBDSensor.
Definition at line 872 of file realsense2Driver.cpp.
|
overridevirtual |
Set the mirroring setting of the sensor.
mirror | true if image should be mirrored, false otherwise |
Implements yarp::dev::IDepthVisualParams.
Definition at line 979 of file realsense2Driver.cpp.
|
overridevirtual |
Set the resolution of the depth image from the camera.
width | image width |
height | image height |
Implements yarp::dev::IRGBDSensor.
Definition at line 808 of file realsense2Driver.cpp.
|
overridevirtual |
Set the requested feature to a value (saturation, brightness ...
)
feature | the identifier of the feature to change |
value | new value of the feature, range from 0 to 1 expressed as a percentage |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1123 of file realsense2Driver.cpp.
|
overridevirtual |
Set the requested feature to a value using 2 params (like white balance)
feature | the identifier of the feature to change |
value1 | first param, from 0 to 1 expressed as a percentage |
value2 | second param, from 0 to 1 expressed as a percentage |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1261 of file realsense2Driver.cpp.
|
protected |
Definition at line 482 of file realsense2Driver.cpp.
|
overridevirtual |
Set the requested mode for the feature.
feature | the identifier of the feature to change |
auto_onoff | true to activate 'auto' mode, false to activate 'manual' mode |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1405 of file realsense2Driver.cpp.
|
overridevirtual |
Set the requested feature to a value (saturation, brightness ...
)
feature | the identifier of the feature to change |
value | new value of the feature, from 0 to 1 as a percentage of param range |
Implements yarp::dev::IFrameGrabberControls.
Definition at line 1490 of file realsense2Driver.cpp.
|
inlineprotected |
Definition at line 619 of file realsense2Driver.cpp.
|
overridevirtual |
Set the field of view (FOV) of the rgb camera.
horizontalFov | will set the value of the horizontal fov in degrees |
verticalFov | will set the value of the vertical fov in degrees |
Implements yarp::dev::IRGBDSensor.
Definition at line 866 of file realsense2Driver.cpp.
|
overridevirtual |
Set the mirroring setting of the sensor.
mirror | true if image should be mirrored, false otherwise |
Implements yarp::dev::IRgbVisualParams.
Definition at line 903 of file realsense2Driver.cpp.
|
overridevirtual |
Set the resolution of the rgb image from the camera.
width | image width |
height | image height |
Implements yarp::dev::IRGBDSensor.
Definition at line 831 of file realsense2Driver.cpp.
|
protected |
Definition at line 600 of file realsense2Driver.cpp.
|
overridevirtual |
Return the width of each frame.
Implements yarp::dev::IFrameGrabberImageRaw.
Definition at line 1546 of file realsense2Driver.cpp.
|
protected |
Definition at line 224 of file realsense2Driver.h.
|
protected |
Definition at line 215 of file realsense2Driver.h.
|
protected |
Definition at line 222 of file realsense2Driver.h.
|
protected |
Definition at line 221 of file realsense2Driver.h.
|
protected |
Definition at line 223 of file realsense2Driver.h.
|
protected |
Definition at line 214 of file realsense2Driver.h.
|
protected |
Definition at line 222 of file realsense2Driver.h.
|
protected |
Definition at line 220 of file realsense2Driver.h.
|
protected |
Definition at line 228 of file realsense2Driver.h.
|
protected |
Definition at line 223 of file realsense2Driver.h.
|
protected |
Definition at line 218 of file realsense2Driver.h.
|
protected |
Definition at line 235 of file realsense2Driver.h.
|
protected |
Definition at line 222 of file realsense2Driver.h.
|
protected |
Definition at line 232 of file realsense2Driver.h.
|
protected |
Definition at line 229 of file realsense2Driver.h.
|
mutableprotected |
Definition at line 213 of file realsense2Driver.h.
|
protected |
Definition at line 234 of file realsense2Driver.h.
|
protected |
Definition at line 230 of file realsense2Driver.h.
|
protected |
Definition at line 216 of file realsense2Driver.h.
|
protected |
Definition at line 217 of file realsense2Driver.h.
|
protected |
Definition at line 227 of file realsense2Driver.h.
|
protected |
Definition at line 236 of file realsense2Driver.h.
|
protected |
Definition at line 219 of file realsense2Driver.h.
|
protected |
Definition at line 233 of file realsense2Driver.h.
|
protected |
Definition at line 237 of file realsense2Driver.h.
|
protected |
Definition at line 231 of file realsense2Driver.h.