YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RGBDSensorFromRosTopic.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef RGBD_FROM_ROS_TOPIC_H
7#define RGBD_FROM_ROS_TOPIC_H
8
9#include <iostream>
10#include <cstring>
11#include <map>
12#include <mutex>
13
16#include <yarp/sig/all.h>
17#include <yarp/sig/Matrix.h>
18#include <yarp/os/Stamp.h>
19#include <yarp/os/Property.h>
23
24#include <yarp/os/Node.h>
25#include <yarp/os/Subscriber.h>
26#include <yarp/rosmsg/sensor_msgs/CameraInfo.h>
27#include <yarp/rosmsg/sensor_msgs/Image.h>
28
29#include <yarp/rosmsg/impl/yarpRosHelper.h>
30
32
190{
191private:
192 typedef yarp::os::Stamp Stamp;
195
196public:
197 ~RGBDSensorFromRosTopic() override = default;
198
199 // DeviceDriver
200 bool open(yarp::os::Searchable& config) override;
201 bool close() override;
202
203 // IRGBDSensor
204 int getRgbHeight() override;
205 int getRgbWidth() override;
207 bool getRgbResolution(int &width, int &height) override;
208 bool setRgbResolution(int width, int height) override;
209 bool getRgbFOV(double& horizontalFov, double& verticalFov) override;
210 bool setRgbFOV(double horizontalFov, double verticalFov) override;
211 bool getRgbMirroring(bool& mirror) override;
212 bool setRgbMirroring(bool mirror) override;
213
214 bool getRgbIntrinsicParam(Property& intrinsic) override;
215 int getDepthHeight() override;
216 int getDepthWidth() override;
217 bool setDepthResolution(int width, int height) override;
218 bool getDepthFOV(double& horizontalFov, double& verticalFov) override;
219 bool setDepthFOV(double horizontalFov, double verticalFov) override;
220 bool getDepthIntrinsicParam(Property& intrinsic) override;
221 double getDepthAccuracy() override;
222 bool setDepthAccuracy(double accuracy) override;
223 bool getDepthClipPlanes(double& nearPlane, double& farPlane) override;
224 bool setDepthClipPlanes(double nearPlane, double farPlane) override;
225 bool getDepthMirroring(bool& mirror) override;
226 bool setDepthMirroring(bool mirror) override;
227
228 bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override;
229 bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = nullptr) override;
230 bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = nullptr) override;
231 bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp = nullptr, Stamp* depthStamp = nullptr) override;
232
234 std::string getLastErrorMsg(Stamp* timeStamp = nullptr) override;
235
236 /*
237 //IFrameGrabberControls
238 bool getCameraDescription(CameraDescriptor *camera) override;
239 bool hasFeature(int feature, bool* hasFeature) override;
240 bool setFeature(int feature, double value) override;
241 bool getFeature(int feature, double* value) override;
242 bool setFeature(int feature, double value1, double value2) override;
243 bool getFeature(int feature, double* value1, double* value2) override;
244 bool hasOnOff( int feature, bool* HasOnOff) override;
245 bool setActive( int feature, bool onoff) override;
246 bool getActive( int feature, bool* isActive) override;
247 bool hasAuto( int feature, bool* hasAuto) override;
248 bool hasManual( int feature, bool* hasManual) override;
249 bool hasOnePush(int feature, bool* hasOnePush) override;
250 bool setMode( int feature, FeatureMode mode) override;
251 bool getMode( int feature, FeatureMode *mode) override;
252 bool setOnePush(int feature) override;
253 */
254
255 // ros-topic related
256 mutable std::mutex m_mutex;
260
261 std::string m_lastError;
262};
263#endif
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.
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,...
Definition IRGBDSensor.h:39
The Node class.
Definition Node.h:23
A class for storing options and configuration information.
Definition Property.h:33
A base class for nested structures that can be searched.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
Image class with user control of representation details.
Definition Image.h:374
Typed image class.
Definition Image.h:616
A class for a Matrix.
Definition Matrix.h:39
constexpr char accuracy[]