YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RGBDSensorFromRosTopic.cpp
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#include <algorithm>
7
9#include <yarp/os/Value.h>
10#include <yarp/sig/ImageUtils.h>
11
13
14using namespace yarp::dev;
15using namespace yarp::sig;
16using namespace yarp::os;
17
18
19namespace {
20YARP_LOG_COMPONENT(RGBD_ROS_TOPIC, "yarp.device.RGBDSensorFromRosTopic")
21}
22
23
25{
26 if (!config.check("depth_topic_name")) {
27 yCError(RGBD_ROS_TOPIC) << "missing depth_topic_name parameter, using default one";
28 return false;
29 }
30 std::string depth_topic_name = config.find("depth_topic_name").asString();
31 if(depth_topic_name[0] != '/'){
32 yCError(RGBD_ROS_TOPIC) << "depth_topic_name must begin with an initial /";
33 return false;
34 }
35
36 if (!config.check("color_topic_name")) {
37 yCError(RGBD_ROS_TOPIC) << "missing color_topic_name parameter, using default one";
38 return false;
39 }
40 std::string color_topic_name = config.find("color_topic_name").asString();
41 if(color_topic_name[0] != '/'){
42 yCError(RGBD_ROS_TOPIC) << "color_topic_name must begin with an initial /";
43 return false;
44 }
45 std::string rgb_info_topic_name = color_topic_name.substr(0,color_topic_name.rfind('/')) + "/camera_info";
46 std::string depth_info_topic_name = depth_topic_name.substr(0,depth_topic_name.rfind('/')) + "/camera_info";
47
48 if (!config.check("node_name")) {
49 yCError(RGBD_ROS_TOPIC) << "missing node_name parameter, using default one";
50 return false;
51 }
52 std::string node_name = config.find("node_name").asString();
53 if(node_name[0] != '/'){
54 yCError(RGBD_ROS_TOPIC) << "node_name must begin with an initial /";
55 return false;
56 }
58
59 //m_rgb_input_processor.useCallback(); ///@@@<-SEGFAULT
60 //m_depth_input_processor.useCallback(); ///@@@<-SEGFAULT
65
66 return true;
67}
68
70{
72 {
74 m_rgb_input_processor =nullptr;
75 }
77 {
80 }
81 if (m_ros_node)
82 {
83 delete m_ros_node;
84 m_ros_node=nullptr;
85 }
86 return true;
87}
88
90{
91 if (m_rgb_input_processor==nullptr)
92 {
93 return 0;
94 }
95 return static_cast<int>(m_rgb_input_processor->getHeight());
96}
97
99{
100 if (m_rgb_input_processor==nullptr)
101 {
102 return 0;
103 }
104 return static_cast<int>(m_rgb_input_processor->getWidth());
105}
106
108{
109 YARP_UNUSED(configurations);
110 yCWarning(RGBD_ROS_TOPIC) << "getRgbSupportedConfigurations not implemented yet";
111 return false;
112}
113
114bool RGBDSensorFromRosTopic::getRgbResolution(int &width, int &height)
115{
116 if (m_rgb_input_processor == nullptr)
117 {
118 width=0;
119 height=0;
120 return true;
121 }
122 width = static_cast<int>(m_rgb_input_processor->getWidth());
123 height = static_cast<int>(m_rgb_input_processor->getHeight());
124 return true;
125}
126
128{
129 YARP_UNUSED(width);
130 YARP_UNUSED(height);
131 yCWarning(RGBD_ROS_TOPIC) << "setDepthResolution not supported";
132 return false;
133}
134
136{
137 YARP_UNUSED(width);
138 YARP_UNUSED(height);
139 yCWarning(RGBD_ROS_TOPIC) << "setRgbResolution not supported";
140 return false;
141}
142
143
144bool RGBDSensorFromRosTopic::setRgbFOV(double horizontalFov, double verticalFov)
145{
146 YARP_UNUSED(horizontalFov);
147 YARP_UNUSED(verticalFov);
148 yCWarning(RGBD_ROS_TOPIC) << "setRgbFOV not supported";
149 return false;
150}
151
152bool RGBDSensorFromRosTopic::setDepthFOV(double horizontalFov, double verticalFov)
153{
154 YARP_UNUSED(horizontalFov);
155 YARP_UNUSED(verticalFov);
156 yCWarning(RGBD_ROS_TOPIC) << "setDepthFOV not supported";
157 return false;
158}
159
161{
163 yCWarning(RGBD_ROS_TOPIC) << "setDepthAccuracy not supported";
164 return false;
165}
166
167bool RGBDSensorFromRosTopic::getRgbFOV(double &horizontalFov, double &verticalFov)
168{
169 if (m_rgb_input_processor == nullptr)
170 {
171 horizontalFov=0;
172 verticalFov=0;
173 return true;
174 }
175 return m_rgb_input_processor->getFOV(horizontalFov, verticalFov);
176}
177
179{
181 yCWarning(RGBD_ROS_TOPIC) << "Mirroring not supported";
182 return false;
183}
184
186{
188 yCWarning(RGBD_ROS_TOPIC) << "Mirroring not supported";
189 return false;
190}
191
193{
194 if (m_rgb_input_processor == nullptr)
195 {
196 intrinsic.clear();
197 return true;
198 }
199 return m_rgb_input_processor->getIntrinsicParam(intrinsic);
200}
201
203{
204 if (m_depth_input_processor == nullptr)
205 {
206 return 0;
207 }
208 return static_cast<int>(m_depth_input_processor->getHeight());
209}
210
212{
213 if (m_depth_input_processor == nullptr)
214 {
215 return 0;
216 }
217 return static_cast<int>(m_depth_input_processor->getWidth());
218}
219
220bool RGBDSensorFromRosTopic::getDepthFOV(double& horizontalFov, double& verticalFov)
221{
222 if (m_depth_input_processor == nullptr)
223 {
224 horizontalFov = 0;
225 verticalFov = 0;
226 return true;
227 }
228 return m_depth_input_processor->getFOV(horizontalFov, verticalFov);
229}
230
232{
233 if (m_depth_input_processor == nullptr)
234 {
235 intrinsic.clear();
236 return true;
237 }
239}
240
242{
243 yCWarning(RGBD_ROS_TOPIC) << "getDepthAccuracy not supported";
244 return 0;
245}
246
248{
251 yCWarning(RGBD_ROS_TOPIC) << "getDepthClipPlanes not supported";
252 return false;
253}
254
256{
259 yCWarning(RGBD_ROS_TOPIC) << "setDepthClipPlanes not supported";
260 return false;
261}
262
264{
266 yCWarning(RGBD_ROS_TOPIC) << "getDepthMirroring not supported";
267 return false;
268}
269
271{
273 yCWarning(RGBD_ROS_TOPIC) << "setDepthMirroring not supported";
274 return false;
275}
276
278{
280 yCWarning(RGBD_ROS_TOPIC) << "getExtrinsicParam not supported";
281 return false;
282}
283
285{
286 std::lock_guard<std::mutex> guard(m_mutex);
287 bool rgb_ok = false;
288 if (m_rgb_input_processor!=nullptr)
290 return rgb_ok;
291}
292
294{
295 std::lock_guard<std::mutex> guard(m_mutex);
296 bool depth_ok =false;
297 if (m_depth_input_processor != nullptr)
299 return depth_ok;
300}
301
303{
304 bool rgb_ok = false;
305 bool depth_ok = false;
306 std::lock_guard<std::mutex> guard(m_mutex);
307 if (m_rgb_input_processor != nullptr)
309 if (m_depth_input_processor != nullptr)
311 return (rgb_ok && depth_ok);
312}
313
318
320{
321 YARP_UNUSED(timeStamp);
322 return m_lastError;
323}
324
325/*
326//IFrameGrabberControls
327bool RGBDSensorFromRosTopic::getCameraDescription(CameraDescriptor* camera)
328{
329 camera->deviceDescription = "Ros Camera";
330 camera->busType = BusType::BUS_UNKNOWN;
331 return true;
332}
333
334bool RGBDSensorFromRosTopic::hasFeature(int feature, bool* hasFeature)
335{
336 yCWarning(RGBD_ROS_TOPIC) << "hasFeature not supported";
337 return false;
338}
339
340bool RGBDSensorFromRosTopic::setFeature(int feature, double value)
341{
342 yCWarning(RGBD_ROS_TOPIC) << "setFeature not supported";
343 return false;
344}
345
346bool RGBDSensorFromRosTopic::getFeature(int feature, double *value)
347{
348 yCWarning(RGBD_ROS_TOPIC) << "getFeature not supported";
349 return false; return true;
350}
351
352bool RGBDSensorFromRosTopic::setFeature(int feature, double value1, double value2)
353{
354 yCWarning(RGBD_ROS_TOPIC) << "setFeature not supported";
355 return false;
356}
357
358bool RGBDSensorFromRosTopic::getFeature(int feature, double *value1, double *value2)
359{
360 yCWarning(RGBD_ROS_TOPIC) << "getFeature not supported";
361 return false;
362}
363
364bool RGBDSensorFromRosTopic::hasOnOff( int feature, bool *HasOnOff)
365{
366 yCWarning(RGBD_ROS_TOPIC) << "hasOnOff not supported";
367 return false;
368}
369
370bool RGBDSensorFromRosTopic::setActive( int feature, bool onoff)
371{
372 yCWarning(RGBD_ROS_TOPIC) << "setActive not supported";
373 return false;
374}
375
376bool RGBDSensorFromRosTopic::getActive( int feature, bool *isActive)
377{
378 yCWarning(RGBD_ROS_TOPIC) << "getActive not supported";
379 return false;
380}
381
382bool RGBDSensorFromRosTopic::hasAuto(int feature, bool *hasAuto)
383{
384 yCWarning(RGBD_ROS_TOPIC) << "hasAuto not supported";
385 return false;
386}
387
388bool RGBDSensorFromRosTopic::hasManual( int feature, bool* hasManual)
389{
390 yCWarning(RGBD_ROS_TOPIC) << "hasManual not supported";
391 return false;
392}
393
394bool RGBDSensorFromRosTopic::hasOnePush(int feature, bool* hasOnePush)
395{
396 yCWarning(RGBD_ROS_TOPIC) << "hasOnePush not supported";
397 return false;
398}
399
400bool RGBDSensorFromRosTopic::setMode(int feature, FeatureMode mode)
401{
402 yCWarning(RGBD_ROS_TOPIC) << "setMode not supported";
403 return false;
404}
405
406bool RGBDSensorFromRosTopic::getMode(int feature, FeatureMode* mode)
407{
408 yCWarning(RGBD_ROS_TOPIC) << "getMode not supported";
409 *mode = MODE_UNKNOWN;
410 return false;
411}
412
413bool RGBDSensorFromRosTopic::setOnePush(int feature)
414{
415 yCWarning(RGBD_ROS_TOPIC) << "setOnePush not supported";
416 return false;
417}
418*/
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.
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.
bool getFOV(double &horizontalFov, double &verticalFov) const
bool getLastDepthData(yarp::sig::ImageOf< yarp::sig::PixelFloat > &data, yarp::os::Stamp &stmp)
bool getIntrinsicParam(yarp::os::Property &intrinsic) const
bool getLastRGBData(yarp::sig::FlexImage &data, yarp::os::Stamp &stmp)
A mini-server for performing network communication in the background.
The Node class.
Definition Node.h:23
A class for storing options and configuration information.
Definition Property.h:33
void clear()
Remove all associations.
A base class for nested structures that can be searched.
Definition Searchable.h:31
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
void useCallback(TypedReaderCallback< T > &callback)
Definition Subscriber.h:135
Image class with user control of representation details.
Definition Image.h:374
A class for a Matrix.
Definition Matrix.h:39
#define yCError(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
Definition jointData.cpp:13
An interface to the operating system, including Port based communication.
constexpr char accuracy[]
#define YARP_UNUSED(var)
Definition api.h:162