6#ifndef RGBD_FROM_ROS_TOPIC_H
7#define RGBD_FROM_ROS_TOPIC_H
26#include <yarp/rosmsg/sensor_msgs/CameraInfo.h>
27#include <yarp/rosmsg/sensor_msgs/Image.h>
29#include <yarp/rosmsg/impl/yarpRosHelper.h>
201 bool close()
override;
209 bool getRgbFOV(
double& horizontalFov,
double& verticalFov)
override;
210 bool setRgbFOV(
double horizontalFov,
double verticalFov)
override;
218 bool getDepthFOV(
double& horizontalFov,
double& verticalFov)
override;
219 bool setDepthFOV(
double horizontalFov,
double verticalFov)
override;
contains the definition of a Matrix type
yarp::sig::ImageOf< yarp::sig::PixelFloat > depthImage
RGBDSensorFromRosTopic is a driver for a virtual RGBD device: the data is not originated from a physi...
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
yarp::os::Node * m_ros_node
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 getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
int getDepthHeight() override
Return the height of each frame.
~RGBDSensorFromRosTopic() override=default
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * m_depth_input_processor
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * m_rgb_input_processor
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=nullptr, Stamp *depthStamp=nullptr) override
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
int getRgbHeight() override
Return the height of each frame.
int getRgbWidth() override
Return the width of each frame.
int getDepthWidth() override
Return the height of each frame.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=nullptr) override
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
std::string getLastErrorMsg(Stamp *timeStamp=nullptr) override
Return an error message in case of error.
bool close() override
Close the DeviceDriver.
Interface implemented by all device drivers.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
A class for storing options and configuration information.
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.
Image class with user control of representation details.
constexpr char accuracy[]