YARP
Yet Another Robot Platform
yarp::dev::RGBDSensorClient Class Reference

#include <RGBDSensorClient/RGBDSensorClient.h>

+ Inheritance diagram for yarp::dev::RGBDSensorClient:

Detailed Description

Description of input parameters

A Network client to receive data from kinect-like devices. This device will read from two streams of data through different ports, one for the color frame and the other one for depth image following Framegrabber and IDepthSensor interfaces specification respectively. See they documentation for more details about each interface.

This device is paired with its server called RGBDSensorWrapper to receive the data streams and perform remote operations.

Parameters required by this device are:

Parameter name SubParameter Type Units Default Value Required Description Notes
localImagePort - string - - Full name of the local port to open, e.g. /myApp/RGBD/rgb_camera:i
localDepthPort - string - - Full name of the local port to open, e.g. /myApp/RGBD/depth_camera:i
localRpcPort - string - - Full name of the local RPC port to open, e.g. /myApp/RGBD/rpc
remoteImagePort - string - - Full name of the port to read color images from, e.g. /robotName/RGBD/image_camera:o
remoteDepthPort - string - - Full name of the port to read depth images from, e.g. /robotName/RGBD/depth_camera:o
remoteRpcPort - string - - Full name of the remote RPC port, e.g. /robotName/RGBD/rpc

Configuration file using .ini format, using subdevice keyword.

device RGBDSensorClient
localImagePort /clientRgbPort:i
localDepthPort /clientDepthPort:i
localRpcPort /clientRpcPort
remoteImagePort /RGBD/rgbCamera:o
remoteDepthPort /RGBD/depthCamera:o
remoteRpcPort /RGBD/rpc

XML format, using 'networks' keyword. This file is meant to be used in junction with yarprobotinterface executable, therefore has an addictional section at the end.

<!-- Following parameters are meaningful ONLY for yarprobotinterface -->
<param name="localImagePort"> /clientRgbPort:i </param>
<param name="localDepthPort"> /clientDepthPort:i </param>
<param name="localRpcPort"> /clientRpcPort </param>
<param name="remoteImagePort"> /RGBD/rgbCamera:o </param>
<param name="localDepthPort"> /RGBD/depthCamera:o </param>
<param name="remoteRpcPort"> /RGBD/rpc </param>

Definition at line 90 of file RGBDSensorClient.h.

Public Member Functions

 RGBDSensorClient ()
 
 ~RGBDSensorClient ()
 
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< 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 getRgbIntrinsicParam (yarp::os::Property &intrinsic) override
 Get the intrinsic parameters 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...
 
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...
 
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 &near, double &far) override
 Get the clipping planes of the sensor. More...
 
bool setDepthClipPlanes (double near, double far) override
 Set the clipping planes of the sensor. More...
 
bool getDepthIntrinsicParam (yarp::os::Property &intrinsic) override
 Get the intrinsic parameters of the depth camera. 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 open (yarp::os::Searchable &config) override
 Create and configure a device, by name. More...
 
bool close () override
 Close the DeviceDriver. More...
 
bool getExtrinsicParam (yarp::sig::Matrix &extrinsic) override
 Get the extrinsic parameters from the device. More...
 
IRGBDSensor::RGBDSensor_status getSensorStatus () override
 Get the surrent status of the sensor, using enum type. More...
 
std::string getLastErrorMsg (yarp::os::Stamp *timeStamp=NULL) override
 Return an error message in case of error. More...
 
bool getRgbImage (yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=NULL) override
 Get the rgb frame from the device. More...
 
bool getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=NULL) override
 Get the depth frame from the device. More...
 
bool getImages (yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=NULL, yarp::os::Stamp *depthStamp=NULL) override
 Get the both the color and depth frame in a single call. More...
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
virtual ~DeviceDriver ()
 Destructor. More...
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver. More...
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others. More...
 
- Public Member Functions inherited from yarp::os::IConfig
virtual ~IConfig ()
 Destructor. More...
 
virtual bool configure (Searchable &config)
 Change online parameters. More...
 
- Public Member Functions inherited from yarp::dev::FrameGrabberControls_Sender
 FrameGrabberControls_Sender (yarp::os::Port &port)
 
virtual ~FrameGrabberControls_Sender ()
 
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...
 
- Public Member Functions inherited from yarp::dev::IFrameGrabberControls
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)
 
- Public Member Functions inherited from yarp::dev::IRGBDSensor
virtual ~IRGBDSensor ()
 
- Public Member Functions inherited from yarp::dev::IRgbVisualParams
virtual ~IRgbVisualParams ()
 
- Public Member Functions inherited from yarp::dev::IDepthVisualParams
virtual ~IDepthVisualParams ()
 

Additional Inherited Members

- Public Types inherited from yarp::dev::IRGBDSensor
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
}
 

Constructor & Destructor Documentation

◆ RGBDSensorClient()

RGBDSensorClient::RGBDSensorClient ( )

Definition at line 31 of file RGBDSensorClient.cpp.

◆ ~RGBDSensorClient()

RGBDSensorClient::~RGBDSensorClient ( )

Definition at line 42 of file RGBDSensorClient.cpp.

Member Function Documentation

◆ close()

bool RGBDSensorClient::close ( void  )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 304 of file RGBDSensorClient.cpp.

◆ getDepthAccuracy()

double RGBDSensorClient::getDepthAccuracy ( )
overridevirtual

Get the minimum detectable variation in distance [meter].

Returns
the sensor resolution in meters.

Implements yarp::dev::IRGBDSensor.

Definition at line 471 of file RGBDSensorClient.cpp.

◆ getDepthClipPlanes()

bool RGBDSensorClient::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 479 of file RGBDSensorClient.cpp.

◆ getDepthFOV()

bool RGBDSensorClient::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 463 of file RGBDSensorClient.cpp.

◆ getDepthHeight()

int RGBDSensorClient::getDepthHeight ( )
overridevirtual

Return the height of each frame.

Returns
depth image height

Implements yarp::dev::IRGBDSensor.

Definition at line 451 of file RGBDSensorClient.cpp.

◆ getDepthImage()

bool RGBDSensorClient::getDepthImage ( yarp::sig::ImageOf< yarp::sig::PixelFloat > &  depthImage,
yarp::os::Stamp timeStamp = NULL 
)
overridevirtual

Get the depth 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, the user must provide memory allocation
Returns
True on success

Implements yarp::dev::IRGBDSensor.

Definition at line 376 of file RGBDSensorClient.cpp.

◆ getDepthIntrinsicParam()

bool RGBDSensorClient::getDepthIntrinsicParam ( yarp::os::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
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 487 of file RGBDSensorClient.cpp.

◆ getDepthMirroring()

bool RGBDSensorClient::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 492 of file RGBDSensorClient.cpp.

◆ getDepthWidth()

int RGBDSensorClient::getDepthWidth ( )
overridevirtual

Return the height of each frame.

Returns
depth image height

Implements yarp::dev::IRGBDSensor.

Definition at line 455 of file RGBDSensorClient.cpp.

◆ getExtrinsicParam()

bool RGBDSensorClient::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 329 of file RGBDSensorClient.cpp.

◆ getImages()

bool RGBDSensorClient::getImages ( yarp::sig::FlexImage colorFrame,
yarp::sig::ImageOf< yarp::sig::PixelFloat > &  depthFrame,
yarp::os::Stamp colorStamp = NULL,
yarp::os::Stamp depthStamp = NULL 
)
overridevirtual

Get the both the color and depth frame in a single call.

Implementation should assure the best possible synchronization is achieved accordingly to synch policy set by the user. TimeStamps are referred to acquisition time of the corresponding piece of information. If the device is not providing TimeStamps, then 'timeStamp' field should be set to '-1'.

Parameters
colorFramepointer to FlexImage data to hold the color frame from the sensor
depthFramepointer to FlexImage data to hold the depth frame from the sensor
colorStamppointer to memory to hold the Stamp of the color frame
depthStamppointer to memory to hold the Stamp of the depth frame
Returns
true if able to get both data.

Implements yarp::dev::IRGBDSensor.

Definition at line 383 of file RGBDSensorClient.cpp.

◆ getLastErrorMsg()

std::string RGBDSensorClient::getLastErrorMsg ( yarp::os::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 359 of file RGBDSensorClient.cpp.

◆ getRgbFOV()

bool RGBDSensorClient::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 425 of file RGBDSensorClient.cpp.

◆ getRgbHeight()

int RGBDSensorClient::getRgbHeight ( )
overridevirtual

Return the height of each frame.

Returns
rgb image height

Implements yarp::dev::IRGBDSensor.

Definition at line 404 of file RGBDSensorClient.cpp.

◆ getRgbImage()

bool RGBDSensorClient::getRgbImage ( yarp::sig::FlexImage rgbImage,
yarp::os::Stamp timeStamp = NULL 
)
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, the user must provide memory allocation
Returns
True on success

Implements yarp::dev::IRGBDSensor.

Definition at line 369 of file RGBDSensorClient.cpp.

◆ getRgbIntrinsicParam()

bool RGBDSensorClient::getRgbIntrinsicParam ( yarp::os::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
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 433 of file RGBDSensorClient.cpp.

◆ getRgbMirroring()

bool RGBDSensorClient::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 438 of file RGBDSensorClient.cpp.

◆ getRgbResolution()

bool RGBDSensorClient::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 417 of file RGBDSensorClient.cpp.

◆ getRgbSupportedConfigurations()

bool RGBDSensorClient::getRgbSupportedConfigurations ( yarp::sig::VectorOf< 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 413 of file RGBDSensorClient.cpp.

◆ getRgbWidth()

int RGBDSensorClient::getRgbWidth ( )
overridevirtual

Return the width of each frame.

Returns
rgb image width

Implements yarp::dev::IRGBDSensor.

Definition at line 409 of file RGBDSensorClient.cpp.

◆ getSensorStatus()

IRGBDSensor::RGBDSensor_status RGBDSensorClient::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 348 of file RGBDSensorClient.cpp.

◆ open()

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

Create and configure a device, by name.

The config object should have a property called "device" that is set to the common name of the device. All other properties are passed on the the device's DeviceDriver::open method.

Parameters
configconfiguration options for the device
Returns
the device, if it could be created and configured, otherwise NULL. The user is responsible for deallocating the device.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 50 of file RGBDSensorClient.cpp.

◆ setDepthAccuracy()

bool RGBDSensorClient::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 475 of file RGBDSensorClient.cpp.

◆ setDepthClipPlanes()

bool RGBDSensorClient::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 483 of file RGBDSensorClient.cpp.

◆ setDepthFOV()

bool RGBDSensorClient::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 467 of file RGBDSensorClient.cpp.

◆ setDepthMirroring()

bool RGBDSensorClient::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 497 of file RGBDSensorClient.cpp.

◆ setDepthResolution()

bool RGBDSensorClient::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 459 of file RGBDSensorClient.cpp.

◆ setRgbFOV()

bool RGBDSensorClient::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 429 of file RGBDSensorClient.cpp.

◆ setRgbMirroring()

bool RGBDSensorClient::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 443 of file RGBDSensorClient.cpp.

◆ setRgbResolution()

bool RGBDSensorClient::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 421 of file RGBDSensorClient.cpp.


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