YARP
Yet Another Robot Platform
FrameGrabber_nws_ros.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
4 * SPDX-License-Identifier: BSD-3-Clause
5 */
6
8
10#include <yarp/os/LogStream.h>
11
12#include <yarp/dev/PolyDriver.h>
13
14#include <rosPixelCode.h>
15
16namespace {
17YARP_LOG_COMPONENT(FRAMEGRABBER_NWS_ROS, "yarp.device.frameGrabber_nws_ros")
18} // namespace
19
20
22 PeriodicThread(s_default_period)
23{
24}
25
26
28{
29 close();
30}
31
32
34{
35 if (!m_active) {
36 return false;
37 }
38 m_active = false;
39
40 detach();
41
42 publisherPort_image.interrupt();
43 publisherPort_image.close();
44
45 publisherPort_cameraInfo.interrupt();
46 publisherPort_cameraInfo.close();
47
48 if (node != nullptr) {
49 node->interrupt();
50 delete node;
51 node = nullptr;
52 }
53
54 if (subdevice) {
55 subdevice->close();
56 delete subdevice;
57 subdevice = nullptr;
58 }
59
60 isSubdeviceOwned = false;
61
62 return true;
63}
64
65
67{
68 if (m_active) {
69 yCError(FRAMEGRABBER_NWS_ROS, "Device is already opened");
70 return false;
71 }
72
73 // Check "period" option
74 if (config.check("period", "refresh period(in s) of the broadcasted values through yarp ports") && config.find("period").isFloat64()) {
75 m_period = config.find("period").asFloat64();
76 } else {
77 yCInfo(FRAMEGRABBER_NWS_ROS)
78 << "Period parameter not found, using default of"
79 << s_default_period
80 << "seconds";
81 }
82 PeriodicThread::setPeriod(m_period);
83
84 // Check "node_name" option and open node
85 if (!config.check("node_name"))
86 {
87 yCError(FRAMEGRABBER_NWS_ROS) << "Missing node_name parameter";
88 return false;
89 }
90 std::string nodeName = config.find("node_name").asString();
91 if (nodeName.c_str()[0] != '/') {
92 yCError(FRAMEGRABBER_NWS_ROS) << "Missing '/' in node_name parameter";
93 return false;
94 }
95
96 node = new yarp::os::Node(nodeName);
97
98 // Check "topic_name" option and open publisher
99 if (!config.check("topic_name"))
100 {
101 yCError(FRAMEGRABBER_NWS_ROS) << "Missing topic_name parameter";
102 return false;
103 }
104 std::string topicName = config.find("topic_name").asString();
105 if (topicName.c_str()[0] != '/') {
106 yCError(FRAMEGRABBER_NWS_ROS) << "Missing '/' in topic_name parameter";
107 return false;
108 }
109
110 // set "imageTopicName" and open publisher
111 if (!publisherPort_image.topic(topicName)) {
112 yCError(FRAMEGRABBER_NWS_ROS) << "Unable to publish data on " << topicName << " topic, check your yarp-ROS network configuration";
113 return false;
114 }
115
116 // set "cameraInfoTopicName" and open publisher
117
118
119 std::string cameraInfoTopicName = topicName.substr(0,topicName.rfind('/')) + "/camera_info";
120 if (!publisherPort_cameraInfo.topic(cameraInfoTopicName)) {
121 yCError(FRAMEGRABBER_NWS_ROS) << "Unable to publish data on" << cameraInfoTopicName << "topic, check your yarp-ROS network configuration";
122 return false;
123 }
124
125 // Check "frame_id" option
126 if (!config.check("frame_id"))
127 {
128 yCError(FRAMEGRABBER_NWS_ROS) << "Missing frame_id parameter";
129 return false;
130 }
131 m_frameId = config.find("frame_id").asString();
132
133 // Check "subdevice" option and eventually open the device
134 isSubdeviceOwned = config.check("subdevice");
135 if (isSubdeviceOwned) {
137 subdevice = new yarp::dev::PolyDriver;
138 p.fromString(config.toString());
139 p.put("pixelType", VOCAB_PIXEL_RGB);
140 p.setMonitor(config.getMonitor(), "subdevice"); // pass on any monitoring
141 p.unput("device");
142 p.put("device", config.find("subdevice").asString()); // subdevice was already checked before
143
144 // if errors occurred during open, quit here.
145 subdevice->open(p);
146
147 if (!(subdevice->isValid())) {
148 yCError(FRAMEGRABBER_NWS_ROS, "Unable to open subdevice");
149 return false;
150 }
151 if (!attach(subdevice)) {
152 yCError(FRAMEGRABBER_NWS_ROS, "Unable to attach subdevice");
153 return false;
154 }
155 } else {
156 yCInfo(FRAMEGRABBER_NWS_ROS) << "Running, waiting for attach...";
157 }
158
159 m_active = true;
160
161 return true;
162}
163
165{
166 if (!poly->isValid()) {
167 yCError(FRAMEGRABBER_NWS_ROS) << "Device " << poly << " to attach to is not valid ... cannot proceed";
168 return false;
169 }
170
171 poly->view(iRgbVisualParams);
172 poly->view(iFrameGrabberImage);
173 poly->view(iPreciselyTimed);
174
175 if (iFrameGrabberImage == nullptr) {
176 yCError(FRAMEGRABBER_NWS_ROS) << "IFrameGrabberImage interface is not available on the device";
177 return false;
178 }
179
180 if (iRgbVisualParams == nullptr) {
181 yCWarning(FRAMEGRABBER_NWS_ROS) << "IRgbVisualParams interface is not available on the device";
182 }
183
184 return PeriodicThread::start();
185}
186
187
189{
192 }
193
194 iRgbVisualParams = nullptr;
195 iFrameGrabberImage = nullptr;
196 iPreciselyTimed = nullptr;
197
198 return true;
199}
200
202{
204 return true;
205}
206
208{
209 delete img;
210 img = nullptr;
211}
212
213
214// Publish the images on the buffered port
216{
217 if (publisherPort_image.getOutputCount() == 0 && publisherPort_cameraInfo.getOutputCount() == 0) {
218 // If no ports are connected, do not call getImage on the interface.
219 return;
220 }
221
222 if (iPreciselyTimed) {
223 m_stamp = iPreciselyTimed->getLastInputStamp();
224 } else {
225 m_stamp.update(yarp::os::Time::now());
226 }
227
228 if (iFrameGrabberImage && publisherPort_image.getOutputCount() > 0) {
229 iFrameGrabberImage->getImage(*img);
230 auto& image = publisherPort_image.prepare();
231
232 image.data.resize(img->getRawImageSize());
233 image.width = img->width();
234 image.height = img->height();
236 image.step = img->getRowSize();
237 image.header.frame_id = m_frameId;
238 image.header.stamp = m_stamp.getTime();
239 image.header.seq = m_stamp.getCount();
240 image.is_bigendian = 0;
241
242 memcpy(image.data.data(), img->getRawImage(), img->getRawImageSize());
243
244 publisherPort_image.setEnvelope(m_stamp);
245 publisherPort_image.write();
246 }
247
248 if (iRgbVisualParams && publisherPort_cameraInfo.getOutputCount() > 0) {
249 auto& cameraInfo = publisherPort_cameraInfo.prepare();
250
251 if (setCamInfo(cameraInfo)) {
252 publisherPort_cameraInfo.setEnvelope(m_stamp);
253 publisherPort_cameraInfo.write();
254 } else {
255 publisherPort_cameraInfo.unprepare();
256 }
257 }
258}
259
260namespace {
261template <class T>
262struct param
263{
264 param(T& inVar, std::string inName) :
265 var(&inVar),
266 parname(std::move(inName))
267 {
268 }
269 T* var;
270 std::string parname;
271};
272} // namespace
273
274bool FrameGrabber_nws_ros::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo)
275{
276 yCAssert(FRAMEGRABBER_NWS_ROS, iRgbVisualParams);
277
278 yarp::os::Property camData;
279 if (!iRgbVisualParams->getRgbIntrinsicParam(camData)) {
280 yCErrorThreadOnce(FRAMEGRABBER_NWS_ROS) << "Unable to get intrinsic param from rgb sensor!";
281 return false;
282 }
283
284 if (!camData.check("distortionModel")) {
285 yCWarning(FRAMEGRABBER_NWS_ROS) << "Missing distortion model";
286 return false;
287 }
288
289 std::string distModel = camData.find("distortionModel").asString();
290 if (distModel != "plumb_bob") {
291 yCError(FRAMEGRABBER_NWS_ROS) << "Distortion model not supported";
292 return false;
293 }
294
295 double phyF = 0.0;
296 double fx = 0.0;
297 double fy = 0.0;
298 double cx = 0.0;
299 double cy = 0.0;
300 double k1 = 0.0;
301 double k2 = 0.0;
302 double t1 = 0.0;
303 double t2 = 0.0;
304 double k3 = 0.0;
305
306 std::vector<param<double>> parVector;
307 parVector.emplace_back(phyF,"physFocalLength");
308 parVector.emplace_back(fx,"focalLengthX");
309 parVector.emplace_back(fy,"focalLengthY");
310 parVector.emplace_back(cx,"principalPointX");
311 parVector.emplace_back(cy,"principalPointY");
312 parVector.emplace_back(k1,"k1");
313 parVector.emplace_back(k2,"k2");
314 parVector.emplace_back(t1,"t1");
315 parVector.emplace_back(t2,"t2");
316 parVector.emplace_back(k3,"k3");
317
318 for(auto& par : parVector) {
319 if(!camData.check(par.parname)) {
320 yCWarning(FRAMEGRABBER_NWS_ROS) << "Driver has not the param:" << par.parname;
321 return false;
322 }
323 *(par.var) = camData.find(par.parname).asFloat64();
324 }
325
326 cameraInfo.header.frame_id = m_frameId;
327 cameraInfo.header.seq = m_stamp.getCount();
328 cameraInfo.header.stamp = m_stamp.getTime();
329 cameraInfo.width = iRgbVisualParams->getRgbWidth();
330 cameraInfo.height = iRgbVisualParams->getRgbHeight();
331 cameraInfo.distortion_model = distModel;
332
333 cameraInfo.D.resize(5);
334 cameraInfo.D[0] = k1;
335 cameraInfo.D[1] = k2;
336 cameraInfo.D[2] = t1;
337 cameraInfo.D[3] = t2;
338 cameraInfo.D[4] = k3;
339
340 cameraInfo.K.resize(9);
341 cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
342 cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
343 cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
344
345 /*
346 * ROS documentation on cameraInfo message:
347 * "Rectification matrix (stereo cameras only)
348 * A rotation matrix aligning the camera coordinate system to the ideal
349 * stereo image plane so that epipolar lines in both stereo images are
350 * parallel."
351 * useless in our case, it will be an identity matrix
352 */
353
354 cameraInfo.R.assign(9, 0);
355 cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
356
357 cameraInfo.P.resize(12);
358 cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
359 cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
360 cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
361
362 cameraInfo.binning_x = cameraInfo.binning_y = 0;
363 cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
364 cameraInfo.roi.do_rectify = false;
365 return true;
366}
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
void run() override
Loop function.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
bool close() override
Close the DeviceDriver.
bool threadInit() override
Initialization method.
void threadRelease() override
Release method.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:88
virtual bool getImage(ImageType &image)=0
Get an image from the frame grabber.
virtual yarp::os::Stamp getLastInputStamp()=0
Return the time stamp relative to the last acquisition.
virtual bool getRgbIntrinsicParam(yarp::os::Property &intrinsic)=0
Get the intrinsic parameters of the rgb camera.
virtual int getRgbHeight()=0
Return the height of each frame.
virtual int getRgbWidth()=0
Return the width of each frame.
A container for a device driver.
Definition: PolyDriver.h:23
bool close() override
Close the DeviceDriver.
Definition: PolyDriver.cpp:173
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:196
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:140
int getOutputCount() override
Determine how many output connections this port has.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
The Node class.
Definition: Node.h:23
void interrupt()
interrupt delegates the call to the Node port interrupt.
Definition: Node.cpp:597
bool isRunning() const
Returns true when the thread is started, false otherwise.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
A class for storing options and configuration information.
Definition: Property.h:33
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Property.cpp:1051
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:1015
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Property.cpp:1041
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1046
void close() override
Stop port activity.
Definition: Publisher.h:84
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:63
bool unprepare()
Give the last prepared object back to YARP without writing it.
Definition: Publisher.h:133
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Publisher.h:90
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:148
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:123
A base class for nested structures that can be searched.
Definition: Searchable.h:63
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:124
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:34
int getCount() const
Get the sequence number.
Definition: Stamp.cpp:29
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
Definition: Value.cpp:150
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
int getPixelCode() const override
Gets pixel type identifier.
Definition: Image.h:769
size_t width() const
Gets width of image in pixels.
Definition: Image.h:163
size_t getRowSize() const
Size of the underlying image buffer rows.
Definition: Image.h:189
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition: Image.cpp:542
size_t getRawImageSize() const
Access to the internal buffer size information (this is how much memory has been allocated for the im...
Definition: Image.cpp:551
size_t height() const
Gets height of image in pixels.
Definition: Image.h:169
#define yCInfo(component,...)
Definition: LogComponent.h:171
#define yCError(component,...)
Definition: LogComponent.h:213
#define yCAssert(component, x)
Definition: LogComponent.h:240
#define yCWarning(component,...)
Definition: LogComponent.h:192
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76
#define yCErrorThreadOnce(component,...)
Definition: LogComponent.h:215
@ VOCAB_PIXEL_RGB
Definition: Image.h:44
yarp::rosmsg::sensor_msgs::CameraInfo CameraInfo
Definition: CameraInfo.h:21
STL namespace.
std::string yarp2RosPixelCode(int code)
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121