|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
9 #ifndef RGBD_FROM_ROS_TOPIC_H
10 #define RGBD_FROM_ROS_TOPIC_H
207 bool close()
override;
215 bool getRgbFOV(
double& horizontalFov,
double& verticalFov)
override;
216 bool setRgbFOV(
double horizontalFov,
double verticalFov)
override;
224 bool getDepthFOV(
double& horizontalFov,
double& verticalFov)
override;
225 bool setDepthFOV(
double horizontalFov,
double verticalFov)
override;
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
int getRgbWidth() override
Return the width of each frame.
bool close() override
Close the DeviceDriver.
A base class for nested structures that can be searched.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
int getDepthWidth() override
Return the height of each frame.
int getDepthHeight() override
Return the height of each frame.
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.
yarp::os::Node * m_ros_node
Interface implemented by all device drivers.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * m_rgb_input_processor
contains the definition of a Matrix type
std::string m_rgb_data_topic_name
yarp::sig::ImageOf< yarp::sig::PixelFloat > depthImage
int getRgbHeight() override
Return the height of each frame.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
std::string m_depth_data_topic_name
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
std::string m_depth_info_topic_name
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
Image class with user control of representation details.
std::string m_rgb_info_topic_name
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
~RGBDSensorFromRosTopic() override=default
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * m_depth_input_processor
A generic interface for cameras that have both color camera as well as depth camera sensor,...
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
An abstraction for a time stamp and/or sequence number.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=nullptr) override
RGBDSensorFromRosTopic is a driver for a virtual RGBD device: the data is not originated from a physi...
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
define common interfaces to discover remote camera capabilities
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
yarp::os::Stamp m_depth_stamp
yarp::os::Stamp m_rgb_stamp
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
A class for storing options and configuration information.
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override