RGBDSensorFromRosTopic
is a driver for a virtual RGBD device: the data is not originated from a physical sensor but from a ROS topic.
More...
#include <RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h>
Public Member Functions | |
~RGBDSensorFromRosTopic () 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=nullptr, Stamp *depthStamp=nullptr) override |
RGBDSensor_status | getSensorStatus () override |
Get the surrent status of the sensor, using enum type. More... | |
std::string | getLastErrorMsg (Stamp *timeStamp=nullptr) override |
Return an error message in case of error. More... | |
![]() | |
DeviceDriver () | |
DeviceDriver (const DeviceDriver &other)=delete | |
DeviceDriver (DeviceDriver &&other) noexcept=delete | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (DeviceDriver &&other) noexcept=delete |
~DeviceDriver () override | |
bool | open (yarp::os::Searchable &config) override |
Open the DeviceDriver. More... | |
bool | close () override |
Close the DeviceDriver. More... | |
virtual std::string | id () const |
Return the id assigned to the PolyDriver. More... | |
virtual void | setId (const std::string &id) |
Set the id for this device. 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 | open (Searchable &config) |
Initialize the object. More... | |
virtual bool | close () |
Shut the object down. More... | |
virtual bool | configure (Searchable &config) |
Change online parameters. More... | |
![]() | |
virtual | ~IRGBDSensor () |
int | getRgbHeight () override=0 |
Return the height of each frame. More... | |
int | getRgbWidth () override=0 |
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=0 |
Set the resolution of the rgb image from the camera. More... | |
bool | getRgbFOV (double &horizontalFov, double &verticalFov) override=0 |
Get the field of view (FOV) of the rgb camera. More... | |
bool | setRgbFOV (double horizontalFov, double verticalFov) override=0 |
Set the field of view (FOV) of the rgb camera. More... | |
bool | getRgbIntrinsicParam (yarp::os::Property &intrinsic) override=0 |
Get the intrinsic parameters of the rgb camera. More... | |
int | getDepthHeight () override=0 |
Return the height of each frame. More... | |
int | getDepthWidth () override=0 |
Return the height of each frame. More... | |
bool | setDepthResolution (int width, int height) override=0 |
Set the resolution of the depth image from the camera. More... | |
bool | getDepthFOV (double &horizontalFov, double &verticalFov) override=0 |
Get the field of view (FOV) of the depth camera. More... | |
bool | setDepthFOV (double horizontalFov, double verticalFov) override=0 |
Set the field of view (FOV) of the depth camera. More... | |
double | getDepthAccuracy () override=0 |
Get the minimum detectable variation in distance [meter]. More... | |
bool | setDepthAccuracy (double accuracy) override=0 |
Set the minimum detectable variation in distance [meter] when possible. More... | |
bool | getDepthClipPlanes (double &nearPlane, double &farPlane) override=0 |
Get the clipping planes of the sensor. More... | |
bool | setDepthClipPlanes (double nearPlane, double farPlane) override=0 |
Set the clipping planes of the sensor. More... | |
bool | getDepthIntrinsicParam (yarp::os::Property &intrinsic) override=0 |
Get the intrinsic parameters of the depth camera. More... | |
virtual bool | getExtrinsicParam (yarp::sig::Matrix &extrinsic)=0 |
Get the extrinsic parameters from the device. More... | |
virtual std::string | getLastErrorMsg (yarp::os::Stamp *timeStamp=nullptr)=0 |
Return an error message in case of error. More... | |
virtual bool | getRgbImage (yarp::sig::FlexImage &rgbImage, yarp::os::Stamp *timeStamp=nullptr)=0 |
Get the rgb frame from the device. More... | |
virtual bool | getDepthImage (yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr)=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=nullptr, yarp::os::Stamp *depthStamp=nullptr)=0 |
Get the both the color and depth frame in a single call. More... | |
virtual RGBDSensor_status | getSensorStatus ()=0 |
Get the surrent status of the sensor, using enum type. More... | |
![]() | |
virtual | ~IRgbVisualParams () |
virtual int | getRgbHeight ()=0 |
Return the height of each frame. More... | |
virtual int | getRgbWidth ()=0 |
Return the width of each frame. More... | |
virtual bool | getRgbSupportedConfigurations (yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) |
Get the possible configurations of the camera. More... | |
virtual bool | getRgbResolution (int &width, int &height) |
Get the resolution of the rgb image from the camera. More... | |
virtual bool | setRgbResolution (int width, int height)=0 |
Set the resolution of the rgb image from the camera. More... | |
virtual bool | getRgbFOV (double &horizontalFov, double &verticalFov)=0 |
Get the field of view (FOV) of the rgb camera. More... | |
virtual bool | setRgbFOV (double horizontalFov, double verticalFov)=0 |
Set the field of view (FOV) of the rgb camera. More... | |
virtual bool | getRgbIntrinsicParam (yarp::os::Property &intrinsic)=0 |
Get the intrinsic parameters of the rgb camera. More... | |
virtual bool | getRgbMirroring (bool &mirror)=0 |
Get the mirroring setting of the sensor. More... | |
virtual bool | setRgbMirroring (bool mirror)=0 |
Set the mirroring setting of the sensor. More... | |
![]() | |
virtual | ~IDepthVisualParams () |
virtual int | getDepthHeight ()=0 |
Return the height of each frame. More... | |
virtual int | getDepthWidth ()=0 |
Return the height of each frame. More... | |
virtual bool | setDepthResolution (int width, int height)=0 |
Set the resolution of the depth image from the camera. More... | |
virtual bool | getDepthFOV (double &horizontalFov, double &verticalFov)=0 |
Get the field of view (FOV) of the depth camera. More... | |
virtual bool | setDepthFOV (double horizontalFov, double verticalFov)=0 |
Set the field of view (FOV) of the depth camera. More... | |
virtual bool | getDepthIntrinsicParam (yarp::os::Property &intrinsic)=0 |
Get the intrinsic parameters of the depth camera. More... | |
virtual double | getDepthAccuracy ()=0 |
Get the minimum detectable variation in distance [meter]. More... | |
virtual bool | setDepthAccuracy (double accuracy)=0 |
Set the minimum detectable variation in distance [meter] when possible. More... | |
virtual bool | getDepthClipPlanes (double &nearPlane, double &farPlane)=0 |
Get the clipping planes of the sensor. More... | |
virtual bool | setDepthClipPlanes (double nearPlane, double farPlane)=0 |
Set the clipping planes of the sensor. More... | |
virtual bool | getDepthMirroring (bool &mirror)=0 |
Get the mirroring setting of the sensor. More... | |
virtual bool | setDepthMirroring (bool mirror)=0 |
Set the mirroring setting of the sensor. More... | |
Public Attributes | |
std::mutex | m_mutex |
yarp::os::Node * | m_ros_node = nullptr |
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * | m_rgb_input_processor = nullptr |
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * | m_depth_input_processor = nullptr |
std::string | m_lastError |
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 } |
RGBDSensorFromRosTopic
is a driver for a virtual RGBD device: the data is not originated from a physical sensor but from a ROS topic.
This device driver exposes the IRGBDSensor interface to read the images published by a ROS node. See the documentation for more details about each interface.
This device can be used in two different ways:
When used as a client, the RGBDSensorFromRosTopic device directly connects to the ROS publisher via tcp_ros
carrier. This mode does not use a RGBDSensorWrapper and thus minimize latency. It is thus recommended when the application consists of a single client. However, if multiple clients are involved, as shown in the diagram below, this architecture might be inefficient, due to the multiple tcp_ros connections.
The second mode, instead, is useful if the application consists of several modules, and each of them employ a client connected to the same server (RGBDSensorWrapper). In this case, if all the modules run on the same machine, the unix_stream
can be employed to share data between them, minimizing data transfer operations and greatly boosting the performance. See the digram below.
YARP device name |
---|
RGBDSensorFromRosTopic |
Parameters used by this device are:
Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
---|---|---|---|---|---|---|---|
color_topic_name | - | string | - | - | Yes | The device connects to this ROS topic to get RGB data (there must be also camera_info with the last subtopic) |
| depth_topic_name | - | string | - | - | Yes | The device connects to this ROS topic to get Depth data (there must be also camera_info with the last subtopic) | | * | node_name | - | string | - | - | Yes | the name of the ros node | | | node_name | - | string | - | - | Yes | the name of the ros node | | * | node_name | - | string | - | - | Yes | the name of the ros node | |
Example of configuration file (using .ini format) when the device is wrapped by RGBDSensorWrapper.
Definition at line 187 of file RGBDSensorFromRosTopic.h.
|
overridedefault |
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 69 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Get the minimum detectable variation in distance [meter].
Implements yarp::dev::IRGBDSensor.
Definition at line 241 of file RGBDSensorFromRosTopic.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 247 of file RGBDSensorFromRosTopic.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 220 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 202 of file RGBDSensorFromRosTopic.cpp.
|
override |
Definition at line 293 of file RGBDSensorFromRosTopic.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 | |
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 231 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Get the mirroring setting of the sensor.
mirror | true if image is mirrored, false otherwise |
Implements yarp::dev::IDepthVisualParams.
Definition at line 263 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 211 of file RGBDSensorFromRosTopic.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 277 of file RGBDSensorFromRosTopic.cpp.
|
override |
Definition at line 302 of file RGBDSensorFromRosTopic.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 319 of file RGBDSensorFromRosTopic.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 167 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Return the height of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 89 of file RGBDSensorFromRosTopic.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 284 of file RGBDSensorFromRosTopic.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 | |
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 192 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Get the mirroring setting of the sensor.
mirror | true if image is mirrored, false otherwise |
Implements yarp::dev::IRgbVisualParams.
Definition at line 178 of file RGBDSensorFromRosTopic.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 114 of file RGBDSensorFromRosTopic.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 107 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Return the width of each frame.
Implements yarp::dev::IRGBDSensor.
Definition at line 98 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Get the surrent status of the sensor, using enum type.
Implements yarp::dev::IRGBDSensor.
Definition at line 314 of file RGBDSensorFromRosTopic.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). |
@<-OK
@<-OK
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 24 of file RGBDSensorFromRosTopic.cpp.
|
overridevirtual |
Set the minimum detectable variation in distance [meter] when possible.
the | desired resolution in meters. |
Implements yarp::dev::IRGBDSensor.
Definition at line 160 of file RGBDSensorFromRosTopic.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 255 of file RGBDSensorFromRosTopic.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 152 of file RGBDSensorFromRosTopic.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 270 of file RGBDSensorFromRosTopic.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 127 of file RGBDSensorFromRosTopic.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 144 of file RGBDSensorFromRosTopic.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 185 of file RGBDSensorFromRosTopic.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 135 of file RGBDSensorFromRosTopic.cpp.
yarp::dev::RGBDRosConversionUtils::commonImageProcessor* RGBDSensorFromRosTopic::m_depth_input_processor = nullptr |
Definition at line 259 of file RGBDSensorFromRosTopic.h.
std::string RGBDSensorFromRosTopic::m_lastError |
Definition at line 261 of file RGBDSensorFromRosTopic.h.
|
mutable |
Definition at line 256 of file RGBDSensorFromRosTopic.h.
yarp::dev::RGBDRosConversionUtils::commonImageProcessor* RGBDSensorFromRosTopic::m_rgb_input_processor = nullptr |
Definition at line 258 of file RGBDSensorFromRosTopic.h.
yarp::os::Node* RGBDSensorFromRosTopic::m_ros_node = nullptr |
Definition at line 257 of file RGBDSensorFromRosTopic.h.