YARP
Yet Another Robot Platform
RGBDSensorFromRosTopic.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #ifndef RGBD_FROM_ROS_TOPIC_H
10 #define RGBD_FROM_ROS_TOPIC_H
11 
12 #include <iostream>
13 #include <cstring>
14 #include <map>
15 #include <mutex>
16 
17 #include <yarp/dev/DeviceDriver.h>
19 #include <yarp/os/PeriodicThread.h>
20 #include <yarp/sig/all.h>
21 #include <yarp/sig/Matrix.h>
22 #include <yarp/os/Stamp.h>
23 #include <yarp/os/Property.h>
24 #include <yarp/dev/IRGBDSensor.h>
26 #include <RGBDRosConversionUtils.h>
27 
28 #include <yarp/os/Node.h>
29 #include <yarp/os/Subscriber.h>
32 
34 
36 
195 {
196 private:
197  typedef yarp::os::Stamp Stamp;
200 
201 public:
203  ~RGBDSensorFromRosTopic() override = default;
204 
205  // DeviceDriver
206  bool open(yarp::os::Searchable& config) override;
207  bool close() override;
208 
209  // IRGBDSensor
210  int getRgbHeight() override;
211  int getRgbWidth() override;
213  bool getRgbResolution(int &width, int &height) override;
214  bool setRgbResolution(int width, int height) override;
215  bool getRgbFOV(double& horizontalFov, double& verticalFov) override;
216  bool setRgbFOV(double horizontalFov, double verticalFov) override;
217  bool getRgbMirroring(bool& mirror) override;
218  bool setRgbMirroring(bool mirror) override;
219 
220  bool getRgbIntrinsicParam(Property& intrinsic) override;
221  int getDepthHeight() override;
222  int getDepthWidth() override;
223  bool setDepthResolution(int width, int height) override;
224  bool getDepthFOV(double& horizontalFov, double& verticalFov) override;
225  bool setDepthFOV(double horizontalFov, double verticalFov) override;
226  bool getDepthIntrinsicParam(Property& intrinsic) override;
227  double getDepthAccuracy() override;
228  bool setDepthAccuracy(double accuracy) override;
229  bool getDepthClipPlanes(double& nearPlane, double& farPlane) override;
230  bool setDepthClipPlanes(double nearPlane, double farPlane) override;
231  bool getDepthMirroring(bool& mirror) override;
232  bool setDepthMirroring(bool mirror) override;
233 
234  bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override;
235  bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = nullptr) override;
236  bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = nullptr) override;
237  bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp=NULL, Stamp* depthStamp=NULL) override;
238 
240  std::string getLastErrorMsg(Stamp* timeStamp = NULL) override;
241 
242  /*
243  //IFrameGrabberControls
244  bool getCameraDescription(CameraDescriptor *camera) override;
245  bool hasFeature(int feature, bool* hasFeature) override;
246  bool setFeature(int feature, double value) override;
247  bool getFeature(int feature, double* value) override;
248  bool setFeature(int feature, double value1, double value2) override;
249  bool getFeature(int feature, double* value1, double* value2) override;
250  bool hasOnOff( int feature, bool* HasOnOff) override;
251  bool setActive( int feature, bool onoff) override;
252  bool getActive( int feature, bool* isActive) override;
253  bool hasAuto( int feature, bool* hasAuto) override;
254  bool hasManual( int feature, bool* hasManual) override;
255  bool hasOnePush(int feature, bool* hasOnePush) override;
256  bool setMode( int feature, FeatureMode mode) override;
257  bool getMode( int feature, FeatureMode *mode) override;
258  bool setOnePush(int feature) override;
259  */
260 
261  // ros-topic related
262  mutable std::mutex m_mutex;
270 
273  std::string m_lastError;
274  bool m_verbose;
276 };
277 #endif
RGBDSensorFromRosTopic::getLastErrorMsg
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
Definition: RGBDSensorFromRosTopic.cpp:284
RGBDSensorFromRosTopic::getRgbWidth
int getRgbWidth() override
Return the width of each frame.
Definition: RGBDSensorFromRosTopic.cpp:85
RGBDSensorFromRosTopic::close
bool close() override
Close the DeviceDriver.
Definition: RGBDSensorFromRosTopic.cpp:59
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
RGBDSensorFromRosTopic::getRgbResolution
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
Definition: RGBDSensorFromRosTopic.cpp:97
RGBDSensorFromRosTopic::m_mutex
std::mutex m_mutex
Definition: RGBDSensorFromRosTopic.h:262
RGBDSensorFromRosTopic::getDepthWidth
int getDepthWidth() override
Return the height of each frame.
Definition: RGBDSensorFromRosTopic.cpp:183
Subscriber.h
RGBDSensorFromRosTopic::getDepthHeight
int getDepthHeight() override
Return the height of each frame.
Definition: RGBDSensorFromRosTopic.cpp:174
RGBDRosConversionUtils.h
RGBDSensorFromRosTopic::getExtrinsicParam
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
Definition: RGBDSensorFromRosTopic.cpp:243
RGBDSensorFromRosTopic::setDepthResolution
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
Definition: RGBDSensorFromRosTopic.cpp:110
RGBDSensorFromRosTopic::m_ros_node
yarp::os::Node * m_ros_node
Definition: RGBDSensorFromRosTopic.h:263
all.h
yarp::dev::DeviceDriver
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
RGBDSensorFromRosTopic::getDepthMirroring
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
Definition: RGBDSensorFromRosTopic.cpp:231
RGBDSensorFromRosTopic::getDepthFOV
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
Definition: RGBDSensorFromRosTopic.cpp:192
RGBDSensorFromRosTopic::m_rgb_input_processor
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * m_rgb_input_processor
Definition: RGBDSensorFromRosTopic.h:264
RGBDSensorParamParser.h
Matrix.h
contains the definition of a Matrix type
RGBDSensorFromRosTopic::m_rgb_data_topic_name
std::string m_rgb_data_topic_name
Definition: RGBDSensorFromRosTopic.h:266
depthImage
yarp::sig::ImageOf< yarp::sig::PixelFloat > depthImage
Definition: RGBDSensorFromRosTopic.h:35
RGBDSensorFromRosTopic::getRgbHeight
int getRgbHeight() override
Return the height of each frame.
Definition: RGBDSensorFromRosTopic.cpp:79
yarp::dev::IRGBDSensor::RGBDSensor_status
RGBDSensor_status
Definition: IRGBDSensor.h:63
RGBDSensorFromRosTopic::setRgbResolution
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
Definition: RGBDSensorFromRosTopic.cpp:116
RGBDSensorFromRosTopic::m_depth_data_topic_name
std::string m_depth_data_topic_name
Definition: RGBDSensorFromRosTopic.h:267
RGBDSensorFromRosTopic::getRgbImage
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
Definition: RGBDSensorFromRosTopic.cpp:249
yarpRosHelper.h
yarp::sig::ImageOf< yarp::sig::PixelFloat >
RGBDSensorFromRosTopic::RGBDSensorFromRosTopic
RGBDSensorFromRosTopic()
Definition: RGBDSensorFromRosTopic.cpp:30
RGBDSensorFromRosTopic::getRgbMirroring
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
Definition: RGBDSensorFromRosTopic.cpp:152
yarp::sig::VectorOf< yarp::dev::CameraConfig >
RGBDSensorFromRosTopic::open
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition: RGBDSensorFromRosTopic.cpp:35
RGBDSensorFromRosTopic::m_depth_info_topic_name
std::string m_depth_info_topic_name
Definition: RGBDSensorFromRosTopic.h:269
Property.h
RGBDSensorFromRosTopic::setRgbFOV
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
Definition: RGBDSensorFromRosTopic.cpp:123
yarp::sig::FlexImage
Image class with user control of representation details.
Definition: Image.h:403
RGBDSensorFromRosTopic::m_rgb_info_topic_name
std::string m_rgb_info_topic_name
Definition: RGBDSensorFromRosTopic.h:268
Stamp.h
RGBDSensorFromRosTopic::getDepthIntrinsicParam
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
Definition: RGBDSensorFromRosTopic.cpp:203
Node.h
RGBDSensorFromRosTopic::~RGBDSensorFromRosTopic
~RGBDSensorFromRosTopic() override=default
CameraInfo.h
RGBDSensorFromRosTopic::m_depth_input_processor
yarp::dev::RGBDRosConversionUtils::commonImageProcessor * m_depth_input_processor
Definition: RGBDSensorFromRosTopic.h:265
yarp::os::Node
The Node class.
Definition: Node.h:27
yarp::dev::IRGBDSensor
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:56
RGBDSensorFromRosTopic::getRgbFOV
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
Definition: RGBDSensorFromRosTopic.cpp:141
RGBDSensorFromRosTopic::setDepthFOV
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
Definition: RGBDSensorFromRosTopic.cpp:129
PeriodicThread.h
RGBDSensorFromRosTopic::getRgbIntrinsicParam
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
Definition: RGBDSensorFromRosTopic.cpp:164
RGBDSensorFromRosTopic::setDepthAccuracy
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
Definition: RGBDSensorFromRosTopic.cpp:135
yarp::os::Stamp
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
IRGBDSensor.h
RGBDSensorFromRosTopic::getDepthImage
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=nullptr) override
Definition: RGBDSensorFromRosTopic.cpp:258
RGBDSensorFromRosTopic
RGBDSensorFromRosTopic is a driver for a virtual RGBD device: the data is not originated from a physi...
Definition: RGBDSensorFromRosTopic.h:195
RGBDSensorFromRosTopic::setDepthClipPlanes
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
Definition: RGBDSensorFromRosTopic.cpp:225
RGBDSensorFromRosTopic::getRgbSupportedConfigurations
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
Definition: RGBDSensorFromRosTopic.cpp:91
RGBDSensorFromRosTopic::getSensorStatus
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
Definition: RGBDSensorFromRosTopic.cpp:279
RGBDSensorFromRosTopic::getDepthClipPlanes
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
Definition: RGBDSensorFromRosTopic.cpp:219
RGBDSensorFromRosTopic::m_verbose
bool m_verbose
Definition: RGBDSensorFromRosTopic.h:274
Image.h
FrameGrabberControl2.h
define common interfaces to discover remote camera capabilities
RGBDSensorFromRosTopic::setRgbMirroring
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
Definition: RGBDSensorFromRosTopic.cpp:158
RGBDSensorFromRosTopic::m_depth_stamp
yarp::os::Stamp m_depth_stamp
Definition: RGBDSensorFromRosTopic.h:272
RGBDSensorFromRosTopic::m_lastError
std::string m_lastError
Definition: RGBDSensorFromRosTopic.h:273
RGBDSensorFromRosTopic::m_initialized
bool m_initialized
Definition: RGBDSensorFromRosTopic.h:275
RGBDSensorFromRosTopic::m_rgb_stamp
yarp::os::Stamp m_rgb_stamp
Definition: RGBDSensorFromRosTopic.h:271
RGBDSensorFromRosTopic::setDepthMirroring
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
Definition: RGBDSensorFromRosTopic.cpp:237
RGBDSensorFromRosTopic::getDepthAccuracy
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
Definition: RGBDSensorFromRosTopic.cpp:213
yarp::dev::RGBDRosConversionUtils::commonImageProcessor
Definition: RGBDRosConversionUtils.h:37
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
RGBDSensorFromRosTopic::getImages
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
Definition: RGBDSensorFromRosTopic.cpp:267
DeviceDriver.h
yarp::sig::Matrix
A class for a Matrix.
Definition: Matrix.h:46