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 | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (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 DeviceDriver * | getImplementation () |
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_t > | m_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 } |
Definition at line 29 of file realsense2Driver.h.
realsense2Driver::realsense2Driver | ( | ) |
Definition at line 432 of file realsense2Driver.cpp.
|
overridedefault |
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Reimplemented in realsense2withIMUDriver.
Definition at line 855 of file realsense2Driver.cpp.
|
protected |
Definition at line 521 of file realsense2Driver.cpp.
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 1444 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 1224 of file realsense2Driver.cpp.
|
overridevirtual |
Get the minimum detectable variation in distance [meter].
Implements yarp::dev::IRGBDSensor.
Definition at line 1010 of file realsense2Driver.cpp.
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 1020 of file realsense2Driver.cpp.
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 996 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 986 of file realsense2Driver.cpp.
|
override |
Definition at line 1084 of file realsense2Driver.cpp.
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 | |
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.
Get the mirroring setting of the sensor.
mirror | true if image is mirrored, false otherwise |
Implements yarp::dev::IDepthVisualParams.
Definition at line 1045 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 991 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 1057 of file realsense2Driver.cpp.
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 1322 of file realsense2Driver.cpp.
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 1389 of file realsense2Driver.cpp.
|
protected |
Definition at line 1146 of file realsense2Driver.cpp.
|
protected |
Definition at line 1106 of file realsense2Driver.cpp.
|
overridevirtual |
Get an image from the frame grabber.
image | the image to be filled |
Implements yarp::dev::IFrameGrabberOf< yarp::sig::ImageOf< yarp::sig::PixelMono > >.
Definition at line 1633 of file realsense2Driver.cpp.
|
override |
Definition at line 1192 of file realsense2Driver.cpp.
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 1219 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 1576 of file realsense2Driver.cpp.
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 960 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 861 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 1062 of file realsense2Driver.cpp.
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 | |
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.
Get the mirroring setting of the sensor.
mirror | true if image is mirrored, false otherwise |
Implements yarp::dev::IRgbVisualParams.
Definition at line 969 of file realsense2Driver.cpp.
Get the resolution of the rgb image from the camera.
width | image width |
height | image height |
Reimplemented from yarp::dev::IRGBDSensor.
Definition at line 877 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 871 of file realsense2Driver.cpp.
|
overridevirtual |
Return the width of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 866 of file realsense2Driver.cpp.
|
overridevirtual |
Get the surrent status of the sensor, using enum type.
Implements yarp::dev::IRGBDSensor.
Definition at line 1214 of file realsense2Driver.cpp.
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 1476 of file realsense2Driver.cpp.
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 1231 of file realsense2Driver.cpp.
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 1495 of file realsense2Driver.cpp.
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 1515 of file realsense2Driver.cpp.
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 1395 of file realsense2Driver.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IFrameGrabberImageBase.
Definition at line 1673 of file realsense2Driver.cpp.
|
inlineprotected |
Definition at line 530 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 809 of file realsense2Driver.cpp.
|
protected |
Definition at line 483 of file realsense2Driver.cpp.
|
protected |
Definition at line 468 of file realsense2Driver.cpp.
|
protected |
Definition at line 453 of file realsense2Driver.cpp.
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 1414 of file realsense2Driver.cpp.
Set the minimum detectable variation in distance [meter] when possible.
the | desired resolution in meters. |
Implements yarp::dev::IRGBDSensor.
Definition at line 950 of file realsense2Driver.cpp.
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 1034 of file realsense2Driver.cpp.
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 944 of file realsense2Driver.cpp.
Set the mirroring setting of the sensor.
mirror | true if image should be mirrored, false otherwise |
Implements yarp::dev::IDepthVisualParams.
Definition at line 1051 of file realsense2Driver.cpp.
Set the resolution of the depth image from the camera.
width | image width |
height | image height |
Implements yarp::dev::IRGBDSensor.
Definition at line 884 of file realsense2Driver.cpp.
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 1245 of file realsense2Driver.cpp.
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 1383 of file realsense2Driver.cpp.
Definition at line 493 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 1527 of file realsense2Driver.cpp.
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 1612 of file realsense2Driver.cpp.
|
inlineprotected |
Definition at line 680 of file realsense2Driver.cpp.
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 938 of file realsense2Driver.cpp.
Set the mirroring setting of the sensor.
mirror | true if image should be mirrored, false otherwise |
Implements yarp::dev::IRgbVisualParams.
Definition at line 975 of file realsense2Driver.cpp.
Set the resolution of the rgb image from the camera.
width | image width |
height | image height |
Implements yarp::dev::IRGBDSensor.
Definition at line 904 of file realsense2Driver.cpp.
|
protected |
Definition at line 661 of file realsense2Driver.cpp.
|
overridevirtual |
Return the width of each frame.
Implements yarp::dev::IFrameGrabberImageBase.
Definition at line 1678 of file realsense2Driver.cpp.
|
protected |
Definition at line 133 of file realsense2Driver.h.
|
protected |
Definition at line 124 of file realsense2Driver.h.
|
protected |
Definition at line 131 of file realsense2Driver.h.
|
protected |
Definition at line 130 of file realsense2Driver.h.
|
protected |
Definition at line 132 of file realsense2Driver.h.
|
protected |
Definition at line 123 of file realsense2Driver.h.
|
protected |
Definition at line 131 of file realsense2Driver.h.
|
protected |
Definition at line 129 of file realsense2Driver.h.
|
protected |
Definition at line 141 of file realsense2Driver.h.
|
protected |
Definition at line 132 of file realsense2Driver.h.
|
protected |
Definition at line 138 of file realsense2Driver.h.
|
protected |
Definition at line 137 of file realsense2Driver.h.
|
protected |
Definition at line 127 of file realsense2Driver.h.
|
protected |
Definition at line 148 of file realsense2Driver.h.
|
protected |
Definition at line 131 of file realsense2Driver.h.
|
protected |
Definition at line 145 of file realsense2Driver.h.
|
mutableprotected |
Definition at line 142 of file realsense2Driver.h.
|
mutableprotected |
Definition at line 122 of file realsense2Driver.h.
|
protected |
Definition at line 147 of file realsense2Driver.h.
|
protected |
Definition at line 143 of file realsense2Driver.h.
|
protected |
Definition at line 125 of file realsense2Driver.h.
|
protected |
Definition at line 126 of file realsense2Driver.h.
|
protected |
Definition at line 140 of file realsense2Driver.h.
|
protected |
Definition at line 150 of file realsense2Driver.h.
|
protected |
Definition at line 149 of file realsense2Driver.h.
|
protected |
Definition at line 128 of file realsense2Driver.h.
|
protected |
Definition at line 146 of file realsense2Driver.h.
|
protected |
Definition at line 151 of file realsense2Driver.h.
|
protected |
Definition at line 144 of file realsense2Driver.h.