YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches

RGBDSensorClient: 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. More...

#include <networkWrappers/RGBDSensorClient/RGBDSensorClient.h>

+ Inheritance diagram for RGBDSensorClient:

Public Member Functions

 RGBDSensorClient ()
 
 RGBDSensorClient (const RGBDSensorClient &)=delete
 
 RGBDSensorClient (RGBDSensorClient &&)=delete
 
RGBDSensorClientoperator= (const RGBDSensorClient &)=delete
 
RGBDSensorClientoperator= (RGBDSensorClient &&)=delete
 
 ~RGBDSensorClient () override
 
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 getRgbIntrinsicParam (yarp::os::Property &intrinsic) override
 Get the intrinsic parameters 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.
 
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.
 
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 &near, double &far) override
 Get the clipping planes of the sensor.
 
bool setDepthClipPlanes (double near, double far) override
 Set the clipping planes of the sensor.
 
bool getDepthIntrinsicParam (yarp::os::Property &intrinsic) override
 Get the intrinsic parameters of the depth camera.
 
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 open (yarp::os::Searchable &config) override
 Create and configure a device, by name.
 
bool close () override
 Close the DeviceDriver.
 
bool getExtrinsicParam (yarp::sig::Matrix &extrinsic) override
 Get the extrinsic parameters from the device.
 
IRGBDSensor::RGBDSensor_status getSensorStatus () override
 Get the surrent status of the sensor, using enum type.
 
std::string getLastErrorMsg (yarp::os::Stamp *timeStamp=nullptr) override
 Return an error message in case of error.
 
bool getRgbImage (yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=nullptr) override
 Get the rgb frame from the device.
 
bool getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr) override
 Get the depth frame from the device.
 
bool getImages (yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr) override
 Get the both the color and depth frame in a single call.
 
- 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::proto::framegrabber::FrameGrabberControls_Forwarder
 FrameGrabberControls_Forwarder (yarp::os::Port &port)
 
 ~FrameGrabberControls_Forwarder () override=default
 
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 ... )
 
- 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::IRGBDSensor
virtual ~IRGBDSensor ()
 
- Public Member Functions inherited from yarp::dev::IRgbVisualParams
virtual ~IRgbVisualParams ()
 
- Public Member Functions inherited from yarp::dev::IDepthVisualParams
virtual ~IDepthVisualParams ()
 
- Public Member Functions inherited from RGBDSensorClient_ParamsParser
 RGBDSensorClient_ParamsParser ()
 
 ~RGBDSensorClient_ParamsParser () override=default
 
bool parseParams (const yarp::os::Searchable &config) override
 Parse the DeviceDriver parameters.
 
std::string getDeviceClassName () const override
 Get the name of the DeviceDriver class.
 
std::string getDeviceName () const override
 Get the name of the device (i.e.
 
std::string getDocumentationOfDeviceParams () const override
 Get the documentation of the DeviceDriver's parameters.
 
std::vector< std::string > getListOfParams () const override
 Return a list of all params used by the device.
 
- Public Member Functions inherited from yarp::dev::IDeviceDriverParams
virtual ~IDeviceDriverParams ()
 

Protected Attributes

yarp::os::Port rpcPort
 
RgbImageBufferedPort colorFrame_StreamingPort
 
FloatImageBufferedPort depthFrame_StreamingPort
 
yarp::dev::IRGBDSensorsensor_p {nullptr}
 
IRGBDSensor::RGBDSensor_status sensorStatus {IRGBDSensor::RGBD_SENSOR_NOT_READY}
 
int verbose {2}
 
yarp::os::Stamp colorStamp
 
yarp::os::Stamp depthStamp
 
RGBDSensor_StreamingMsgParserstreamingReader {nullptr}
 

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
}
 
- Public Attributes inherited from RGBDSensorClient_ParamsParser
const std::string m_device_classname = {"RGBDSensorClient"}
 
const std::string m_device_name = {"RGBDSensorClient"}
 
bool m_parser_is_strict = false
 
const parser_version_type m_parser_version = {}
 
const std::string m_period_defaultValue = {"0.03"}
 
const std::string m_localImagePort_defaultValue = {"/RGBD_nwc/Image:o"}
 
const std::string m_localDepthPort_defaultValue = {"/RGBD_nwc/Depth:o"}
 
const std::string m_remoteImagePort_defaultValue = {"/RGBD_nws/Image:o"}
 
const std::string m_remoteDepthPort_defaultValue = {"/RGBD_nws/Depth:i"}
 
const std::string m_localRpcPort_defaultValue = {"/RGBD_nwc/rpc:o"}
 
const std::string m_remoteRpcPort_defaultValue = {"/RGBD_nws/rpc:i"}
 
const std::string m_ImageCarrier_defaultValue = {"udp"}
 
const std::string m_DepthCarrier_defaultValue = {"udp"}
 
double m_period = {0.03}
 
std::string m_localImagePort = {"/RGBD_nwc/Image:o"}
 
std::string m_localDepthPort = {"/RGBD_nwc/Depth:o"}
 
std::string m_remoteImagePort = {"/RGBD_nws/Image:o"}
 
std::string m_remoteDepthPort = {"/RGBD_nws/Depth:i"}
 
std::string m_localRpcPort = {"/RGBD_nwc/rpc:o"}
 
std::string m_remoteRpcPort = {"/RGBD_nws/rpc:i"}
 
std::string m_ImageCarrier = {"udp"}
 
std::string m_DepthCarrier = {"udp"}
 

Detailed Description

RGBDSensorClient: 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.

Description of input parameters

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

Parameters required by this device are shown in class: RGBDSensorClient_ParamsParser

Definition at line 46 of file RGBDSensorClient.h.

Constructor & Destructor Documentation

◆ RGBDSensorClient() [1/3]

RGBDSensorClient::RGBDSensorClient ( )

Definition at line 23 of file RGBDSensorClient.cpp.

◆ RGBDSensorClient() [2/3]

RGBDSensorClient::RGBDSensorClient ( const RGBDSensorClient )
delete

◆ RGBDSensorClient() [3/3]

RGBDSensorClient::RGBDSensorClient ( RGBDSensorClient &&  )
delete

◆ ~RGBDSensorClient()

RGBDSensorClient::~RGBDSensorClient ( )
override

Definition at line 31 of file RGBDSensorClient.cpp.

Member Function Documentation

◆ close()

bool RGBDSensorClient::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 118 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 289 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 299 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 279 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 264 of file RGBDSensorClient.cpp.

◆ getDepthImage()

bool RGBDSensorClient::getDepthImage ( yarp::sig::ImageOf< yarp::sig::PixelFloat > &  depthImage,
yarp::os::Stamp timeStamp = nullptr 
)
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 191 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
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 309 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 314 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 269 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 143 of file RGBDSensorClient.cpp.

◆ getImages()

bool RGBDSensorClient::getImages ( yarp::sig::FlexImage colorFrame,
yarp::sig::ImageOf< yarp::sig::PixelFloat > &  depthFrame,
yarp::os::Stamp colorStamp = nullptr,
yarp::os::Stamp depthStamp = nullptr 
)
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 196 of file RGBDSensorClient.cpp.

◆ getLastErrorMsg()

std::string RGBDSensorClient::getLastErrorMsg ( yarp::os::Stamp timeStamp = nullptr)
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 175 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 236 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 211 of file RGBDSensorClient.cpp.

◆ getRgbImage()

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

Implements yarp::dev::IRGBDSensor.

Definition at line 186 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
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 246 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 251 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 226 of file RGBDSensorClient.cpp.

◆ getRgbSupportedConfigurations()

bool RGBDSensorClient::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 221 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 216 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 163 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 39 of file RGBDSensorClient.cpp.

◆ operator=() [1/2]

RGBDSensorClient & RGBDSensorClient::operator= ( const RGBDSensorClient )
delete

◆ operator=() [2/2]

RGBDSensorClient & RGBDSensorClient::operator= ( RGBDSensorClient &&  )
delete

◆ 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 294 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 304 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 284 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 319 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 274 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 241 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 256 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 231 of file RGBDSensorClient.cpp.

Member Data Documentation

◆ colorFrame_StreamingPort

RgbImageBufferedPort RGBDSensorClient::colorFrame_StreamingPort
protected

Definition at line 59 of file RGBDSensorClient.h.

◆ colorStamp

yarp::os::Stamp RGBDSensorClient::colorStamp
protected

Definition at line 67 of file RGBDSensorClient.h.

◆ depthFrame_StreamingPort

FloatImageBufferedPort RGBDSensorClient::depthFrame_StreamingPort
protected

Definition at line 60 of file RGBDSensorClient.h.

◆ depthStamp

yarp::os::Stamp RGBDSensorClient::depthStamp
protected

Definition at line 68 of file RGBDSensorClient.h.

◆ rpcPort

yarp::os::Port RGBDSensorClient::rpcPort
protected

Definition at line 53 of file RGBDSensorClient.h.

◆ sensor_p

yarp::dev::IRGBDSensor* RGBDSensorClient::sensor_p {nullptr}
protected

Definition at line 63 of file RGBDSensorClient.h.

◆ sensorStatus

IRGBDSensor::RGBDSensor_status RGBDSensorClient::sensorStatus {IRGBDSensor::RGBD_SENSOR_NOT_READY}
protected

Definition at line 64 of file RGBDSensorClient.h.

◆ streamingReader

RGBDSensor_StreamingMsgParser* RGBDSensorClient::streamingReader {nullptr}
protected

Definition at line 71 of file RGBDSensorClient.h.

◆ verbose

int RGBDSensorClient::verbose {2}
protected

Definition at line 65 of file RGBDSensorClient.h.


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