genicam_device_nodelet.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Heiko Hirschmueller
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its contributors
18  * may be used to endorse or promote products derived from this software without
19  * specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #include "genicam_device_nodelet.h"
45 
46 #include <rc_genicam_api/device.h>
47 #include <rc_genicam_api/stream.h>
48 #include <rc_genicam_api/buffer.h>
49 #include <rc_genicam_api/config.h>
51 
53 #include <exception>
54 
55 #include <sstream>
56 #include <stdexcept>
57 
58 #include <ros/ros.h>
59 #include <rc_common_msgs/ReturnCodeConstants.h>
60 #include <rc_common_msgs/CameraParam.h>
61 
62 namespace rc
63 {
65 {
66  scomponents = 0;
67  scolor = 0;
68 
69  running = false;
70 
71  gev_packet_size = 0;
77  streaming = false;
78 }
79 
81 {
82  NODELET_INFO("Shutting down");
83 
84  // signal running threads and wait until they finish
85 
86  running = false;
87  if (grab_thread.joinable())
88  {
89  grab_thread.join();
90  }
91 
93 }
94 
96 {
97  NODELET_INFO("Initialization started");
98 
99  std::string ns = ros::this_node::getNamespace();
100 
101  if (ns.size() > 0 && ns[0] == '/')
102  {
103  ns = ns.substr(1);
104  }
105 
106  if (ns.size() > 0)
107  {
108  frame_id = ns + "_camera";
109  }
110  else
111  {
112  frame_id = "camera";
113  }
114 
115  // get parameter configuration
116 
118  ros::NodeHandle nh(getNodeHandle(), "");
119 
120  std::string id = "*";
121  std::string access = "control";
122 
123  pnh.param("device", id, id);
124  pnh.param("gev_access", access, access);
125 
126  rcg::Device::ACCESS access_id;
127  if (access == "exclusive")
128  {
129  access_id = rcg::Device::EXCLUSIVE;
130  }
131  else if (access == "control")
132  {
133  access_id = rcg::Device::CONTROL;
134  }
135  else
136  {
137  NODELET_FATAL_STREAM("Access must be 'control' or 'exclusive': " << access);
138  return;
139  }
140 
141  // setup services
142 
144  pnh.advertiseService("depth_acquisition_trigger", &GenICamDeviceNodelet::depthAcquisitionTrigger, this);
145 
146  // add callbacks for diagnostics publishing
147 
150 
151  // start grabbing thread
152 
153  running = true;
154  grab_thread = std::thread(&GenICamDeviceNodelet::grab, this, id, access_id);
155 
156  NODELET_INFO("Initialization done");
157 }
158 
159 bool GenICamDeviceNodelet::depthAcquisitionTrigger(rc_common_msgs::Trigger::Request& req,
160  rc_common_msgs::Trigger::Response& res)
161 {
162  std::lock_guard<std::recursive_mutex> lock(device_mtx);
163 
164  if (nodemap)
165  {
166  if (config.depth_acquisition_mode != "Continuous")
167  {
168  try
169  {
170  NODELET_DEBUG("Triggering stereo matching");
171 
172  rcg::callCommand(nodemap, "DepthAcquisitionTrigger", true);
173 
174  res.return_code.value = rc_common_msgs::ReturnCodeConstants::SUCCESS;
175  res.return_code.message = "Stereo matching was triggered.";
176  }
177  catch (const std::exception& ex)
178  {
179  res.return_code.value = rc_common_msgs::ReturnCodeConstants::INTERNAL_ERROR;
180  res.return_code.message = ex.what();
181  NODELET_ERROR_STREAM(ex.what());
182  }
183  }
184  else
185  {
186  res.return_code.value = rc_common_msgs::ReturnCodeConstants::NOT_APPLICABLE;
187  res.return_code.message = "Triggering stereo matching is only possible if acquisition_mode is set to SingleFrame "
188  "or SingleFrameOut1!";
189  NODELET_DEBUG_STREAM("" << res.return_code.message);
190  }
191  }
192  else
193  {
194  res.return_code.value = rc_common_msgs::ReturnCodeConstants::NOT_APPLICABLE;
195  res.return_code.message = "Not connected";
196  }
197 
198  return true;
199 }
200 
202 {
203  std::lock_guard<std::recursive_mutex> lock(device_mtx);
204 
206 
207  // get current camera configuration
208 
209  config.camera_fps = rcg::getFloat(nodemap, "AcquisitionFrameRate", 0, 0, true);
210 
211  std::string v = rcg::getEnum(nodemap, "ExposureAuto", true);
212 
213  if (v == "Off")
214  {
215  config.camera_exp_control = "Manual";
216  config.camera_exp_auto_mode = "Normal";
217  }
218  else if (v == "HDR")
219  {
220  config.camera_exp_control = "HDR";
221  config.camera_exp_auto_mode = "Normal";
222  }
223  else
224  {
225  config.camera_exp_control = "Auto";
226 
227  if (v == "Continuous")
228  {
229  config.camera_exp_auto_mode = "Normal";
230  }
231  else
232  {
233  config.camera_exp_auto_mode = v;
234  }
235  }
236 
237  config.camera_exp_max = rcg::getFloat(nodemap, "ExposureTimeAutoMax", 0, 0, true) / 1000000;
238 
239  try
240  {
241  config.camera_exp_auto_average_max = rcg::getFloat(nodemap, "RcExposureAutoAverageMax", 0, 0, true);
242  config.camera_exp_auto_average_min = rcg::getFloat(nodemap, "RcExposureAutoAverageMin", 0, 0, true);
243  }
244  catch (const std::exception&)
245  {
246  config.camera_exp_auto_average_max = 0.75f;
247  config.camera_exp_auto_average_min = 0.25f;
248  }
249 
250  config.camera_exp_width = rcg::getInteger(nodemap, "ExposureRegionWidth", 0, 0, true);
251  config.camera_exp_height = rcg::getInteger(nodemap, "ExposureRegionHeight", 0, 0, true);
252  config.camera_exp_offset_x = rcg::getInteger(nodemap, "ExposureRegionOffsetX", 0, 0, true);
253  config.camera_exp_offset_y = rcg::getInteger(nodemap, "ExposureRegionOffsetY", 0, 0, true);
254  config.camera_exp_value = rcg::getFloat(nodemap, "ExposureTime", 0, 0, true) / 1000000;
255 
256  rcg::setEnum(nodemap, "GainSelector", "All", false);
257  config.camera_gain_value = rcg::getFloat(nodemap, "Gain", 0, 0, true);
258 
259  config.camera_gamma = rcg::getFloat(nodemap, "Gamma", 0, 0, false);
260  if (config.camera_gamma == 0)
261  {
262  config.camera_gamma=1.0;
263  }
264 
265  try
266  {
267  std::string v = rcg::getEnum(nodemap, "BalanceWhiteAuto", true);
268 
269  config.camera_wb_auto = (v != "Off");
270  rcg::setEnum(nodemap, "BalanceRatioSelector", "Red", true);
271  config.camera_wb_ratio_red = rcg::getFloat(nodemap, "BalanceRatio", 0, 0, true);
272  rcg::setEnum(nodemap, "BalanceRatioSelector", "Blue", true);
273  config.camera_wb_ratio_blue = rcg::getFloat(nodemap, "BalanceRatio", 0, 0, true);
274  }
275  catch (const std::exception&)
276  {
277  config.camera_wb_auto = true;
278  config.camera_wb_ratio_red = 1.2;
279  config.camera_wb_ratio_blue = 2.4;
280  }
281 
282  // get depth image configuration
283 
284  config.depth_acquisition_mode = rcg::getEnum(nodemap, "DepthAcquisitionMode", true);
285  config.depth_quality = rcg::getEnum(nodemap, "DepthQuality", true);
286  config.depth_static_scene = rcg::getBoolean(nodemap, "DepthStaticScene", true);
287  config.depth_double_shot = rcg::getBoolean(nodemap, "DepthDoubleShot", false);
288  config.depth_seg = rcg::getInteger(nodemap, "DepthSeg", 0, 0, true);
289  config.depth_smooth = rcg::getBoolean(nodemap, "DepthSmooth", true);
290  config.depth_fill = rcg::getInteger(nodemap, "DepthFill", 0, 0, true);
291  config.depth_minconf = rcg::getFloat(nodemap, "DepthMinConf", 0, 0, true);
292  config.depth_mindepth = rcg::getFloat(nodemap, "DepthMinDepth", 0, 0, true);
293  config.depth_maxdepth = rcg::getFloat(nodemap, "DepthMaxDepth", 0, 0, true);
294  config.depth_maxdeptherr = rcg::getFloat(nodemap, "DepthMaxDepthErr", 0, 0, true);
295 
296  config.ptp_enabled = rcg::getBoolean(nodemap, "PtpEnable", false);
297 
298  rcg::setEnum(nodemap, "LineSelector", "Out1", true);
299  config.out1_mode = rcg::getEnum(nodemap, "LineSource", true);
300 
301  rcg::setEnum(nodemap, "LineSelector", "Out2", false);
302  config.out2_mode = rcg::getEnum(nodemap, "LineSource", true);
303 
304  try
305  {
306  config.depth_exposure_adapt_timeout = rcg::getFloat(nodemap, "DepthExposureAdaptTimeout", 0, 0, true);
307  }
308  catch (const std::exception&)
309  {
310  NODELET_WARN("rc_visard_driver: rc_visard has an older firmware, depth_exposure_adapt_timeout is not available.");
311  }
312 
313  // try to get ROS parameters: if parameter is not set in parameter server
314  // default to current sensor configuration
315 
316  pnh.param("camera_fps", config.camera_fps, config.camera_fps);
317  pnh.param("camera_exp_control", config.camera_exp_control, config.camera_exp_control);
318  pnh.param("camera_exp_auto_mode", config.camera_exp_auto_mode, config.camera_exp_auto_mode);
319  pnh.param("camera_exp_max", config.camera_exp_max, config.camera_exp_max);
320  pnh.param("camera_exp_auto_average_max", config.camera_exp_auto_average_max, config.camera_exp_auto_average_max);
321  pnh.param("camera_exp_auto_average_min", config.camera_exp_auto_average_min, config.camera_exp_auto_average_min);
322  pnh.param("camera_exp_value", config.camera_exp_value, config.camera_exp_value);
323  pnh.param("camera_gain_value", config.camera_gain_value, config.camera_gain_value);
324  pnh.param("camera_gamma", config.camera_gamma, config.camera_gamma);
325  pnh.param("camera_exp_offset_x", config.camera_exp_offset_x, config.camera_exp_offset_x);
326  pnh.param("camera_exp_offset_y", config.camera_exp_offset_y, config.camera_exp_offset_y);
327  pnh.param("camera_exp_width", config.camera_exp_width, config.camera_exp_width);
328  pnh.param("camera_exp_height", config.camera_exp_height, config.camera_exp_height);
329  pnh.param("camera_wb_auto", config.camera_wb_auto, config.camera_wb_auto);
330  pnh.param("camera_wb_ratio_red", config.camera_wb_ratio_red, config.camera_wb_ratio_red);
331  pnh.param("camera_wb_ratio_blue", config.camera_wb_ratio_blue, config.camera_wb_ratio_blue);
332  pnh.param("depth_acquisition_mode", config.depth_acquisition_mode, config.depth_acquisition_mode);
333  pnh.param("depth_quality", config.depth_quality, config.depth_quality);
334  pnh.param("depth_static_scene", config.depth_static_scene, config.depth_static_scene);
335  pnh.param("depth_double_shot", config.depth_double_shot, config.depth_double_shot);
336  pnh.param("depth_seg", config.depth_seg, config.depth_seg);
337  pnh.param("depth_smooth", config.depth_smooth, config.depth_smooth);
338  pnh.param("depth_fill", config.depth_fill, config.depth_fill);
339  pnh.param("depth_minconf", config.depth_minconf, config.depth_minconf);
340  pnh.param("depth_mindepth", config.depth_mindepth, config.depth_mindepth);
341  pnh.param("depth_maxdepth", config.depth_maxdepth, config.depth_maxdepth);
342  pnh.param("depth_maxdeptherr", config.depth_maxdeptherr, config.depth_maxdeptherr);
343  pnh.param("depth_exposure_adapt_timeout", config.depth_exposure_adapt_timeout, config.depth_exposure_adapt_timeout);
344  pnh.param("ptp_enabled", config.ptp_enabled, config.ptp_enabled);
345  pnh.param("out1_mode", config.out1_mode, config.out1_mode);
346  pnh.param("out2_mode", config.out2_mode, config.out2_mode);
347 
348  // set parameters on parameter server so that dynamic reconfigure picks them up
349 
350  pnh.setParam("camera_fps", config.camera_fps);
351  pnh.setParam("camera_exp_control", config.camera_exp_control);
352  pnh.setParam("camera_exp_auto_mode", config.camera_exp_auto_mode);
353  pnh.setParam("camera_exp_max", config.camera_exp_max);
354  pnh.setParam("camera_exp_auto_average_max", config.camera_exp_auto_average_max);
355  pnh.setParam("camera_exp_auto_average_min", config.camera_exp_auto_average_min);
356  pnh.setParam("camera_exp_value", config.camera_exp_value);
357  pnh.setParam("camera_gain_value", config.camera_gain_value);
358  pnh.setParam("camera_gamma", config.camera_gamma);
359  pnh.setParam("camera_exp_offset_x", config.camera_exp_offset_x);
360  pnh.setParam("camera_exp_offset_y", config.camera_exp_offset_y);
361  pnh.setParam("camera_exp_width", config.camera_exp_width);
362  pnh.setParam("camera_exp_height", config.camera_exp_height);
363  pnh.setParam("camera_wb_auto", config.camera_wb_auto);
364  pnh.setParam("camera_wb_ratio_red", config.camera_wb_ratio_red);
365  pnh.setParam("camera_wb_ratio_blue", config.camera_wb_ratio_blue);
366  pnh.setParam("depth_acquisition_mode", config.depth_acquisition_mode);
367  pnh.setParam("depth_quality", config.depth_quality);
368  pnh.setParam("depth_static_scene", config.depth_static_scene);
369  pnh.setParam("depth_double_shot", config.depth_double_shot);
370  pnh.setParam("depth_seg", config.depth_seg);
371  pnh.setParam("depth_smooth", config.depth_smooth);
372  pnh.setParam("depth_fill", config.depth_fill);
373  pnh.setParam("depth_minconf", config.depth_minconf);
374  pnh.setParam("depth_mindepth", config.depth_mindepth);
375  pnh.setParam("depth_maxdepth", config.depth_maxdepth);
376  pnh.setParam("depth_maxdeptherr", config.depth_maxdeptherr);
377  pnh.setParam("depth_exposure_adapt_timeout", config.depth_exposure_adapt_timeout);
378  pnh.setParam("ptp_enabled", config.ptp_enabled);
379  pnh.setParam("out1_mode", config.out1_mode);
380  pnh.setParam("out2_mode", config.out2_mode);
381 }
382 
383 namespace
384 {
385 
386 /*
387  Limit value with actual min/max values before setting.
388 */
389 
390 inline double setFloatLimited(const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
391  const char *name, double value)
392 {
393  double vmin=0;
394  double vmax=0;
395 
396  rcg::getFloat(nodemap, name, &vmin, &vmax, true);
397 
398  value = std::max(vmin, std::min(value, vmax));
399 
400  rcg::setFloat(nodemap, name, value, true);
401 
402  return value;
403 }
404 
405 inline int setIntegerLimited(const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
406  const char *name, int value)
407 {
408  int64_t vmin=0;
409  int64_t vmax=0;
410 
411  rcg::getInteger(nodemap, name, &vmin, &vmax, true);
412 
413  value = static_cast<int>(std::max(vmin, std::min(static_cast<int64_t>(value), vmax)));
414 
415  rcg::setInteger(nodemap, name, value, true);
416 
417  return value;
418 }
419 
420 }
421 
422 void GenICamDeviceNodelet::reconfigure(rc_genicam_driver::rc_genicam_driverConfig& c, uint32_t level)
423 {
424  std::lock_guard<std::recursive_mutex> lock(device_mtx);
425 
426  try
427  {
428  if (nodemap)
429  {
430  if (level & 1)
431  {
432  c.camera_fps = setFloatLimited(nodemap, "AcquisitionFrameRate", c.camera_fps);
433  }
434 
435  if (level & 2)
436  {
437  if (c.camera_exp_control == "HDR")
438  {
439  if (!rcg::setEnum(nodemap, "ExposureAuto", "HDR", false))
440  {
441  NODELET_WARN_STREAM("Sensor does not support HDR. Please update firmware.");
442  c.camera_exp_control = "Auto";
443  }
444  }
445 
446  if (c.camera_exp_control == "Auto")
447  {
448  // Normal means continuous and off must be controlled with exp_auto
449 
450  if (c.camera_exp_auto_mode == "Off" || c.camera_exp_auto_mode == "Normal")
451  {
452  c.camera_exp_auto_mode = "Continuous";
453  }
454 
455  // find user requested auto exposure mode in the list of enums
456 
457  std::vector<std::string> list;
458  rcg::getEnum(nodemap, "ExposureAuto", list, false);
459 
460  std::string mode = "Continuous";
461  for (size_t i = 0; i < list.size(); i++)
462  {
463  if (c.camera_exp_auto_mode == list[i])
464  {
465  mode = list[i];
466  }
467  }
468 
469  // set auto exposure mode
470 
471  rcg::setEnum(nodemap, "ExposureAuto", mode.c_str(), true);
472 
473  // Continuous means normal
474 
475  if (mode == "Continuous")
476  {
477  mode = "Normal";
478  }
479 
480  c.camera_exp_auto_mode = mode;
481  }
482  else if (c.camera_exp_control != "HDR")
483  {
484  c.camera_exp_control = "Manual";
485 
486  rcg::setEnum(nodemap, "ExposureAuto", "Off", true);
487 
488  usleep(100 * 1000);
489 
490  c.camera_exp_value = rcg::getFloat(nodemap, "ExposureTime", 0, 0, true, true) / 1000000;
491  c.camera_gain_value = rcg::getFloat(nodemap, "Gain", 0, 0, true, true);
492  }
493  }
494 
495  if (level & 4)
496  {
497  c.camera_exp_max = setFloatLimited(nodemap, "ExposureTimeAutoMax",
498  1000000 * c.camera_exp_max)/1000000;
499  }
500 
501  if (level & 8)
502  {
503  if (!rcg::setFloat(nodemap, "RcExposureAutoAverageMax", c.camera_exp_auto_average_max, false))
504  {
505  NODELET_WARN("rc_visard does not support parameter 'exp_auto_average_max'");
506  c.camera_exp_auto_average_max = 0.75f;
507  }
508  }
509 
510  if (level & 16)
511  {
512  if (!rcg::setFloat(nodemap, "RcExposureAutoAverageMin", c.camera_exp_auto_average_min, false))
513  {
514  NODELET_WARN("rc_visard does not support parameter 'exp_auto_average_min'");
515  c.camera_exp_auto_average_min = 0.25f;
516  }
517  }
518 
519  if (level & 32)
520  {
521  c.camera_exp_value = setFloatLimited(nodemap, "ExposureTime",
522  1000000 * c.camera_exp_value)/1000000;
523  }
524 
525  c.camera_gain_value = round(c.camera_gain_value / 6) * 6;
526 
527  if (level & 64)
528  {
529  c.camera_gain_value = setFloatLimited(nodemap, "Gain", c.camera_gain_value);
530  }
531 
532  if (level & 536870912)
533  {
534  if (!rcg::setFloat(nodemap, "Gamma", c.camera_gamma, false))
535  {
536  if (c.camera_gamma != 1.0)
537  {
538  NODELET_WARN_STREAM("Sensor does not support gamma. Please update firmware.");
539  c.camera_gamma = 1.0;
540  }
541  }
542  }
543 
544  if (level & 128)
545  {
546  c.camera_exp_offset_x = setIntegerLimited(nodemap, "ExposureRegionOffsetX",
547  c.camera_exp_offset_x);
548  }
549 
550  if (level & 256)
551  {
552  c.camera_exp_offset_y = setIntegerLimited(nodemap, "ExposureRegionOffsetY",
553  c.camera_exp_offset_y);
554  }
555 
556  if (level & 512)
557  {
558  c.camera_exp_width = setIntegerLimited(nodemap, "ExposureRegionWidth",
559  c.camera_exp_width);
560  }
561 
562  if (level & 1024)
563  {
564  c.camera_exp_height = setIntegerLimited(nodemap, "ExposureRegionHeight",
565  c.camera_exp_height);
566  }
567 
568  bool color_ok = true;
569 
570  if (level & 2048)
571  {
572  if (c.camera_wb_auto)
573  {
574  color_ok = rcg::setEnum(nodemap, "BalanceWhiteAuto", "Continuous", false);
575  }
576  else
577  {
578  color_ok = rcg::setEnum(nodemap, "BalanceWhiteAuto", "Off", false);
579 
580  usleep(100 * 1000);
581 
582  rcg::setEnum(nodemap, "BalanceRatioSelector", "Red", false);
583  c.camera_wb_ratio_red = rcg::getFloat(nodemap, "BalanceRatio", 0, 0, false, true);
584 
585  rcg::setEnum(nodemap, "BalanceRatioSelector", "Blue", false);
586  c.camera_wb_ratio_blue = rcg::getFloat(nodemap, "BalanceRatio", 0, 0, false, true);
587  }
588  }
589 
590  if (level & 4096)
591  {
592  rcg::setEnum(nodemap, "BalanceRatioSelector", "Red", false);
593  color_ok = rcg::setFloat(nodemap, "BalanceRatio", c.camera_wb_ratio_red, false);
594  }
595 
596  if (level & 8192)
597  {
598  rcg::setEnum(nodemap, "BalanceRatioSelector", "Blue", false);
599  color_ok = rcg::setFloat(nodemap, "BalanceRatio", c.camera_wb_ratio_blue, false);
600  }
601 
602  if (!color_ok)
603  {
604  c.camera_wb_auto = true;
605  c.camera_wb_ratio_red = 1.2;
606  c.camera_wb_ratio_blue = 2.4;
607  }
608 
609  if (level & 16384)
610  {
611  // correct configuration strings if needed
612 
613  if (c.depth_acquisition_mode == "S" || c.depth_acquisition_mode == "SingleFrame")
614  {
615  c.depth_acquisition_mode = "SingleFrame";
616  }
617  else if (c.depth_acquisition_mode == "O" || c.depth_acquisition_mode == "SingleFrameOut1")
618  {
619  c.depth_acquisition_mode = "SingleFrameOut1";
620  }
621  else if (c.depth_acquisition_mode == "C" || c.depth_acquisition_mode == "Continuous")
622  {
623  c.depth_acquisition_mode = "Continuous";
624  }
625  else
626  {
627  c.depth_acquisition_mode = "Continuous";
628  }
629 
630  rcg::setEnum(nodemap, "DepthAcquisitionMode", c.depth_acquisition_mode.c_str(), true);
631  }
632 
633  if (level & 32768)
634  {
635  if (c.depth_quality == "Full" || c.depth_quality == "F")
636  {
637  c.depth_quality = "Full";
638  }
639  else if (c.depth_quality == "High" || c.depth_quality == "H")
640  {
641  c.depth_quality = "High";
642  }
643  else if (c.depth_quality == "Medium" || c.depth_quality == "M")
644  {
645  c.depth_quality = "Medium";
646  }
647  else if (c.depth_quality == "Low" || c.depth_quality == "L")
648  {
649  c.depth_quality = "Low";
650  }
651  else
652  {
653  c.depth_quality = "High";
654  }
655 
656  try
657  {
658  rcg::setEnum(nodemap, "DepthQuality", c.depth_quality.c_str(), true);
659  }
660  catch (const std::exception&)
661  {
662  c.depth_quality = "High";
663  rcg::setEnum(nodemap, "DepthQuality", c.depth_quality.c_str(), false);
664 
665  NODELET_ERROR("Cannot set full quality. Sensor may have no 'stereo_plus' license!");
666  }
667  }
668 
669  if (level & 65536)
670  {
671  rcg::setBoolean(nodemap, "DepthStaticScene", c.depth_static_scene, true);
672  }
673 
674  if (level & 131072)
675  {
676  try
677  {
678  rcg::setBoolean(nodemap, "DepthDoubleShot", c.depth_double_shot, true);
679  }
680  catch (const std::exception&)
681  {
682  c.depth_double_shot = false;
683  NODELET_ERROR("Cannot set double shot mode. Please update the sensor to version >= 20.11.0!");
684  }
685  }
686 
687  if (level & 262144)
688  {
689  rcg::setInteger(nodemap, "DepthSeg", c.depth_seg, true);
690  }
691 
692  if (level & 524288 && c.depth_smooth != config.depth_smooth)
693  {
694  try
695  {
696  rcg::setBoolean(nodemap, "DepthSmooth", c.depth_smooth, true);
697  }
698  catch (const std::exception&)
699  {
700  c.depth_smooth = false;
701  rcg::setBoolean(nodemap, "DepthSmooth", c.depth_smooth, false);
702 
703  NODELET_ERROR("Cannot switch on smoothing. Sensor may have no 'stereo_plus' license!");
704  }
705  }
706 
707  if (level & 1048576)
708  {
709  rcg::setInteger(nodemap, "DepthFill", c.depth_fill, true);
710  }
711 
712  if (level & 2097152)
713  {
714  rcg::setFloat(nodemap, "DepthMinConf", c.depth_minconf, true);
715  }
716 
717  if (level & 4194304)
718  {
719  rcg::setFloat(nodemap, "DepthMinDepth", c.depth_mindepth, true);
720  }
721 
722  if (level & 8388608)
723  {
724  rcg::setFloat(nodemap, "DepthMaxDepth", c.depth_maxdepth, true);
725  }
726 
727  if (level & 16777216)
728  {
729  rcg::setFloat(nodemap, "DepthMaxDepthErr", c.depth_maxdeptherr, true);
730  }
731 
732  if ((level & 33554432) && c.ptp_enabled != config.ptp_enabled)
733  {
734  if (!rcg::setBoolean(nodemap, "PtpEnable", c.ptp_enabled, false))
735  {
736  NODELET_ERROR("Cannot change PTP.");
737  c.ptp_enabled = false;
738  }
739  }
740 
741  if ((level & 67108864) && c.out1_mode != config.out1_mode)
742  {
743  if (c.out1_mode != "Low" && c.out1_mode != "High" && c.out1_mode != "ExposureActive" &&
744  c.out1_mode != "ExposureAlternateActive")
745  {
746  c.out1_mode = "Low";
747  }
748 
749  rcg::setEnum(nodemap, "LineSelector", "Out1", true);
750 
751  if (!rcg::setEnum(nodemap, "LineSource", c.out1_mode.c_str(), false))
752  {
753  c.out1_mode = "Low";
754  NODELET_ERROR("Cannot change out1 mode. Sensor may have no 'iocontrol' license!");
755  }
756  }
757 
758  if (level & 134217728 && c.out2_mode != config.out2_mode)
759  {
760  if (c.out2_mode != "Low" && c.out2_mode != "High" && c.out2_mode != "ExposureActive" &&
761  c.out2_mode != "ExposureAlternateActive")
762  {
763  c.out2_mode = "Low";
764  }
765 
766  if (rcg::setEnum(nodemap, "LineSelector", "Out2", false))
767  {
768  if (!rcg::setEnum(nodemap, "LineSource", c.out2_mode.c_str(), false))
769  {
770  c.out2_mode = "Low";
771  NODELET_ERROR("Cannot change out2 mode. Sensor may have no 'iocontrol' license!");
772  }
773  }
774  }
775  if (level & 268435456)
776  {
777  if (!rcg::setFloat(nodemap, "DepthExposureAdaptTimeout", c.depth_exposure_adapt_timeout, false))
778  {
779  c.depth_exposure_adapt_timeout = 0.0;
780  NODELET_ERROR("Cannot set depth_exposure_adapt_timeout. Please update the sensor to version >= 21.10!");
781  }
782  }
783  }
784  }
785  catch (const std::exception& ex)
786  {
787  NODELET_ERROR_STREAM(ex.what());
788  }
789 
790  config = c;
791 }
792 
794 {
795  std::lock_guard<std::recursive_mutex> lock(device_mtx);
796 
797  // collect required components and color
798 
799  int rcomponents = 0;
800  bool rcolor = false;
801 
802  for (auto&& p : pub)
803  {
804  p->requiresComponents(rcomponents, rcolor);
805  }
806 
807  // Intensity is contained in IntensityCombined
808 
810  {
811  rcomponents &= ~GenICam2RosPublisher::ComponentIntensity;
812  }
813 
814  // enable or disable components as required
815 
816  const static struct
817  {
818  const char* name;
819  int flag;
820  } comp[] = { { "Intensity", GenICam2RosPublisher::ComponentIntensity },
821  { "IntensityCombined", GenICam2RosPublisher::ComponentIntensityCombined },
825  { 0, 0 } };
826 
827  for (size_t i = 0; comp[i].name != 0; i++)
828  {
829  if (((rcomponents ^ scomponents) & comp[i].flag) || force)
830  {
831  rcg::setEnum(nodemap, "ComponentSelector", comp[i].name, true);
832  rcg::setBoolean(nodemap, "ComponentEnable", (rcomponents & comp[i].flag), true);
833 
834  const char* status = "disabled";
835  if (rcomponents & comp[i].flag)
836  status = "enabled";
837 
838  if (!force)
839  {
840  NODELET_INFO_STREAM("Component '" << comp[i].name << "' " << status);
841  }
842  }
843  }
844 
845  // enable or disable color
846 
847  if (rcolor != scolor || force)
848  {
849  std::string format = "Mono8";
850  if (rcolor)
851  {
852  format = color_format;
853  }
854 
855  rcg::setEnum(nodemap, "ComponentSelector", "Intensity", true);
856  rcg::setEnum(nodemap, "PixelFormat", format.c_str(), false);
857  rcg::setEnum(nodemap, "ComponentSelector", "IntensityCombined", true);
858  rcg::setEnum(nodemap, "PixelFormat", format.c_str(), false);
859  }
860 
861  // store current settings
862 
863  scomponents = rcomponents;
864  scolor = rcolor;
865 }
866 
868 {
869  updateSubscriptions(false);
870 }
871 
873 {
874  stat.add("connection_loss_total", connection_loss_total);
875  stat.add("complete_buffers_total", complete_buffers_total);
876  stat.add("incomplete_buffers_total", incomplete_buffers_total);
877  stat.add("image_receive_timeouts_total", image_receive_timeouts_total);
878  stat.add("current_reconnect_trial", current_reconnect_trial);
879 
880  // general connection status
881 
882  if (device_serial.empty())
883  {
884  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Disconnected");
885  return;
886  }
887 
888  // at least we are connected to gev server
889 
890  stat.add("ip_interface", device_interface);
891  stat.add("ip_address", device_ip);
892  stat.add("gev_packet_size", gev_packet_size);
893 
894  if (scomponents)
895  {
896  if (streaming)
897  {
898  // someone subscribed to images, and we actually receive data via GigE vision
899  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Streaming");
900  }
901  else
902  {
903  // someone subscribed to images, but we do not receive any data via GigE vision (yet)
904  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No data");
905  }
906  }
907  else
908  {
909  // no one requested images -> node is ok but stale
910  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Idle");
911  }
912 }
913 
915 {
916  if (device_serial.empty())
917  {
918  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Unknown");
919  }
920  else
921  {
922  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Info");
923  stat.add("model", device_model);
924  stat.add("image_version", device_version);
925  stat.add("serial", device_serial);
926  stat.add("mac", device_mac);
927  stat.add("user_id", device_name);
928  }
929 }
930 
931 namespace
932 {
933 std::vector<std::shared_ptr<rcg::Device> > getSupportedDevices(const std::string& devid,
934  const std::vector<std::string>& iname)
935 {
936  std::vector<std::shared_ptr<rcg::System> > system = rcg::System::getSystems();
937  std::vector<std::shared_ptr<rcg::Device> > ret;
938 
939  for (size_t i = 0; i < system.size(); i++)
940  {
941  system[i]->open();
942 
943  std::vector<std::shared_ptr<rcg::Interface> > interf = system[i]->getInterfaces();
944 
945  for (size_t k = 0; k < interf.size(); k++)
946  {
947  if (interf[k]->getTLType() == "GEV" &&
948  (iname.size() == 0 || std::find(iname.begin(), iname.end(), interf[k]->getID()) != iname.end()))
949  {
950  interf[k]->open();
951 
952  std::vector<std::shared_ptr<rcg::Device> > device = interf[k]->getDevices();
953 
954  for (size_t j = 0; j < device.size(); j++)
955  {
956  if ((device[j]->getVendor() == "Roboception GmbH" ||
957  device[j]->getModel().substr(0, 9) == "rc_visard" || device[j]->getModel().substr(0, 7) == "rc_cube") &&
958  (devid == "*" || device[j]->getID() == devid || device[j]->getSerialNumber() == devid ||
959  device[j]->getDisplayName() == devid))
960  {
961  ret.push_back(device[j]);
962  }
963  }
964 
965  interf[k]->close();
966  }
967  }
968 
969  system[i]->close();
970  }
971 
972  return ret;
973 }
974 
975 class NoDeviceException : public std::invalid_argument
976 {
977 public:
978  NoDeviceException(const char* msg) : std::invalid_argument(msg)
979  {
980  }
981 };
982 
983 void split(std::vector<std::string>& list, const std::string& s, char delim, bool skip_empty = true)
984 {
985  std::stringstream in(s);
986  std::string elem;
987 
988  while (getline(in, elem, delim))
989  {
990  if (!skip_empty || elem.size() > 0)
991  {
992  list.push_back(elem);
993  }
994  }
995 }
996 
997 } // namespace
998 
1000 {
1001  try
1002  {
1003  device_model = "";
1004  device_version = "";
1005  device_serial = "";
1006  device_mac = "";
1007  device_name = "";
1008  device_interface = "";
1009  device_ip = "";
1010  gev_packet_size = 0;
1012 
1013  NODELET_INFO_STREAM("Grabbing thread started for device '" << id << "'");
1014 
1015  // loop until nodelet is killed
1016 
1017  while (running)
1018  {
1019  streaming = false;
1020 
1021  // report standard exceptions and try again
1022 
1023  try
1024  {
1025  std::shared_ptr<GenApi::CChunkAdapter> chunkadapter;
1026 
1027  {
1028  std::lock_guard<std::recursive_mutex> lock(device_mtx);
1029 
1030  // open device and get nodemap
1031 
1032  std::vector<std::string> iname; // empty
1033  std::string dname = id;
1034 
1035  {
1036  size_t i = dname.find(':');
1037  if (i != std::string::npos)
1038  {
1039  if (i > 0)
1040  {
1041  iname.push_back(id.substr(0, i));
1042  }
1043 
1044  dname = dname.substr(i + 1);
1045  }
1046  }
1047 
1048  std::vector<std::shared_ptr<rcg::Device> > devices = getSupportedDevices(dname, iname);
1049 
1050  if (devices.size() == 0)
1051  {
1052  throw NoDeviceException(("Cannot find device '" + id + "'").c_str());
1053  }
1054 
1055  if (devices.size() > 1)
1056  {
1057  throw std::invalid_argument("Too many devices, please specify unique ID");
1058  }
1059 
1060  dev = devices[0];
1061  dev->open(access);
1062  nodemap = dev->getRemoteNodeMap();
1063 
1064  // ensure that device version >= 20.04
1065 
1066  device_version = rcg::getString(nodemap, "DeviceVersion");
1067 
1068  std::vector<std::string> list;
1069  split(list, device_version, '.');
1070 
1071  if (list.size() < 3 || std::stoi(list[0]) < 20 || (std::stoi(list[0]) == 20 && std::stoi(list[1]) < 4))
1072  {
1073  running = false;
1074  throw std::invalid_argument("Device version must be 20.04 or higher: " + device_version);
1075  }
1076 
1077  // check if device is ready
1078 
1079  if (!rcg::getBoolean(nodemap, "RcSystemReady", true, true))
1080  {
1081  throw std::invalid_argument("Device is not yet ready");
1082  }
1083 
1084  // get serial number and IP
1085 
1086  device_interface = dev->getParent()->getID();
1087  device_serial = dev->getSerialNumber();
1088  device_mac = rcg::getString(nodemap, "GevMACAddress", false);
1089  device_name = rcg::getString(nodemap, "DeviceUserID", true);
1090  device_ip = rcg::getString(nodemap, "GevCurrentIPAddress", false);
1091 
1093  << "Connecting to sensor '" << device_interface << ":" << device_serial << "' alias "
1094  << dev->getDisplayName());
1095 
1097 
1098  // get model type of the device
1099 
1100  device_model = rcg::getString(nodemap, "DeviceModelName");
1101 
1102  // initialise configuration and start dynamic reconfigure server
1103 
1104  if (!reconfig)
1105  {
1107  reconfig = new dynamic_reconfigure::Server<rc_genicam_driver::rc_genicam_driverConfig>(
1109  }
1110 
1111  // initialize some values as the old values are checked in the
1112  // reconfigure callback
1113 
1114  config.depth_smooth = rcg::getBoolean(nodemap, "DepthSmooth", true);
1115 
1116  rcg::setEnum(nodemap, "LineSelector", "Out1", true);
1117  config.out1_mode = rcg::getEnum(nodemap, "LineSource", true);
1118  rcg::setEnum(nodemap, "LineSelector", "Out2", false);
1119  config.out2_mode = rcg::getEnum(nodemap, "LineSource", true);
1120 
1121  config.ptp_enabled = rcg::getBoolean(nodemap, "PtpEnable", false);
1122 
1123  // assign callback each time to trigger resetting all values
1124 
1125  dynamic_reconfigure::Server<rc_genicam_driver::rc_genicam_driverConfig>::CallbackType cb;
1126  cb = boost::bind(&GenICamDeviceNodelet::reconfigure, this, _1, _2);
1127  reconfig->setCallback(cb);
1128  }
1129 
1130  // enable chunk data and multipart
1131 
1132  rcg::setEnum(nodemap, "AcquisitionAlternateFilter", "Off", false);
1133  rcg::setEnum(nodemap, "AcquisitionMultiPartMode", "SingleComponent", true);
1134  rcg::setBoolean(nodemap, "ChunkModeActive", true, true);
1135 
1136  // set up chunk adapter
1137 
1138  chunkadapter = rcg::getChunkAdapter(nodemap, dev->getTLType());
1139 
1140  // check for color and iocontrol
1141 
1142  bool color = false;
1143 
1144  {
1145  std::vector<std::string> formats;
1146  rcg::setEnum(nodemap, "ComponentSelector", "Intensity", true);
1147  rcg::getEnum(nodemap, "PixelFormat", formats, true);
1148  for (auto&& format : formats)
1149  {
1150  if (format == "YCbCr411_8")
1151  {
1152  color_format = "YCbCr411_8";
1153  color = true;
1154  break;
1155  }
1156 
1157  if (format == "RGB8")
1158  {
1159  color_format = "RGB8";
1160  color = true;
1161  break;
1162  }
1163  }
1164  }
1165 
1166  bool iocontrol_avail = nodemap->_GetNode("LineSource")->GetAccessMode() == GenApi::RW;
1167 
1168  if (!color)
1169  {
1170  NODELET_INFO("Not a color camera. wb_auto, wb_ratio_red and wb_ratio_blue are without "
1171  "function.");
1172  }
1173 
1174  if (nodemap->_GetNode("DepthSmooth")->GetAccessMode() != GenApi::RW)
1175  {
1176  NODELET_WARN("No stereo_plus license on device. quality=full and smoothing is not available.");
1177  }
1178 
1179  if (!iocontrol_avail)
1180  {
1181  NODELET_WARN("No iocontrol license on device. out1_mode and out2_mode are without function.");
1182  }
1183 
1184  // advertise publishers
1185 
1186  ros::NodeHandle nh(getNodeHandle(), "stereo");
1188  std::function<void()> callback = std::bind(&GenICamDeviceNodelet::subChanged, this);
1189 
1190  pub.clear();
1191  scomponents = 0;
1192  scolor = false;
1193 
1194  pub.push_back(std::make_shared<CameraInfoPublisher>(nh, frame_id, true, callback));
1195  pub.push_back(std::make_shared<CameraInfoPublisher>(nh, frame_id, false, callback));
1196  pub.push_back(std::make_shared<CameraParamPublisher>(nh, frame_id, true, callback));
1197  pub.push_back(std::make_shared<CameraParamPublisher>(nh, frame_id, false, callback));
1198 
1199  pub.push_back(std::make_shared<ImagePublisher>(it, frame_id, true, false, iocontrol_avail, callback));
1200  pub.push_back(std::make_shared<ImagePublisher>(it, frame_id, false, false, iocontrol_avail, callback));
1201 
1202  if (color)
1203  {
1204  pub.push_back(std::make_shared<ImagePublisher>(it, frame_id, true, true, iocontrol_avail, callback));
1205  pub.push_back(std::make_shared<ImagePublisher>(it, frame_id, false, true, iocontrol_avail, callback));
1206  }
1207 
1208  pub.push_back(std::make_shared<DisparityPublisher>(nh, frame_id, callback));
1209  pub.push_back(std::make_shared<DisparityColorPublisher>(it, frame_id, callback));
1210  pub.push_back(std::make_shared<DepthPublisher>(nh, frame_id, callback));
1211 
1212  pub.push_back(std::make_shared<ConfidencePublisher>(nh, frame_id, callback));
1213  pub.push_back(std::make_shared<ErrorDisparityPublisher>(nh, frame_id, callback));
1214  pub.push_back(std::make_shared<ErrorDepthPublisher>(nh, frame_id, callback));
1215 
1216  pub.push_back(std::make_shared<Points2Publisher>(nh, frame_id, callback));
1217 
1218  // make nodemap available to publshers
1219 
1220  for (auto&& p : pub)
1221  {
1222  p->setNodemap(nodemap);
1223  }
1224 
1225  // update subscriptions
1226 
1227  updateSubscriptions(true);
1228 
1229  // start streaming
1230 
1231  std::vector<std::shared_ptr<rcg::Stream> > stream = dev->getStreams();
1232 
1233  if (stream.size() == 0)
1234  {
1235  throw std::invalid_argument("Device does not offer streams");
1236  }
1237 
1238  stream[0]->open();
1239  stream[0]->startStreaming();
1240 
1242 
1244 
1245  NODELET_INFO_STREAM("Start streaming images");
1246 
1247  // grabbing and publishing
1248 
1249  while (running)
1250  {
1251  // grab next buffer
1252 
1253  const rcg::Buffer* buffer = stream[0]->grab(500);
1254  std::string out1_mode_on_sensor;
1255 
1256  // process buffer
1257 
1258  if (buffer)
1259  {
1260  streaming = true;
1261 
1262  if (buffer->getIsIncomplete())
1263  {
1265  out1_mode_on_sensor = "";
1266  }
1267  else
1268  {
1270 
1271  std::lock_guard<std::recursive_mutex> lock(device_mtx);
1272 
1273  if (gev_packet_size == 0)
1274  {
1275  gev_packet_size = rcg::getInteger(nodemap, "GevSCPSPacketSize", 0, 0, false, false);
1276  }
1277 
1278  // attach buffer to nodemap to access chunk data
1279 
1280  chunkadapter->AttachBuffer(reinterpret_cast<std::uint8_t*>(buffer->getGlobalBase()),
1281  buffer->getSizeFilled());
1282 
1283  // get out1 mode on device, which may have changed
1284 
1285  rcg::setEnum(nodemap, "ChunkLineSelector", "Out1", true);
1286  out1_mode_on_sensor = rcg::getEnum(nodemap, "ChunkLineSource", true);
1287 
1288  // publish all parts of buffer
1289 
1290  uint32_t npart = buffer->getNumberOfParts();
1291  for (uint32_t part = 0; part < npart; part++)
1292  {
1293  if (buffer->getImagePresent(part))
1294  {
1295  uint64_t pixelformat = buffer->getPixelFormat(part);
1296  for (auto&& p : pub)
1297  {
1298  p->publish(buffer, part, pixelformat);
1299  }
1300  }
1301  }
1302 
1303  // detach buffer from nodemap
1304 
1305  chunkadapter->DetachBuffer();
1306  }
1307  }
1308  else
1309  {
1311  streaming = false;
1312 
1313  // get out1 mode from sensor (this is also used to check if the
1314  // connection is still valid)
1315 
1316  std::lock_guard<std::recursive_mutex> lock(device_mtx);
1317  rcg::setEnum(nodemap, "LineSelector", "Out1", true);
1318  out1_mode_on_sensor = rcg::getString(nodemap, "LineSource", true, true);
1319  }
1320 
1321  {
1322  std::lock_guard<std::recursive_mutex> lock(device_mtx);
1323 
1324  // update out1 mode, if it is different to current settings on sensor
1325  // (which is the only GEV parameter which could have changed outside this code,
1326  // i.e. on the rc_visard by the stereomatching module)
1327 
1328  if (out1_mode_on_sensor.size() == 0)
1329  {
1330  // use current settings if the value on the sensor cannot be determined
1331  out1_mode_on_sensor = config.out1_mode;
1332  }
1333 
1334  if (out1_mode_on_sensor != config.out1_mode)
1335  {
1336  config.out1_mode = out1_mode_on_sensor;
1337  reconfig->updateConfig(config);
1338  }
1339  }
1340 
1341  updater.update();
1342  }
1343 
1344  pub.clear();
1345 
1346  // stop streaming
1347 
1348  stream[0]->stopStreaming();
1349  stream[0]->close();
1350 
1351  // stop publishing
1352 
1353  device_model = "";
1354  device_version = "";
1355  device_serial = "";
1356  device_mac = "";
1357  device_name = "";
1358  device_interface = "";
1359  device_ip = "";
1360  gev_packet_size = 0;
1361  streaming = false;
1362 
1364  }
1365  catch (const NoDeviceException& ex)
1366  {
1367  // report error, wait and retry
1368 
1369  NODELET_WARN_STREAM(ex.what());
1370 
1372  streaming = false;
1373  pub.clear();
1374 
1376 
1377  sleep(3);
1378  }
1379  catch (const std::exception& ex)
1380  {
1381  // close everything and report error
1382 
1383  if (device_ip.size() > 0)
1384  {
1386  }
1387 
1388  device_model = "";
1389  device_version = "";
1390  device_serial = "";
1391  device_mac = "";
1392  device_name = "";
1393  device_interface = "";
1394  device_ip = "";
1395  gev_packet_size = 0;
1396  streaming = false;
1397 
1399  pub.clear();
1400 
1401  NODELET_ERROR_STREAM(ex.what());
1402 
1404 
1405  sleep(3);
1406  }
1407 
1408  // close device
1409 
1410  {
1411  std::lock_guard<std::recursive_mutex> lock(device_mtx);
1412 
1413  if (dev)
1414  dev->close();
1415 
1416  dev.reset();
1417  nodemap.reset();
1418  }
1419  }
1420  }
1421  catch (const std::exception& ex)
1422  {
1423  NODELET_FATAL_STREAM(ex.what());
1424  }
1425  catch (...)
1426  {
1427  NODELET_FATAL("Unknown exception");
1428  }
1429 
1430  device_model = "";
1431  device_version = "";
1432  device_serial = "";
1433  device_mac = "";
1434  device_name = "";
1435  device_interface = "";
1436  device_ip = "";
1437  gev_packet_size = 0;
1438  streaming = false;
1440 
1441  running = false;
1442  NODELET_INFO("Grabbing thread stopped");
1443 }
1444 
1445 } // namespace rc
1446 
Interface for all publishers relating to images, point clouds or other stereo-camera data...
std::shared_ptr< rcg::Device > dev
msg
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
#define NODELET_INFO_STREAM(...)
#define NODELET_ERROR(...)
bool depthAcquisitionTrigger(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
#define NODELET_WARN(...)
diagnostic_updater::Updater updater
void summary(unsigned char lvl, const std::string s)
std::istream & getline(std::istream &is, GENICAM_NAMESPACE::gcstring &str)
int64_t round(double x)
std::shared_ptr< GenApi::CChunkAdapter > getChunkAdapter(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const std::string &tltype)
static const int ComponentDisparity
ros::NodeHandle & getNodeHandle() const
void setHardwareID(const std::string &hwid)
XmlRpcServer s
static std::vector< std::shared_ptr< System > > getSystems()
size_t getSizeFilled() const
rc_genicam_driver::rc_genicam_driverConfig config
void add(const std::string &name, TaskFunction f)
__int64 int64_t
#define NODELET_WARN_STREAM(...)
int64_t getInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t *vmin=0, int64_t *vmax=0, bool exception=false, bool igncache=false)
ros::NodeHandle & getPrivateNodeHandle() const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::recursive_mutex reconfig_mtx
bool setFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double value, bool exception=false)
void * getGlobalBase() const
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
static const int ComponentConfidence
static void clearSystems()
static const int ComponentIntensity
#define NODELET_ERROR_STREAM(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool getImagePresent(std::uint32_t part) const
void publishConnectionDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ROSCPP_DECL const std::string & getNamespace()
void updateSubscriptions(bool force=false)
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
ros::ServiceServer trigger_service
#define NODELET_DEBUG_STREAM(...)
uint64_t getPixelFormat(std::uint32_t part) const
bool setBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool value, bool exception=false)
std::shared_ptr< GenApi::CNodeMapRef > nodemap
#define NODELET_INFO(...)
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *vmax=0, bool exception=false, bool igncache=false)
dynamic_reconfigure::Server< rc_genicam_driver::rc_genicam_driverConfig > * reconfig
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void publishDeviceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void grab(std::string id, rcg::Device::ACCESS access)
bool callCommand(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
bool getIsIncomplete() const
#define NODELET_FATAL_STREAM(...)
bool setInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t value, bool exception=false)
void add(const std::string &key, const T &val)
std::vector< std::shared_ptr< GenICam2RosPublisher > > pub
#define NODELET_FATAL(...)
RW
void reconfigure(rc_genicam_driver::rc_genicam_driverConfig &c, uint32_t level)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::uint32_t getNumberOfParts() const
#define NODELET_DEBUG(...)
std::string getString(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
static const int ComponentIntensityCombined
std::recursive_mutex device_mtx


rc_genicam_driver
Author(s): Heiko Hirschmueller , Felix Ruess
autogenerated on Sun Mar 12 2023 02:20:15