device_nodelet.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Heiko Hirschmueller, Christian Emmerich
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 "device_nodelet.h"
45 
47 
48 #include <rc_genicam_api/device.h>
49 #include <rc_genicam_api/stream.h>
50 #include <rc_genicam_api/buffer.h>
51 #include <rc_genicam_api/config.h>
53 
55 
57 #include <exception>
58 
59 #include <sstream>
60 #include <stdexcept>
61 
62 #include <ros/ros.h>
63 #include <geometry_msgs/PoseWithCovarianceStamped.h>
65 #include <rc_common_msgs/ReturnCodeConstants.h>
66 #include <rc_common_msgs/CameraParam.h>
67 
68 namespace {
69 
71  bool isRcVisardDevice(const std::string& vendor, const std::string& model)
72  {
73  bool isKuka3DPerception = vendor.find("KUKA") != std::string::npos && model.find("3d_perception") != std::string::npos;
74  bool isRcVisard = model.find("rc_visard") != std::string::npos;
75  return isKuka3DPerception || isRcVisard;
76  }
77 
79  std::vector<std::string> discoverRcVisardDevices()
80  {
81  std::vector<std::string> device_ids;
82  for (auto system : rcg::System::getSystems())
83  {
84  system->open();
85  for (auto interf : system->getInterfaces())
86  {
87  interf->open();
88  for (auto dev : interf->getDevices())
89  {
90  if (isRcVisardDevice(dev->getVendor(), dev->getModel()))
91  {
92  device_ids.push_back(dev->getID());
93  }
94  }
95  interf->close();
96  }
97  system->close();
98  }
99  return device_ids;
100  }
101 
102  void split(std::vector<std::string>& list, const std::string& s, char delim, bool skip_empty = true)
103  {
104  std::stringstream in(s);
105  std::string elem;
106 
107  while (getline(in, elem, delim))
108  {
109  if (!skip_empty || elem.size() > 0)
110  {
111  list.push_back(elem);
112  }
113  }
114  }
115 } // namespace
116 
117 namespace rc
118 {
119 namespace rcd = dynamics;
120 using rc_common_msgs::ReturnCodeConstants;
121 
123  const std::string& stream, ros::NodeHandle& nh,
124  const std::string& frame_id_prefix, bool tfEnabled,
125  bool staticImu2CamTf)
126 {
127  if (stream == "pose")
128  {
129  return ThreadedStream::Ptr(new PoseAndTFStream(rcdIface, stream, nh, frame_id_prefix, tfEnabled));
130  }
131  if (stream == "pose_ins" || stream == "pose_rt" || stream == "pose_rt_ins" || stream == "imu")
132  {
133  return ThreadedStream::Ptr(new Protobuf2RosStream(rcdIface, stream, nh, frame_id_prefix));
134  }
135  if (stream == "dynamics" || stream == "dynamics_ins")
136  {
137  return ThreadedStream::Ptr(new DynamicsStream(rcdIface, stream, nh, frame_id_prefix, !staticImu2CamTf));
138  }
139 
140  throw std::runtime_error(std::string("Not yet implemented! Stream type: ") + stream);
141 }
142 
144 {
145  reconfig = 0;
146  dev_supports_gain = false;
147  dev_supports_color = false;
148  dev_supports_wb = false;
151  iocontrol_avail = false;
152  dev_supports_double_shot = false;
154  level = 0;
155 
157 
159 
160  stopRecoverThread = false;
161  recoveryRequested = true;
162  cntConsecutiveRecoveryFails = -1; // first time not giving any warnings
168 }
169 
171 {
172  std::cout << "rc_visard_driver: Shutting down" << std::endl;
173 
174  // signal running threads and wait until they finish
175 
176  stopImageThread = true;
177  dynamicsStreams->stop_all();
178  stopRecoverThread = true;
179 
180  if (imageThread.joinable())
181  imageThread.join();
182  dynamicsStreams->join_all();
183  if (recoverThread.joinable())
184  recoverThread.join();
185 
186  delete reconfig;
187 
189 }
190 
192 {
193  // run initialization and recover routine in separate thread
195 
196  // add callbacks for diagnostics publishing
199 }
200 
202 {
203  // get parameter configuration
204 
206 
207  // device defaults to empty string which serves as a wildcard to connect to any
208  // rc_visard as long as only one sensor is available in the network
209  std::string device = "";
210  std::string access = "control";
212 
213  tfEnabled = false;
216  tfPrefix = (ns != "") ? ns + "_" : "";
217 
218  pnh.param("device", device, device);
219  pnh.param("gev_access", access, access);
220  pnh.param("max_reconnects", maxNumRecoveryTrials, maxNumRecoveryTrials);
221  pnh.param("enable_tf", tfEnabled, tfEnabled);
222  pnh.param("autostart_dynamics", autostartDynamics, autostartDynamics);
223  pnh.param("autostart_dynamics_with_slam", autostartSlam, autostartSlam);
224  pnh.param("autostop_dynamics", autostopDynamics, autostopDynamics);
225  pnh.param("autopublish_trajectory", autopublishTrajectory, autopublishTrajectory);
226 
227  rcg::Device::ACCESS access_id;
228  if (access == "exclusive")
229  {
230  access_id = rcg::Device::EXCLUSIVE;
231  }
232  else if (access == "control")
233  {
234  access_id = rcg::Device::CONTROL;
235  }
236  else if (access == "off")
237  {
238  access_id = rcg::Device::READONLY;
239  }
240  else
241  {
242  ROS_FATAL_STREAM("rc_visard_driver: Access must be 'control', 'exclusive' or 'off': " << access);
243  return;
244  }
245 
246  // setup service for depth acquisition trigger
247 
249 
250  // setup services for starting and stopping rcdynamics module
251 
258 
261  slamSaveMapService = pnh.advertiseService("slam_save_map", &DeviceNodelet::saveSlamMap, this);
262  slamLoadMapService = pnh.advertiseService("slam_load_map", &DeviceNodelet::loadSlamMap, this);
263  slamRemoveMapService = pnh.advertiseService("slam_remove_map", &DeviceNodelet::removeSlamMap, this);
264 
266  {
267  trajPublisher = getNodeHandle().advertise<nav_msgs::Path>("trajectory", 10);
268  }
269 
270  // run start-keep-alive-and-recover loop
271 
272  while (!stopRecoverThread && (
273  (maxNumRecoveryTrials < 0) ||
275  ))
276  {
277  // check if everything is running smoothly
278 
279  if (!recoveryRequested)
280  {
281  bool allSucceeded = (!imageRequested || imageSuccess);
282  if ((cntConsecutiveRecoveryFails > 0) && allSucceeded)
283  {
285  ROS_INFO("rc_visard_driver: Device successfully recovered from previous fail(s)!");
286  }
287 
288  updater.update(); // regularly update the status for publishing diagnostics (rate limited by parameter '~diagnostic_period')
289  usleep(1000 * 100);
290  continue;
291  }
292 
293  // it's not running smoothly, we need recovery
294 
298  }
299  updater.force_update(); // immediately update the diagnostics status
300 
301  // stop image and dynamics threads
302 
303  stopImageThread = true;
304  dynamicsStreams->stop_all();
305 
306  if (imageThread.joinable())
307  imageThread.join();
308  dynamicsStreams->join_all();
309 
310  // try discover, open and bring up device
311 
312  bool successfullyOpened = false;
313  while (!stopRecoverThread && !successfullyOpened && (
314  (maxNumRecoveryTrials < 0) ||
316  ))
317  {
318  // if we are recovering, put warning and wait before retrying
319 
321  {
322  ROS_ERROR_STREAM("rc_visard_driver: Failed or lost connection. Trying to recover"
323  " rc_visard_driver from failed state ("
325  << ((maxNumRecoveryTrials>=0) ? std::string("/") + std::to_string(maxNumRecoveryTrials) : "" )
326  << ")...");
327  usleep(1000 * 500);
328  }
329 
330  try
331  {
332  if (rcgdev)
333  {
334  rcgdev->close();
335  }
336 
337  if (device.size() == 0)
338  {
339  ROS_INFO("No device ID given in the private parameter 'device'! Trying to auto-detect a single rc_visard device in the network...");
340  auto device_ids = discoverRcVisardDevices();
341  if (device_ids.size() != 1)
342  {
344  throw std::runtime_error("Auto-connection with rc_visard device failed because none or multiple devices were found!");
345  }
346  ROS_INFO_STREAM("Found rc_visard device '" << device_ids[0] << "'");
347  rcgdev = rcg::getDevice(device_ids[0].c_str());
348  } else {
349  rcgdev = rcg::getDevice(device.c_str());
350  }
351 
352  if (!rcgdev)
353  {
355  throw std::invalid_argument("Unknown or non-unique device '" + device + "'");
356  }
357 
358  ROS_INFO_STREAM("rc_visard_driver: Opening connection to '" << rcgdev->getID() << "'");
359  rcgdev->open(access_id);
360  rcgnodemap = rcgdev->getRemoteNodeMap();
361 
362  // ensure that device version >= 20.04
363 
364  dev_version = rcg::getString(rcgnodemap, "DeviceVersion");
365 
366  std::vector<std::string> list;
367  split(list, dev_version, '.');
368 
369  if (list.size() < 3 || std::stoi(list[0]) < 20 || (std::stoi(list[0]) == 20 && std::stoi(list[1]) < 4))
370  {
371  throw std::invalid_argument("Device version must be 20.04 or higher: " + dev_version);
372  }
373 
374  // check if device is ready
375 
376  if (!rcg::getBoolean(rcgnodemap, "RcSystemReady", true, true))
377  {
378  ROS_INFO_STREAM("rc_visard_driver: rc_visard device not yet ready (GEV). Trying again...");
379  continue; // to next trial!
380  }
381 
382  // extract some diagnostics data from device
383  dev_serialno = rcg::getString(rcgnodemap, "DeviceID", true);
384  dev_macaddr = rcg::getString(rcgnodemap, "GevMACAddress", true);
385  dev_ipaddr = rcg::getString(rcgnodemap, "GevCurrentIPAddress", true);
386  gev_userid = rcg::getString(rcgnodemap, "DeviceUserID", true);
387  gev_packet_size = rcg::getString(rcgnodemap, "GevSCPSPacketSize", true);
388 
391 
392  // instantiating dynamics interface, check if ready, and autostart dynamics on sensor if desired
393 
394  dynamicsInterface = rcd::RemoteInterface::create(dev_ipaddr);
395  try {
396  if (!dynamicsInterface->checkSystemReady())
397  {
398  ROS_INFO_STREAM("rc_visard_driver: rc_visard device not yet ready (REST). Trying again...");
399  continue; // to next trial!
400  }
401  } catch (std::exception& e)
402  {
403  ROS_ERROR_STREAM("rc_visard_driver: checking system ready failed: " << e.what());
404  }
405 
407  {
408  ROS_INFO_STREAM("rc_visard_driver: Auto-start requested (" <<
409  "autostart_dynamics=" << autostartDynamics << ", "
410  "autostart_dynamics_with_slam=" << autostartSlam << ")");
411 
412  rc_common_msgs::Trigger::Request dummyreq;
413  rc_common_msgs::Trigger::Response dummyresp;
414 
415  bool autostart_failed = false;
416  autostart_failed |= (autostartSlam && !this->dynamicsStartSlam(dummyreq, dummyresp));
417  autostart_failed |= (!autostartSlam && autostartDynamics && !this->dynamicsStart(dummyreq, dummyresp));
418  autostart_failed |= dummyresp.return_code.value < ReturnCodeConstants::SUCCESS;
419 
420  if (autostart_failed)
421  {
422  ROS_WARN_STREAM("rc_visard_driver: Could not auto-start dynamics module! " << dummyresp.return_code.message);
424  continue; // to next trial!
425  }
426  }
427 
428  // get and publish static transform between IMU and camera (if feature available)
429 
430  bool staticImu2CamTf = false;
431  try {
432  auto pbFrame = dynamicsInterface->getCam2ImuTransform();
433 
434  // first prefix all frame ids
435  pbFrame.set_name(tfPrefix + pbFrame.name());
436  pbFrame.set_parent(tfPrefix + pbFrame.parent());
437 
438  // invert cam2imu and convert to tf transform
439  auto imu2cam = tf::StampedTransform(
440  toRosTfTransform(pbFrame.pose().pose()).inverse(),
441  toRosTime(pbFrame.pose().timestamp()),
442  pbFrame.name(), pbFrame.parent());
443  // send it
444  geometry_msgs::TransformStamped msg;
445  tf::transformStampedTFToMsg(imu2cam, msg);
447  staticImu2CamTf = true;
448 
449  } catch (rcd::RemoteInterface::NotAvailable& e)
450  {
451  ROS_WARN_STREAM("rc_visard_driver: Could not get and publish static transformation between camera and IMU "
452  << "because feature is not avilable in that rc_visard firmware version. Please update the firmware image "
453  << "or subscribe to the dynamics topic to have that transformation available in tf.");
454  }
455 
456  // add streaming thread for each available stream on rc_visard device
457 
458  auto availStreams = dynamicsInterface->getAvailableStreams();
460  for (const auto& streamName : availStreams)
461  {
462  try
463  {
464  auto newStream =
466  dynamicsStreams->add(newStream);
467  }
468  catch (const std::exception& e)
469  {
470  ROS_WARN_STREAM("rc_visard_driver: Unable to create dynamics stream of type " << streamName << ": "
471  << e.what());
472  }
473  }
474 
475  successfullyOpened = true;
477  }
478  catch (std::exception& ex)
479  {
481  ROS_ERROR_STREAM("rc_visard_driver: " << ex.what());
482  }
483  }
484  if (stopRecoverThread)
485  break;
486 
488  {
489  ROS_FATAL_STREAM("rc_visard_driver: could not recover from failed state!");
490  break;
491  }
492 
493  // start grabbing threads
494 
495  recoveryRequested = false;
496  if (access_id != rcg::Device::READONLY)
497  {
498  imageThread = std::thread(&DeviceNodelet::grab, this, device, access_id);
499  }
500  dynamicsStreams->start_all();
501 
502  }
503 
504  if (autostopDynamics)
505  {
506  rc_common_msgs::Trigger::Request dummyreq;
507  rc_common_msgs::Trigger::Response dummyresp;
508  ROS_INFO("rc_visard_driver: Autostop dynamics ...");
509  if (!this->dynamicsStop(dummyreq, dummyresp))
510  { // autostop failed!
511  ROS_WARN("rc_visard_driver: Could not auto-stop dynamics module!");
512  }
513  }
514  std::cout << "rc_visard_driver: stopped." << std::endl;
515 }
516 
517 void DeviceNodelet::initConfiguration(const std::shared_ptr<GenApi::CNodeMapRef>& nodemap,
518  rc_visard_driver::rc_visard_driverConfig& cfg, rcg::Device::ACCESS access)
519 {
521 
522  // get current camera configuration
523 
524  cfg.camera_fps = rcg::getFloat(nodemap, "AcquisitionFrameRate", 0, 0, true);
525 
526  std::string v = rcg::getEnum(nodemap, "ExposureAuto", true);
527  cfg.camera_exp_auto = (v != "Off");
528 
529  if (cfg.camera_exp_auto)
530  {
531  if (v == "Continuous")
532  {
533  cfg.camera_exp_auto_mode = "Normal";
534  }
535  else
536  {
537  cfg.camera_exp_auto_mode = v;
538  }
539  }
540 
541  cfg.camera_exp_value = rcg::getFloat(nodemap, "ExposureTime", 0, 0, true) / 1000000;
542  cfg.camera_exp_max = rcg::getFloat(nodemap, "ExposureTimeAutoMax", 0, 0, true) / 1000000;
543 
544  // get optional exposure region
545  cfg.camera_exp_width = rcg::getInteger(nodemap, "ExposureRegionWidth", 0, 0, false);
546  cfg.camera_exp_height = rcg::getInteger(nodemap, "ExposureRegionHeight", 0, 0, false);
547  cfg.camera_exp_offset_x = rcg::getInteger(nodemap, "ExposureRegionOffsetX", 0, 0, false);
548  cfg.camera_exp_offset_y = rcg::getInteger(nodemap, "ExposureRegionOffsetY", 0, 0, false);
549 
550  // get optional gain value
551 
552  v = rcg::getEnum(nodemap, "GainSelector", false);
553  if (v.size() > 0)
554  {
555  dev_supports_gain = true;
556 
557  if (v != "All")
558  {
559  dev_supports_gain = rcg::setEnum(nodemap, "GainSelector", "All", true);
560  }
561 
562  if (dev_supports_gain)
563  {
564  cfg.camera_gain_value = rcg::getFloat(nodemap, "Gain", 0, 0, true);
565  }
566  }
567  else
568  {
569  ROS_WARN("rc_visard_driver: Device does not support setting gain. gain_value is without function.");
570 
571  dev_supports_gain = false;
572  cfg.camera_gain_value = 0;
573  }
574 
575  // check if camera is color camera
576 
577  std::vector<std::string> formats;
578  rcg::setEnum(rcgnodemap, "ComponentSelector", "Intensity", true);
579  rcg::getEnum(rcgnodemap, "PixelFormat", formats, true);
580  for (auto&& format : formats)
581  {
582  if (format == "YCbCr411_8")
583  {
584  dev_supports_color = true;
585  color_format = "YCbCr411_8";
586  break;
587  }
588  if (format == "RGB8")
589  {
590  dev_supports_color = true;
591  color_format = "RGB8";
592  break;
593  }
594 
595  }
596 
597  // get optional white balancing values (only for color camera)
598 
599  v = rcg::getEnum(nodemap, "BalanceWhiteAuto", false);
600  if (dev_supports_color && v.size() > 0)
601  {
602  dev_supports_wb = true;
603  cfg.camera_wb_auto = (v != "Off");
604  rcg::setEnum(nodemap, "BalanceRatioSelector", "Red", true);
605  cfg.camera_wb_ratio_red = rcg::getFloat(nodemap, "BalanceRatio", 0, 0, true);
606  rcg::setEnum(nodemap, "BalanceRatioSelector", "Blue", true);
607  cfg.camera_wb_ratio_blue = rcg::getFloat(nodemap, "BalanceRatio", 0, 0, true);
608  }
609  else
610  {
611  ROS_WARN("rc_visard_driver: Not a color camera. wb_auto, wb_ratio_red and wb_ratio_blue are without function.");
612 
613  dev_supports_wb = false;
614  cfg.camera_wb_auto = true;
615  cfg.camera_wb_ratio_red = 1;
616  cfg.camera_wb_ratio_blue = 1;
617  }
618 
619  // get current depth image configuration
620 
621  v = rcg::getEnum(nodemap, "DepthAcquisitionMode", false);
622  if (v.size() > 0)
623  {
625  cfg.depth_acquisition_mode = v;
626  }
627  else
628  {
629  ROS_WARN("rc_visard_driver: Device does not support triggering depth images. depth_acquisition_mode is without function.");
630 
632  cfg.depth_acquisition_mode = "Continuous";
633  }
634 
635  v = rcg::getEnum(nodemap, "DepthQuality", true);
636  cfg.depth_quality = v;
637 
638  cfg.depth_static_scene = rcg::getBoolean(nodemap, "DepthStaticScene", false);
639  cfg.depth_seg = rcg::getInteger(nodemap, "DepthSeg", 0, 0, true);
640  cfg.depth_fill = rcg::getInteger(nodemap, "DepthFill", 0, 0, true);
641  cfg.depth_minconf = rcg::getFloat(nodemap, "DepthMinConf", 0, 0, true);
642  cfg.depth_mindepth = rcg::getFloat(nodemap, "DepthMinDepth", 0, 0, true);
643  cfg.depth_maxdepth = rcg::getFloat(nodemap, "DepthMaxDepth", 0, 0, true);
644  cfg.depth_maxdeptherr = rcg::getFloat(nodemap, "DepthMaxDepthErr", 0, 0, true);
645 
646  cfg.ptp_enabled = rcg::getBoolean(nodemap, "PtpEnable", false);
647 
648  // check for stereo_plus license
649 
650  try
651  {
652  cfg.depth_smooth = rcg::getBoolean(nodemap, "DepthSmooth", true);
653  stereo_plus_avail = nodemap->_GetNode("DepthSmooth")->GetAccessMode() == GenApi::RW;
654 
655  if (!stereo_plus_avail)
656  {
657  ROS_INFO("rc_visard_driver: License for stereo_plus not available, disabling depth_quality=Full and depth_smooth.");
658  }
659  }
660  catch (const std::exception&)
661  {
662  ROS_WARN("rc_visard_driver: rc_visard has an older firmware, disabling depth_quality=Full and depth_smooth.");
663  stereo_plus_avail = false;
664  }
665 
666  try
667  {
668  cfg.depth_double_shot = rcg::getBoolean(nodemap, "DepthDoubleShot", true);
670  }
671  catch (const std::exception&)
672  {
673  dev_supports_double_shot = false;
674  ROS_WARN("rc_visard_driver: rc_visard has an older firmware, depth_double_shot is not available.");
675  }
676 
677  // check if io-control is available and get values
678 
679  try
680  {
681  // get current values
682 
683  rcg::setEnum(nodemap, "LineSelector", "Out1", true);
684  cfg.out1_mode = rcg::getString(nodemap, "LineSource", true);
685 
686  rcg::setEnum(nodemap, "LineSelector", "Out2", true);
687  cfg.out2_mode = rcg::getString(nodemap, "LineSource", true);
688 
689  // check if license for IO control functions is available
690 
691  iocontrol_avail = nodemap->_GetNode("LineSource")->GetAccessMode() == GenApi::RW;
692 
693  if (!iocontrol_avail)
694  {
695  ROS_INFO("rc_visard_driver: License for iocontrol module not available, disabling out1_mode and out2_mode.");
696  }
697  }
698  catch (const std::exception&)
699  {
700  ROS_WARN("rc_visard_driver: rc_visard has an older firmware, IO control functions are not available.");
701 
702  cfg.out1_mode = "ExposureActive";
703  cfg.out2_mode = "Low";
704 
705  iocontrol_avail = false;
706  }
707 
708  // enabling chunk data for getting live camera/image parameters
709  // (e.g. line status, current gain and exposure, etc.)
710 
711  rcg::setEnum(nodemap, "AcquisitionAlternateFilter", "Off", false);
712  rcg::setEnum(nodemap, "AcquisitionMultiPartMode", "SingleComponent", true);
713  rcg::setBoolean(nodemap, "ChunkModeActive", true, true);
714 
715  try
716  {
717  cfg.depth_exposure_adapt_timeout = rcg::getFloat(nodemap, "DepthExposureAdaptTimeout", 0, 0, true);
719  }
720  catch (const std::exception&)
721  {
723  NODELET_WARN("rc_visard_driver: rc_visard has an older firmware, depth_exposure_adapt_timeout is not available.");
724  }
725 
726  // try to get ROS parameters: if parameter is not set in parameter server, default to current sensor configuration
727 
728  pnh.param("camera_fps", cfg.camera_fps, cfg.camera_fps);
729  pnh.param("camera_exp_auto", cfg.camera_exp_auto, cfg.camera_exp_auto);
730  pnh.param("camera_exp_auto_mode", cfg.camera_exp_auto_mode, cfg.camera_exp_auto_mode);
731  pnh.param("camera_exp_value", cfg.camera_exp_value, cfg.camera_exp_value);
732  pnh.param("camera_gain_value", cfg.camera_gain_value, cfg.camera_gain_value);
733  pnh.param("camera_exp_max", cfg.camera_exp_max, cfg.camera_exp_max);
734  pnh.param("camera_exp_width", cfg.camera_exp_width, cfg.camera_exp_width);
735  pnh.param("camera_exp_height", cfg.camera_exp_height, cfg.camera_exp_height);
736  pnh.param("camera_exp_offset_x", cfg.camera_exp_offset_x, cfg.camera_exp_offset_x);
737  pnh.param("camera_exp_offset_y", cfg.camera_exp_offset_y, cfg.camera_exp_offset_y);
738  pnh.param("camera_wb_auto", cfg.camera_wb_auto, cfg.camera_wb_auto);
739  pnh.param("camera_wb_ratio_red", cfg.camera_wb_ratio_red, cfg.camera_wb_ratio_red);
740  pnh.param("camera_wb_ratio_blue", cfg.camera_wb_ratio_blue, cfg.camera_wb_ratio_blue);
741  pnh.param("depth_acquisition_mode", cfg.depth_acquisition_mode, cfg.depth_acquisition_mode);
742  pnh.param("depth_quality", cfg.depth_quality, cfg.depth_quality);
743  pnh.param("depth_static_scene", cfg.depth_static_scene, cfg.depth_static_scene);
744  pnh.param("depth_double_shot", cfg.depth_double_shot, cfg.depth_double_shot);
745  pnh.param("depth_seg", cfg.depth_seg, cfg.depth_seg);
746  pnh.param("depth_smooth", cfg.depth_smooth, cfg.depth_smooth);
747  pnh.param("depth_fill", cfg.depth_fill, cfg.depth_fill);
748  pnh.param("depth_minconf", cfg.depth_minconf, cfg.depth_minconf);
749  pnh.param("depth_mindepth", cfg.depth_mindepth, cfg.depth_mindepth);
750  pnh.param("depth_maxdepth", cfg.depth_maxdepth, cfg.depth_maxdepth);
751  pnh.param("depth_maxdeptherr", cfg.depth_maxdeptherr, cfg.depth_maxdeptherr);
752  pnh.param("depth_exposure_adapt_timeout", cfg.depth_exposure_adapt_timeout, cfg.depth_exposure_adapt_timeout);
753  pnh.param("ptp_enabled", cfg.ptp_enabled, cfg.ptp_enabled);
754  pnh.param("out1_mode", cfg.out1_mode, cfg.out1_mode);
755  pnh.param("out2_mode", cfg.out2_mode, cfg.out2_mode);
756 
757  // set parameters on parameter server so that dynamic reconfigure picks them up
758 
759  pnh.setParam("camera_fps", cfg.camera_fps);
760  pnh.setParam("camera_exp_auto", cfg.camera_exp_auto);
761  pnh.setParam("camera_exp_auto_mode", cfg.camera_exp_auto_mode);
762  pnh.setParam("camera_exp_value", cfg.camera_exp_value);
763  pnh.setParam("camera_gain_value", cfg.camera_gain_value);
764  pnh.setParam("camera_exp_max", cfg.camera_exp_max);
765  pnh.setParam("camera_exp_width", cfg.camera_exp_width);
766  pnh.setParam("camera_exp_height", cfg.camera_exp_height);
767  pnh.setParam("camera_exp_offset_x", cfg.camera_exp_offset_x);
768  pnh.setParam("camera_exp_offset_y", cfg.camera_exp_offset_y);
769  pnh.setParam("camera_wb_auto", cfg.camera_wb_auto);
770  pnh.setParam("camera_wb_ratio_red", cfg.camera_wb_ratio_red);
771  pnh.setParam("camera_wb_ratio_blue", cfg.camera_wb_ratio_blue);
772  pnh.setParam("depth_acquisition_mode", cfg.depth_acquisition_mode);
773  pnh.setParam("depth_quality", cfg.depth_quality);
774  pnh.setParam("depth_static_scene", cfg.depth_static_scene);
775  pnh.setParam("depth_double_shot", cfg.depth_double_shot);
776  pnh.setParam("depth_seg", cfg.depth_seg);
777  pnh.setParam("depth_smooth", cfg.depth_smooth);
778  pnh.setParam("depth_fill", cfg.depth_fill);
779  pnh.setParam("depth_minconf", cfg.depth_minconf);
780  pnh.setParam("depth_mindepth", cfg.depth_mindepth);
781  pnh.setParam("depth_maxdepth", cfg.depth_maxdepth);
782  pnh.setParam("depth_maxdeptherr", cfg.depth_maxdeptherr);
783  pnh.setParam("depth_exposure_adapt_timeout", cfg.depth_exposure_adapt_timeout);
784  pnh.setParam("ptp_enabled", cfg.ptp_enabled);
785  pnh.setParam("out1_mode", cfg.out1_mode);
786  pnh.setParam("out2_mode", cfg.out2_mode);
787 
788  if (reconfig == 0)
789  {
790  // TODO: we need to dismangle initialization of dynreconfserver from not-READONLY-access-condition
791  reconfig = new dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>(mtx, pnh);
792  }
793  // always set callback to (re)load configuration even after recovery
794  dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>::CallbackType cb;
795  cb = boost::bind(&DeviceNodelet::reconfigure, this, _1, _2);
796  reconfig->setCallback(cb);
797 }
798 
799 void DeviceNodelet::reconfigure(rc_visard_driver::rc_visard_driverConfig& c, uint32_t l)
800 {
801  boost::recursive_mutex::scoped_lock lock(mtx);
802 
803  // check and correct parameters
804 
805  if (!dev_supports_gain)
806  {
807  c.camera_gain_value = 0;
808  l &= ~8192;
809  }
810 
812  {
813  c.depth_double_shot = false;
814  l &= ~32;
815  }
816 
817  c.camera_gain_value = round(c.camera_gain_value / 6) * 6;
818 
819  if (!dev_supports_wb)
820  {
821  c.camera_wb_auto = true;
822  c.camera_wb_ratio_red = 1;
823  c.camera_wb_ratio_blue = 1;
824  l &= ~(16384 | 32768 | 65536);
825  }
826 
828  {
829  c.depth_acquisition_mode = "Continuous";
830  l &= ~1048576;
831  }
832 
833  if (c.depth_quality[0] == 'L')
834  {
835  c.depth_quality = "Low";
836  }
837  else if (c.depth_quality[0] == 'M')
838  {
839  c.depth_quality = "Medium";
840  }
841  else if (c.depth_quality[0] == 'F' && stereo_plus_avail)
842  {
843  c.depth_quality = "Full";
844  }
845  else
846  {
847  c.depth_quality = "High";
848  }
849 
850  if (!stereo_plus_avail)
851  {
852  c.depth_smooth=false;
853  l &= ~4194304;
854  }
855 
856  if (iocontrol_avail)
857  {
858  if (c.out1_mode != "Low" && c.out1_mode != "High" && c.out1_mode != "ExposureActive" &&
859  c.out1_mode != "ExposureAlternateActive")
860  {
861  c.out1_mode = "Low";
862  }
863 
864  if (c.out2_mode != "Low" && c.out2_mode != "High" && c.out2_mode != "ExposureActive" &&
865  c.out2_mode != "ExposureAlternateActive")
866  {
867  c.out2_mode = "Low";
868  }
869  }
870  else
871  {
872  c.out1_mode = "Low";
873  c.out2_mode = "Low";
874  }
875 
877  {
878  c.depth_exposure_adapt_timeout = 0.0;
879  l &= ~268435456;
880  }
881 
882  // if out1_mode or out2_mode are changed, immediately set new value here
883  // If we do this in the grabbing thread we have a race condition and another parameter update
884  if (l & 262144)
885  {
886  l &= ~262144;
887 
889  {
890  rcg::setEnum(rcgnodemap, "LineSelector", "Out1", false);
891  rcg::setEnum(rcgnodemap, "LineSource", c.out1_mode.c_str(), false);
892  ROS_DEBUG_STREAM("Set LineSource Out1 to " << c.out1_mode);
893  }
894  }
895 
896  if (l & 524288)
897  {
898  l &= ~524288;
899 
901  {
902  rcg::setEnum(rcgnodemap, "LineSelector", "Out2", false);
903  rcg::setEnum(rcgnodemap, "LineSource", c.out2_mode.c_str(), false);
904  ROS_DEBUG_STREAM("Set LineSource Out2 to " << c.out2_mode);
905  }
906  }
907 
908  // If camera_exp_auto (ExposureAuto) is changed, immediately set new value here
909  // so that ExposureTime and Gain can be read and published again.
910  // If we do this in the grabbing thread we have a race condition and another parameter update
911  // in the meantime could be lost because we need to overwrite the config with the updated time and gain values.
912  if (l & 2)
913  {
914  l &= ~2;
915 
916  if (rcgnodemap)
917  {
918  if (c.camera_exp_auto)
919  {
920  std::string mode = c.camera_exp_auto_mode;
921  if (mode == "Normal") mode = "Continuous";
922 
923  if (!rcg::setEnum(rcgnodemap, "ExposureAuto", mode.c_str(), false))
924  {
925  c.camera_exp_auto_mode = "Normal";
926  rcg::setEnum(rcgnodemap, "ExposureAuto", "Continuous", true);
927  }
928  }
929  else
930  {
931  rcg::setEnum(rcgnodemap, "ExposureAuto", "Off", true);
932  }
933 
934  // if exposure mode changed to manual, read current exposure value and gain again
935  if (!c.camera_exp_auto)
936  {
937  c.camera_exp_value = rcg::getFloat(rcgnodemap, "ExposureTime", 0, 0, true, true) / 1000000;
938  if (dev_supports_gain)
939  {
940  c.camera_gain_value = rcg::getFloat(rcgnodemap, "Gain", 0, 0, true, true);
941  }
942  }
943  }
944  }
945 
946  // copy config for using it in the grabbing thread
947 
948  config = c;
949  level |= l;
950 }
951 
952 namespace
953 {
954 /*
955  Set changed values of the given configuration.
956 */
957 
958 void setConfiguration(const std::shared_ptr<GenApi::CNodeMapRef>& nodemap,
959  const rc_visard_driver::rc_visard_driverConfig& cfg, uint32_t lvl, bool iocontrol_avail)
960 {
961  uint32_t prev_lvl = 0;
962 
963  while (lvl != 0 && prev_lvl != lvl)
964  {
965  prev_lvl = lvl; // used to avoid endless loops
966 
967  try
968  {
969  // NOTE: The flags used in lvl are defined in cfg/rc_visard_driver.cfg
970 
971  // set changed values via genicam
972 
973  if (lvl & 1)
974  {
975  lvl &= ~1;
976  rcg::setFloat(nodemap, "AcquisitionFrameRate", cfg.camera_fps, true);
977  ROS_DEBUG_STREAM("Set AcquisitionFrameRate to " << cfg.camera_fps);
978  }
979 
980  // lvl 2 (camera_exp_auto) is immediately set in dynamic reconfigure callback
981 
982  if (lvl & 4)
983  {
984  lvl &= ~4;
985  rcg::setFloat(nodemap, "ExposureTime", 1000000 * cfg.camera_exp_value, true);
986  ROS_DEBUG_STREAM("Set ExposureTime to " << cfg.camera_exp_value);
987  }
988 
989  if (lvl & 8192)
990  {
991  lvl &= ~8192;
992  rcg::setFloat(nodemap, "Gain", cfg.camera_gain_value, true);
993  ROS_DEBUG_STREAM("Set Gain to " << cfg.camera_gain_value);
994  }
995 
996  if (lvl & 8)
997  {
998  lvl &= ~8;
999  rcg::setFloat(nodemap, "ExposureTimeAutoMax", 1000000 * cfg.camera_exp_max, true);
1000  ROS_DEBUG_STREAM("Set ExposureTimeAutoMax to " << cfg.camera_exp_max);
1001  }
1002 
1003  if (lvl & 8388608)
1004  {
1005  lvl &= ~8388608;
1006  rcg::setInteger(nodemap, "ExposureRegionWidth", cfg.camera_exp_width, false);
1007  ROS_DEBUG_STREAM("Set ExposureRegionWidth to " << cfg.camera_exp_width);
1008  }
1009 
1010  if (lvl & 16777216)
1011  {
1012  lvl &= ~16777216;
1013  rcg::setInteger(nodemap, "ExposureRegionHeight", cfg.camera_exp_height, false);
1014  ROS_DEBUG_STREAM("Set ExposureRegionHeight to " << cfg.camera_exp_height);
1015  }
1016 
1017  if (lvl & 33554432)
1018  {
1019  lvl &= ~33554432;
1020  rcg::setInteger(nodemap, "ExposureRegionOffsetX", cfg.camera_exp_offset_x, false);
1021  ROS_DEBUG_STREAM("Set ExposureRegionOffsetX to " << cfg.camera_exp_offset_x);
1022  }
1023 
1024  if (lvl & 67108864)
1025  {
1026  lvl &= ~67108864;
1027  rcg::setInteger(nodemap, "ExposureRegionOffsetY", cfg.camera_exp_offset_y, false);
1028  ROS_DEBUG_STREAM("Set ExposureRegionOffsetY to " << cfg.camera_exp_offset_y);
1029  }
1030 
1031  if (lvl & 16384)
1032  {
1033  lvl &= ~16384;
1034 
1035  if (cfg.camera_wb_auto)
1036  {
1037  rcg::setEnum(nodemap, "BalanceWhiteAuto", "Continuous", false);
1038  ROS_DEBUG_STREAM("Set BalanceWhiteAuto to " << "Continuous");
1039  }
1040  else
1041  {
1042  rcg::setEnum(nodemap, "BalanceWhiteAuto", "Off", false);
1043  ROS_DEBUG_STREAM("Set BalanceWhiteAuto to " << "Off");
1044  }
1045  }
1046 
1047  if (lvl & 32768)
1048  {
1049  lvl &= ~32768;
1050 
1051  rcg::setEnum(nodemap, "BalanceRatioSelector", "Red", false);
1052  rcg::setFloat(nodemap, "BalanceRatio", cfg.camera_wb_ratio_red, false);
1053  ROS_DEBUG_STREAM("Set BalanceRatio Red to " << cfg.camera_wb_ratio_red);
1054  }
1055 
1056  if (lvl & 65536)
1057  {
1058  lvl &= ~65536;
1059 
1060  rcg::setEnum(nodemap, "BalanceRatioSelector", "Blue", false);
1061  rcg::setFloat(nodemap, "BalanceRatio", cfg.camera_wb_ratio_blue, false);
1062  ROS_DEBUG_STREAM("Set BalanceRatio Blue to " << cfg.camera_wb_ratio_blue);
1063  }
1064 
1065  if (lvl & 1048576)
1066  {
1067  lvl &= ~1048576;
1068 
1069  std::vector<std::string> list;
1070  rcg::getEnum(nodemap, "DepthAcquisitionMode", list, true);
1071 
1072  std::string val;
1073  for (size_t i = 0; i < list.size(); i++)
1074  {
1075  if (list[i].compare(cfg.depth_acquisition_mode) == 0)
1076  {
1077  val = list[i];
1078  }
1079  }
1080 
1081  if (val.size() > 0)
1082  {
1083  rcg::setEnum(nodemap, "DepthAcquisitionMode", val.c_str(), true);
1084  ROS_DEBUG_STREAM("Set DepthAcquisitionMode to " << val);
1085  }
1086  else
1087  {
1088  ROS_WARN_STREAM("DepthAcquisitionMode " << cfg.depth_acquisition_mode << " not supported by rc_visard");
1089  }
1090 
1091  }
1092 
1093  if (lvl & 16)
1094  {
1095  lvl &= ~16;
1096 
1097  std::vector<std::string> list;
1098  rcg::getEnum(nodemap, "DepthQuality", list, true);
1099 
1100  std::string val;
1101 
1102  if (cfg.depth_quality == "High" && cfg.depth_static_scene)
1103  {
1104  // support for rc_visard < 1.5
1105 
1106  for (size_t i = 0; i < list.size() && val.size() == 0; i++)
1107  {
1108  if (list[i].compare(0, 1, "StaticHigh", 0, 1) == 0)
1109  {
1110  val = "StaticHigh";
1111  }
1112  }
1113  }
1114 
1115  for (size_t i = 0; i < list.size() && val.size() == 0; i++)
1116  {
1117  if (list[i].compare(0, 1, cfg.depth_quality, 0, 1) == 0)
1118  {
1119  val = list[i];
1120  }
1121  }
1122 
1123  if (val.size() > 0)
1124  {
1125  rcg::setEnum(nodemap, "DepthQuality", val.c_str(), true);
1126  ROS_DEBUG_STREAM("Set DepthQuality to " << val);
1127  }
1128  }
1129 
1130  if (lvl & 32)
1131  {
1132  lvl &= ~32;
1133  rcg::setBoolean(nodemap, "DepthDoubleShot", cfg.depth_double_shot, false);
1134  ROS_DEBUG_STREAM("Set DepthDoubleShot to " << cfg.depth_double_shot);
1135  }
1136 
1137  if (lvl & 2097152)
1138  {
1139  lvl &= ~2097152;
1140  ROS_DEBUG_STREAM("Set DepthStaticScene to " << cfg.depth_static_scene);
1141  if (!rcg::setBoolean(nodemap, "DepthStaticScene", cfg.depth_static_scene, false))
1142  {
1143  // support for rc_visard < 1.5
1144 
1145  std::string quality = cfg.depth_quality;
1146 
1147  if (cfg.depth_static_scene && quality == "High")
1148  {
1149  quality = "StaticHigh";
1150  }
1151 
1152  std::vector<std::string> list;
1153  rcg::getEnum(nodemap, "DepthQuality", list, true);
1154 
1155  std::string val;
1156  for (size_t i = 0; i < list.size() && val.size() == 0; i++)
1157  {
1158  if (list[i].compare(0, 1, quality, 0, 1) == 0)
1159  {
1160  val = list[i];
1161  }
1162  }
1163 
1164  if (val.size() > 0)
1165  {
1166  rcg::setEnum(nodemap, "DepthQuality", val.c_str(), true);
1167  ROS_DEBUG_STREAM("Set DepthQuality to " << val);
1168  }
1169  }
1170  }
1171 
1172  if (lvl & 64)
1173  {
1174  lvl &= ~64;
1175  rcg::setInteger(nodemap, "DepthSeg", cfg.depth_seg, true);
1176  ROS_DEBUG_STREAM("Set DepthSeg to " << cfg.depth_seg);
1177  }
1178 
1179  if (lvl & 4194304)
1180  {
1181  lvl &= ~4194304;
1182  rcg::setBoolean(nodemap, "DepthSmooth", cfg.depth_smooth, false);
1183  ROS_DEBUG_STREAM("Set DepthSmooth to " << cfg.depth_smooth);
1184  }
1185 
1186  if (lvl & 256)
1187  {
1188  lvl &= ~256;
1189  rcg::setInteger(nodemap, "DepthFill", cfg.depth_fill, true);
1190  ROS_DEBUG_STREAM("Set DepthFill to " << cfg.depth_fill);
1191  }
1192 
1193  if (lvl & 512)
1194  {
1195  lvl &= ~512;
1196  rcg::setFloat(nodemap, "DepthMinConf", cfg.depth_minconf, true);
1197  ROS_DEBUG_STREAM("Set DepthMinConf to " << cfg.depth_minconf);
1198  }
1199 
1200  if (lvl & 1024)
1201  {
1202  lvl &= ~1024;
1203  rcg::setFloat(nodemap, "DepthMinDepth", cfg.depth_mindepth, true);
1204  ROS_DEBUG_STREAM("Set DepthMinDepth to " << cfg.depth_mindepth);
1205  }
1206 
1207  if (lvl & 2048)
1208  {
1209  lvl &= ~2048;
1210  rcg::setFloat(nodemap, "DepthMaxDepth", cfg.depth_maxdepth, true);
1211  ROS_DEBUG_STREAM("Set DepthMaxDepth to " << cfg.depth_maxdepth);
1212  }
1213 
1214  if (lvl & 4096)
1215  {
1216  lvl &= ~4096;
1217  rcg::setFloat(nodemap, "DepthMaxDepthErr", cfg.depth_maxdeptherr, true);
1218  ROS_DEBUG_STREAM("Set DepthMaxDepthErr to " << cfg.depth_maxdeptherr);
1219  }
1220 
1221  if (lvl & 268435456)
1222  {
1223  lvl &= ~268435456;
1224  rcg::setFloat(nodemap, "DepthExposureAdaptTimeout", cfg.depth_exposure_adapt_timeout, false);
1225  ROS_DEBUG_STREAM("Set DepthExposureAdaptTimeout to " << cfg.depth_exposure_adapt_timeout);
1226  }
1227 
1228  if (lvl & 131072)
1229  {
1230  lvl &= ~131072;
1231  rcg::setBoolean(nodemap, "PtpEnable", cfg.ptp_enabled, true);
1232  ROS_DEBUG_STREAM("Set PtpEnable to " << cfg.ptp_enabled);
1233  }
1234 
1235  // lvl 262144 (out1_mode) is immediately set in dynamic reconfigure callback
1236 
1237  // lvl 524288 (out2_mode) is immediately set in dynamic reconfigure callback
1238  }
1239  catch (const std::exception& ex)
1240  {
1241  ROS_ERROR_STREAM("rc_visard_driver: " << ex.what());
1242  }
1243  }
1244 }
1245 
1246 /*
1247  Disable all available components.
1248 
1249  @param nodemap Feature nodemap.
1250 */
1251 
1252 void disableAll(const std::shared_ptr<GenApi::CNodeMapRef>& nodemap)
1253 {
1254  std::vector<std::string> component;
1255 
1256  rcg::getEnum(nodemap, "ComponentSelector", component, true);
1257 
1258  for (size_t i = 0; i < component.size(); i++)
1259  {
1260  rcg::setEnum(nodemap, "ComponentSelector", component[i].c_str(), true);
1261  rcg::setBoolean(nodemap, "ComponentEnable", false, true);
1262  }
1263 
1264  rcg::setEnum(nodemap, "ComponentSelector", "Intensity");
1265  rcg::setEnum(nodemap, "PixelFormat", "Mono8");
1266 
1267  // if multipart is available, still send single components per buffer
1268  rcg::setEnum(nodemap, "AcquisitionMultiPartMode", "SingleComponent");
1269 }
1270 
1271 /*
1272  Conditionally enables a component.
1273 
1274  @param nodemap Feature nodemap.
1275  @param en_curr Current selection status, which will be changed.
1276  @param en_new New selection status.
1277  @return 1 if status changed, 0 otherwise.
1278 */
1279 
1280 int enable(const std::shared_ptr<GenApi::CNodeMapRef>& nodemap, const char* component, bool& en_curr, bool en_new)
1281 {
1282  if (en_new != en_curr)
1283  {
1284  if (en_new)
1285  ROS_INFO_STREAM("rc_visard_driver: Enabled image stream: " << component);
1286  else
1287  ROS_INFO_STREAM("rc_visard_driver: Disabled image stream: " << component);
1288 
1289  rcg::setEnum(nodemap, "ComponentSelector", component, true);
1290  rcg::setBoolean(nodemap, "ComponentEnable", en_new);
1291  en_curr = en_new;
1292 
1293  return 1;
1294  }
1295 
1296  return 0;
1297 }
1298 
1299 namespace
1300 {
1301 template <class T>
1302 inline rc_common_msgs::KeyValue getKeyValue(const char* key, T value)
1303 {
1304  rc_common_msgs::KeyValue ret;
1305 
1306  ret.key = key;
1307  ret.value = std::to_string(value);
1308 
1309  return ret;
1310 }
1311 
1312 inline rc_common_msgs::KeyValue getKeyValueString(const char* key, const std::string& value)
1313 {
1314  rc_common_msgs::KeyValue ret;
1315 
1316  ret.key = key;
1317  ret.value = value;
1318 
1319  return ret;
1320 }
1321 
1322 } // namespace
1323 
1324 rc_common_msgs::CameraParam extractChunkData(const std::shared_ptr<GenApi::CNodeMapRef>& rcgnodemap)
1325 {
1326  rc_common_msgs::CameraParam cam_param;
1327 
1328  // get list of all available IO lines and iterate over them
1329  // to get input/output masks and LineSource values for outputs
1330 
1331  std::vector<std::string> lines;
1332  rcg::getEnum(rcgnodemap, "LineSelector", lines, true);
1333  uint32_t input_mask = 0;
1334  uint32_t output_mask = 0;
1335  for (size_t i = 0; i < lines.size(); i++)
1336  {
1337  rcg::setEnum(rcgnodemap, "LineSelector", lines[i].c_str(), true);
1338  std::string io = rcg::getEnum(rcgnodemap, "LineMode");
1339 
1340  if (io == "Input")
1341  {
1342  input_mask |= 1 << i;
1343  }
1344 
1345  if (io == "Output")
1346  {
1347  output_mask |= 1 << i;
1348 
1349  // for output also get LineSource for this image
1350  rcg::setEnum(rcgnodemap, "ChunkLineSelector", lines[i].c_str(), true);
1351  rc_common_msgs::KeyValue line_source;
1352  line_source.key = lines[i];
1353  line_source.value = rcg::getEnum(rcgnodemap, "ChunkLineSource", true);
1354  cam_param.line_source.push_back(line_source);
1355  }
1356  }
1357  cam_param.extra_data.push_back(getKeyValue("input_mask", input_mask));
1358  cam_param.extra_data.push_back(getKeyValue("output_mask", output_mask));
1359 
1360  // get LineStatusAll
1361  cam_param.line_status_all = rcg::getInteger(rcgnodemap, "ChunkLineStatusAll", 0, 0, false);
1362 
1363  // get camera's exposure time and gain value
1364  cam_param.gain = rcg::getFloat(rcgnodemap, "ChunkGain", 0, 0, false);
1365  cam_param.exposure_time = rcg::getFloat(rcgnodemap, "ChunkExposureTime", 0, 0, false) / 1000000l;
1366 
1367  // add extra data
1368  try
1369  {
1370  float noise = rcg::getFloat(rcgnodemap, "ChunkRcNoise", 0, 0, true);
1371  cam_param.extra_data.push_back(getKeyValue("noise", noise));
1372  }
1373  catch (std::invalid_argument&)
1374  {
1375  // calculate camera's noise level
1376  static float NOISE_BASE = 2.0;
1377  float noise = static_cast<float>(NOISE_BASE * std::exp(cam_param.gain * std::log(10)/20));
1378  cam_param.extra_data.push_back(getKeyValue("noise", noise));
1379  }
1380 
1381  try
1382  {
1383  bool test = rcg::getBoolean(rcgnodemap, "ChunkRcTest", true);
1384  cam_param.extra_data.push_back(getKeyValue("test", test));
1385  }
1386  catch (std::invalid_argument&)
1387  {
1388  // feature not available on device
1389  }
1390 
1391  try
1392  {
1393  float out1_reduction;
1394  try
1395  {
1396  out1_reduction = rcg::getFloat(rcgnodemap, "ChunkRcOut1Reduction", 0, 0, true);
1397  }
1398  catch (const std::exception&)
1399  {
1400  // try to fallback to older name in versions < 20.10.1
1401  out1_reduction = rcg::getFloat(rcgnodemap, "ChunkRcAdaptiveOut1Reduction", 0, 0, true);
1402  }
1403  cam_param.extra_data.push_back(getKeyValue("out1_reduction", out1_reduction));
1404  }
1405  catch (std::invalid_argument&)
1406  {
1407  // feature not available on device
1408  }
1409 
1410  try
1411  {
1412  float brightness = rcg::getFloat(rcgnodemap, "ChunkRcBrightness", 0, 0, true);
1413  cam_param.extra_data.push_back(getKeyValue("brightness", brightness));
1414  }
1415  catch (std::invalid_argument&)
1416  {
1417  // feature not available on device
1418  }
1419 
1420  try
1421  {
1422  bool adapting = rcg::getBoolean(rcgnodemap, "ChunkRcAutoExposureAdapting", true);
1423  cam_param.extra_data.push_back(getKeyValue("auto_exposure_adapting", adapting));
1424  }
1425  catch (const std::exception&)
1426  {
1427  // feature not available on device
1428  }
1429 
1430  cam_param.extra_data.push_back(getKeyValueString("model_name", rcg::getString(rcgnodemap, "DeviceModelName")));
1431 
1432  return cam_param;
1433 }
1434 
1435 } //anonymous namespace
1436 
1437 void DeviceNodelet::grab(std::string device, rcg::Device::ACCESS access)
1438 {
1439  unsigned int maxNumConsecutiveFails = 5;
1440 
1441  stopImageThread = false;
1442 
1443  imageRequested = true;
1444  imageSuccess = false;
1445 
1446  // at most 5 consecutive failures are permitted
1447 
1448  unsigned int cntConsecutiveFails = 0;
1449  while (!stopImageThread && cntConsecutiveFails < maxNumConsecutiveFails)
1450  {
1451  imageSuccess = false;
1452  try
1453  {
1454  // mark all dynamic parameters as changed
1455 
1456  level=0xffffffff;
1457 
1458  // initially switch off all components
1459 
1460  disableAll(rcgnodemap);
1461 
1462  bool ccolor = false;
1463  bool cintensity = false;
1464  bool cintensitycombined = false;
1465  bool cdisparity = false;
1466  bool cconfidence = false;
1467  bool cerror = false;
1468 
1469  bool firstTime = true;
1470 
1471  // get focal length factor of the camera
1472 
1473  double f = rcg::getFloat(rcgnodemap, "FocalLengthFactor", 0, 0, false);
1474  if (!f) // backward compatibility: also check for old name 'FocalLength'
1475  {
1476  f = rcg::getFloat(rcgnodemap, "FocalLength", 0, 0, false);
1477  if (!f)
1478  {
1479  throw std::runtime_error("Focal length not found: Neither 'FocalLength' nor 'FocalLengthFactor'!");
1480  }
1481  }
1482 
1483  // get baseline of the camera (for backward capability check unit)
1484 
1485  double t = rcg::getFloat(rcgnodemap, "Baseline", 0, 0, true);
1486  GenApi::INode* node = rcgnodemap->_GetNode("Baseline");
1487  if (!node || !GenApi::IsReadable(node))
1488  {
1489  throw std::invalid_argument("Feature not found or not readable: Baseline");
1490  }
1491  GenApi::IFloat* val = dynamic_cast<GenApi::IFloat*>(node);
1492  if (!val)
1493  {
1494  throw std::invalid_argument("Feature not float: Baseline");
1495  }
1496  if (val->GetUnit() == "mm") // in previous versions rc_visard reported as mm
1497  {
1498  t /= 1000;
1499  }
1500 
1501  // get disparity scale
1502 
1503  double scale = rcg::getFloat(rcgnodemap, "Scan3dCoordinateScale", 0, 0, true);
1504 
1505  // check certain values
1506 
1507  rcg::checkFeature(rcgnodemap, "Scan3dOutputMode", "DisparityC");
1508  rcg::checkFeature(rcgnodemap, "Scan3dCoordinateOffset", "0");
1509  rcg::checkFeature(rcgnodemap, "Scan3dInvalidDataFlag", "1");
1510  rcg::checkFeature(rcgnodemap, "Scan3dInvalidDataValue", "0");
1511 
1512  // get current configuration and start dynamic reconfigure server
1513 
1515 
1516  float mindepth = config.depth_mindepth;
1517  float maxdepth = config.depth_maxdepth;
1518  bool is_depth_acquisition_continuous = (config.depth_acquisition_mode[0] == 'C');
1519 
1520  // prepare chunk adapter for getting chunk data
1521 
1522  std::shared_ptr<GenApi::CChunkAdapter> chunkadapter;
1523  chunkadapter = rcg::getChunkAdapter(rcgnodemap, rcgdev->getTLType());
1524 
1525  // initialize all publishers
1526 
1527  ros::NodeHandle nh(getNodeHandle(), "stereo");
1529 
1530  CameraInfoPublisher lcaminfo(nh, tfPrefix, f, t, true);
1531  CameraInfoPublisher rcaminfo(nh, tfPrefix, f, t, false);
1532 
1533  ImagePublisher limage(it, tfPrefix, true, false, true);
1534  ImagePublisher rimage(it, tfPrefix, false, false, true);
1535 
1536  DisparityPublisher disp(nh, tfPrefix, f, t, scale);
1537  DisparityColorPublisher cdisp(it, tfPrefix, f, t, scale);
1538  DepthPublisher depth(nh, tfPrefix, f, t, scale);
1539 
1540  ConfidencePublisher confidence(nh, tfPrefix);
1541  ErrorDisparityPublisher error_disp(nh, tfPrefix, scale);
1542  ErrorDepthPublisher error_depth(nh, tfPrefix, f, t, scale);
1543 
1544  Points2Publisher points2(nh, tfPrefix, f, t, scale);
1545 
1546  // add color image publishers if the camera supports color
1547 
1548  std::shared_ptr<ImagePublisher> limage_color;
1549  std::shared_ptr<ImagePublisher> rimage_color;
1550  if (dev_supports_color)
1551  {
1552  limage_color = std::make_shared<ImagePublisher>(it, tfPrefix, true, true, true);
1553  rimage_color = std::make_shared<ImagePublisher>(it, tfPrefix, false, true, true);
1554  }
1555 
1556  // add camera/image params publishers if the camera supports chunkdata
1557 
1558  std::shared_ptr<CameraParamPublisher> lcamparams = std::make_shared<CameraParamPublisher>(nh, tfPrefix, true);
1559  std::shared_ptr<CameraParamPublisher> rcamparams = std::make_shared<CameraParamPublisher>(nh, tfPrefix, false);
1560 
1561  // start streaming of first stream
1562 
1563  std::vector<std::shared_ptr<rcg::Stream> > stream = rcgdev->getStreams();
1564 
1565  gev_packet_size="";
1566 
1567  if (stream.size() > 0)
1568  {
1569  stream[0]->open();
1570  stream[0]->startStreaming();
1571 
1572  // enter grabbing loop
1573  ros::SteadyTime tlastimage = ros::SteadyTime::now();
1574  std::string out1_mode_on_sensor;
1575 
1576  while (!stopImageThread)
1577  {
1578  const rcg::Buffer* buffer = stream[0]->grab(40);
1579 
1580  if (buffer != 0 && !buffer->getIsIncomplete())
1581  {
1583  if (gev_packet_size.size() == 0)
1584  {
1585  gev_packet_size = rcg::getString(rcgnodemap, "GevSCPSPacketSize", true, true);
1586  ROS_INFO_STREAM("rc_visard_driver: Image streams ready (Packet size "
1587  << gev_packet_size << ")");
1588  }
1589 
1590  // get camera/image parameters (GenICam chunk data) if possible
1591  // (e.g. out1_mode, line_status_all, current gain and exposure, etc.)
1592 
1593  bool out1 = false;
1594  if (chunkadapter && buffer->getContainsChunkdata())
1595  {
1596  chunkadapter->AttachBuffer(reinterpret_cast<std::uint8_t*>(buffer->getGlobalBase()),
1597  buffer->getSizeFilled());
1598 
1599  // get current out1 mode
1600  rcg::setEnum(rcgnodemap, "ChunkLineSelector", "Out1", false);
1601  std::string v = rcg::getEnum(rcgnodemap, "ChunkLineSource", false);
1602 
1603  if (v.size() > 0)
1604  {
1605  out1_mode_on_sensor = v;
1606  }
1607  }
1608 
1609  // if in alternate mode, then make publishers aware of it before
1610  // publishing
1611 
1612  bool out1_alternate = (out1_mode_on_sensor == "ExposureAlternateActive");
1613  points2.setOut1Alternate(out1_alternate);
1614 
1615  rc_common_msgs::CameraParam cam_param;
1616  double camera_fps;
1617 
1618  {
1619  // protect against concurent changes of selector (i.e. LineSelector),
1620  // before reading the corresponding value
1621 
1622  boost::recursive_mutex::scoped_lock lock(mtx);
1623 
1624  cam_param = extractChunkData(rcgnodemap);
1625 
1626  camera_fps = config.camera_fps;
1627  }
1628 
1629  cam_param.is_color_camera = dev_supports_color;
1630  out1 = (cam_param.line_status_all & 0x1);
1631 
1632  uint32_t npart=buffer->getNumberOfParts();
1633  for (uint32_t part=0; part<npart; part++)
1634  {
1635  if (buffer->getImagePresent(part))
1636  {
1637  // reset counter of consecutive missing images and failures
1638  double dt = (ros::SteadyTime::now() - tlastimage).toSec();
1639  double warn_limit = 3.0/camera_fps;
1640  if (dt > warn_limit)
1641  {
1642  ROS_WARN("rc_visard_driver: time between image publish more than %.3fs: %.3fs.", warn_limit, dt);
1643  }
1644  tlastimage = ros::SteadyTime::now();
1645  cntConsecutiveFails = 0;
1646  imageSuccess = true;
1647 
1648  // the buffer is offered to all publishers
1649 
1650  ros::SteadyTime publish_start = ros::SteadyTime::now();
1651 
1652  disp.setDepthRange(mindepth, maxdepth);
1653  cdisp.setDepthRange(mindepth, maxdepth);
1654 
1655  uint64_t pixelformat = buffer->getPixelFormat(part);
1656 
1657  lcaminfo.publish(buffer, part, pixelformat);
1658  rcaminfo.publish(buffer, part, pixelformat);
1659 
1660  if (lcamparams && rcamparams)
1661  {
1662  lcamparams->publish(buffer, cam_param, pixelformat);
1663  rcamparams->publish(buffer, cam_param, pixelformat);
1664  }
1665 
1666  limage.publish(buffer, part, pixelformat, out1);
1667  rimage.publish(buffer, part, pixelformat, out1);
1668 
1669  if (limage_color && rimage_color)
1670  {
1671  limage_color->publish(buffer, part, pixelformat, out1);
1672  rimage_color->publish(buffer, part, pixelformat, out1);
1673  }
1674 
1675  disp.publish(buffer, part, pixelformat);
1676  cdisp.publish(buffer, part, pixelformat);
1677  depth.publish(buffer, part, pixelformat);
1678 
1679  confidence.publish(buffer, part, pixelformat);
1680  error_disp.publish(buffer, part, pixelformat);
1681  error_depth.publish(buffer, part, pixelformat);
1682 
1683  points2.publish(buffer, part, pixelformat, out1);
1684 
1685  dt = (ros::SteadyTime::now() - publish_start).toSec();
1686  if (dt > 0.1)
1687  {
1688  ROS_WARN_STREAM("rc_visard_driver: publishing took " << dt << "s!");
1689  }
1690 
1691  // use out1_mode for updating dynamic parameters (below) only
1692  // from buffers with intensity images
1693 
1694  if (pixelformat != Mono8 && pixelformat != YCbCr411_8)
1695  {
1696  out1_mode_on_sensor = "";
1697  }
1698  }
1699  }
1700 
1701  // detach buffer from nodemap
1702 
1703  if (chunkadapter) chunkadapter->DetachBuffer();
1704  }
1705  else if (buffer != 0 && buffer->getIsIncomplete())
1706  {
1707  tlastimage = ros::SteadyTime::now();
1709  ROS_WARN("rc_visard_driver: Received incomplete image buffer");
1710  }
1711  else if (buffer == 0)
1712  {
1713  // throw an expection if data from enabled components is expected,
1714  // but not comming for more than 3 seconds
1715 
1716  if (cintensity || cintensitycombined ||
1717  (is_depth_acquisition_continuous && (cdisparity || cconfidence || cerror)))
1718  {
1719  double t = (ros::SteadyTime::now() - tlastimage).toSec();
1720 
1721  if (t > 3) // report error
1722  {
1724  std::ostringstream out;
1725  out << "No images received for " << t << " seconds!";
1726  throw std::underflow_error(out.str());
1727  }
1728  }
1729  else
1730  {
1731  // if nothing is expected then store current time as last time
1732  // to avoid possible timeout after resubscription
1733 
1734  tlastimage = ros::SteadyTime::now();
1735  }
1736 
1737  // get out1 mode from sensor (this is also used to check if the
1738  // connection is still valid)
1739 
1740  rcg::setEnum(rcgnodemap, "LineSelector", "Out1", true);
1741  out1_mode_on_sensor = rcg::getString(rcgnodemap, "LineSource", true, true);
1742  }
1743 
1744  // trigger depth
1745 
1747  {
1749  rcg::callCommand(rcgnodemap, "DepthAcquisitionTrigger", true);
1750  ROS_INFO("rc_visard_driver: Depth image acquisition triggered");
1751  }
1752 
1753  // determine what should be streamed, according to subscriptions to
1754  // topics
1755 
1756  // switch color on or off
1757 
1758  if (limage_color && rimage_color && (limage_color->used() || rimage_color->used() || points2.used()))
1759  {
1760  if (!ccolor)
1761  {
1762  rcg::setEnum(rcgnodemap, "ComponentSelector", "Intensity", true);
1763  rcg::setEnum(rcgnodemap, "PixelFormat", color_format.c_str(), false);
1764  rcg::setEnum(rcgnodemap, "ComponentSelector", "IntensityCombined", true);
1765  rcg::setEnum(rcgnodemap, "PixelFormat", color_format.c_str(), false);
1766 
1767  ccolor = true;
1768  }
1769  }
1770  else
1771  {
1772  if (ccolor)
1773  {
1774  rcg::setEnum(rcgnodemap, "ComponentSelector", "Intensity", true);
1775  rcg::setEnum(rcgnodemap, "PixelFormat", "Mono8", true);
1776  ccolor = false;
1777  }
1778  }
1779 
1780  // enable or disable components
1781 
1782  int changed = enable(rcgnodemap, "IntensityCombined", cintensitycombined,
1783  rimage.used() || (rimage_color && rimage_color->used()));
1784 
1785  changed += enable(rcgnodemap, "Intensity", cintensity,
1786  !cintensitycombined && (lcaminfo.used() || rcaminfo.used() ||
1787  (lcamparams && lcamparams->used()) ||
1788  (rcamparams && rcamparams->used()) ||
1789  limage.used() ||
1790  (limage_color && limage_color->used()) || points2.used()));
1791 
1792  changed += enable(rcgnodemap, "Disparity", cdisparity,
1793  disp.used() || cdisp.used() || depth.used() || error_depth.used() || points2.used());
1794 
1795  changed += enable(rcgnodemap, "Confidence", cconfidence, confidence.used());
1796 
1797  changed += enable(rcgnodemap, "Error", cerror, error_disp.used() || error_depth.used());
1798 
1799  // report activation of all components, everytime when a component is
1800  // enabled or disabled
1801 
1802  if (changed > 0 || firstTime)
1803  {
1804  if (cintensity || cintensitycombined || cdisparity || cconfidence || cerror)
1805  imageRequested = true;
1806  else
1807  imageRequested = false;
1808  firstTime = false;
1809  }
1810 
1811  // check if dynamic configuration has changed
1812 
1813  if (level != 0)
1814  {
1815  // set all changed values via genicam
1816 
1817  mtx.lock();
1818  rc_visard_driver::rc_visard_driverConfig cfg = config;
1819  uint32_t lvl = level;
1820  level = 0;
1821  mtx.unlock();
1822 
1823  setConfiguration(rcgnodemap, cfg, lvl, iocontrol_avail);
1824 
1825  mindepth = cfg.depth_mindepth;
1826  maxdepth = cfg.depth_maxdepth;
1827 
1828  // if depth acquisition changed to continuous mode, reset last
1829  // grabbing time to avoid triggering timout if only disparity,
1830  // confidence and/or error components are enabled
1831 
1832  is_depth_acquisition_continuous = (cfg.depth_acquisition_mode[0] == 'C');
1833 
1834  if (lvl & 1048576)
1835  {
1836  if (is_depth_acquisition_continuous)
1837  {
1838  tlastimage = ros::SteadyTime::now();
1839  }
1840  }
1841  }
1842 
1843  // update out1 mode, if it is different to current settings on sensor
1844  // (which is the only GEV parameter which could have changed outside this code,
1845  // i.e. on the rc_visard by the stereomatching module)
1846 
1847  mtx.lock();
1848  if (out1_mode_on_sensor.size() == 0)
1849  {
1850  // use current settings if the value on the sensor cannot be determined
1851  out1_mode_on_sensor = config.out1_mode;
1852  }
1853 
1854  if (out1_mode_on_sensor != config.out1_mode)
1855  {
1856  config.out1_mode = out1_mode_on_sensor;
1857  reconfig->updateConfig(config);
1858  }
1859  mtx.unlock();
1860  }
1861 
1862  stream[0]->stopStreaming();
1863  stream[0]->close();
1864  }
1865  else
1866  {
1867  ROS_ERROR("rc_visard_driver: No stream");
1868  cntConsecutiveFails++;
1869  }
1870  }
1871  catch (const std::exception& ex)
1872  {
1873  ROS_ERROR_STREAM("rc_visard_driver: " << ex.what());
1874  cntConsecutiveFails++;
1875  }
1876  }
1877 
1878  // report failures, if any
1879 
1880  if (cntConsecutiveFails > 0)
1881  {
1882  ROS_ERROR_STREAM("rc_visard_driver: Number of consecutive failures: " << cntConsecutiveFails);
1883  }
1884  if (cntConsecutiveFails >= maxNumConsecutiveFails)
1885  {
1886  ROS_ERROR_STREAM("rc_visard_driver: Image grabbing failed.");
1887  recoveryRequested = true;
1889  }
1890 }
1891 
1892 bool DeviceNodelet::depthAcquisitionTrigger(rc_common_msgs::Trigger::Request& req,
1893  rc_common_msgs::Trigger::Response& resp)
1894 {
1896 
1897  resp.return_code.value = ReturnCodeConstants::SUCCESS;
1898  resp.return_code.message = "";
1899 
1900  return true;
1901 }
1902 
1903 
1905 {
1906  stat.add("connection_loss_total", totalConnectionLosses);
1907  stat.add("complete_buffers_total", totalCompleteBuffers);
1908  stat.add("incomplete_buffers_total", totalIncompleteBuffers);
1909  stat.add("image_receive_timeouts_total", totalImageReceiveTimeouts);
1910  stat.add("current_reconnect_trial", cntConsecutiveRecoveryFails);
1911 
1912  // general connection status is supervised by the recoveryRequested variable
1913 
1914  if (recoveryRequested) {
1915  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Disconnected");
1916  return;
1917  }
1918 
1919  // at least we are connected to gev server
1920 
1921  stat.add("ip_address", dev_ipaddr);
1922  stat.add("gev_packet_size", gev_packet_size);
1923 
1924  if (imageRequested) {
1925  if (imageSuccess) {
1926  // someone subscribed to images, and we actually receive data via GigE vision
1927  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Streaming");
1928  } else {
1929  // someone subscribed to images, but we do not receive any data via GigE vision (yet)
1930  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No data");
1931  }
1932  } else {
1933  // no one requested images -> node is ok but stale
1934  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Idle");
1935  }
1936 
1937 }
1938 
1940  if (dev_serialno.empty()) {
1941  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Unknown");
1942  } else {
1943  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Info");
1944  stat.add("serial", dev_serialno);
1945  stat.add("mac", dev_macaddr);
1946  stat.add("user_id", gev_userid);
1947  stat.add("image_version", dev_version);
1948  }
1949 }
1950 
1951 } // namespace rc
1952 
msg
bool dynamicsStart(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Start Stereo INS.
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
ThreadedStream::Manager::Ptr dynamicsStreams
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
std::shared_ptr< Device > getDevice(const char *devid)
bool used() override
Returns true if there are subscribers to the topic.
#define NODELET_WARN(...)
bool used() override
Returns true if there are subscribers to the topic.
tf::Transform toRosTfTransform(const roboception::msgs::Pose &pose)
Mono8
f
Specific implementation for roboception::msgs::Frame messages that publishes received messages not on...
unsigned int totalIncompleteBuffers
bool dynamicsStopSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Stop SLAM (keep Stereo INS running)
void summary(unsigned char lvl, const std::string s)
bool getContainsChunkdata() const
std::istream & getline(std::istream &is, GENICAM_NAMESPACE::gcstring &str)
void reconfigure(rc_visard_driver::rc_visard_driverConfig &config, uint32_t level)
bool used() override
Returns true if there are subscribers to the topic.
int64_t round(double x)
std::shared_ptr< GenApi::CChunkAdapter > getChunkAdapter(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const std::string &tltype)
bool used() override
Returns true if there are subscribers to the topic.
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
void produce_connection_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
ros::NodeHandle & getNodeHandle() const
void setHardwareID(const std::string &hwid)
static std::vector< std::shared_ptr< System > > getSystems()
bool used() override
Returns true if there are subscribers to the topic.
std::shared_ptr< ThreadedStream > Ptr
size_t getSizeFilled() const
diagnostic_updater::Updater updater
diagnostics publishing
void add(const std::string &name, TaskFunction f)
bool used() override
Returns true if there are subscribers to the topic.
bool getSlamTrajectory(rc_visard_driver::GetTrajectory::Request &req, rc_visard_driver::GetTrajectory::Response &resp)
Get the Slam trajectory.
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::ServiceServer slamLoadMapService
bool dynamicsStartSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Start Stereo INS+SLAM.
void grab(std::string device, rcg::Device::ACCESS access)
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
std::string dev_version
std::string str()
void produce_device_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
#define ROS_WARN(...)
Implementation of a ThreadedStream that receives rc_visard&#39;s dynamics protobuf messages and re-publis...
bool setFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double value, bool exception=false)
YCbCr411_8
ros::ServiceServer depthAcquisitionTriggerService
wrapper for REST-API calls relating to rc_visard&#39;s dynamics interface
void * getGlobalBase() const
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
ros::ServiceServer dynamicsStartSlamService
bool dynamicsRestart(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Restart Stereo INS.
bool removeSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Remove the onboard SLAM map.
ros::ServiceServer getSlamTrajectoryService
bool dev_supports_depth_exposure_adapt_timeout
static void clearSystems()
bool perform_depth_acquisition_trigger
bool tfEnabled
should poses published also via tf?
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
bool dev_supports_depth_acquisition_trigger
virtual void onInit()
void initConfiguration(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, rc_visard_driver::rc_visard_driverConfig &cfg, rcg::Device::ACCESS access)
tf2_ros::StaticTransformBroadcaster tfStaticBroadcaster
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::atomic_bool imageSuccess
bool getImagePresent(std::uint32_t part) const
bool used() override
Returns true if there are subscribers to the topic.
std::thread imageThread
ROSCPP_DECL const std::string & getNamespace()
unsigned int totalCompleteBuffers
static SteadyTime now()
ros::ServiceServer dynamicsStopSlamService
void checkFeature(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool igncache=false)
unsigned int totalImageReceiveTimeouts
#define ROS_FATAL_STREAM(args)
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
std::string color_format
ros::ServiceServer dynamicsRestartSlamService
#define ROS_INFO(...)
static ThreadedStream::Ptr CreateDynamicsStreamOfType(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled, bool staticImu2CamTf)
std::atomic_uint_least32_t level
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
rc_visard_driver::rc_visard_driverConfig config
void keepAliveAndRecoverFromFails()
bool used() override
Returns true if there are subscribers to the topic.
ros::ServiceServer slamSaveMapService
bool IsReadable(const CPointer< T, B > &ptr)
ros::ServiceServer dynamicsStopService
void setOut1Alternate(bool alternate)
std::atomic_bool imageRequested
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string gev_packet_size
#define ROS_WARN_STREAM(args)
ros::Publisher trajPublisher
#define ROS_DEBUG_STREAM(args)
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
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< rcg::Device > rcgdev
bool atLeastOnceSuccessfullyStarted
ros::ServiceServer dynamicsStartService
std::string strip_leading_slash(const std::string &frame_name)
bool dynamicsResetSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Reset SLAM (keep Stereo INS running)
std::atomic_bool stopImageThread
ros::ServiceServer dynamicsRestartService
bool dynamicsStop(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Stop Stereo INS(+SLAM if running)
dynamic_reconfigure::Server< rc_visard_driver::rc_visard_driverConfig > * reconfig
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *vmax=0, bool exception=false, bool igncache=false)
bool dynamicsRestartSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Restart Stereo INS+SLAM.
bool depthAcquisitionTrigger(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Trigger stereo matching in mode &#39;SingleFrame&#39;.
#define ROS_INFO_STREAM(args)
std::atomic_bool stopRecoverThread
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
rc::dynamics::RemoteInterface::Ptr dynamicsInterface
std::string dev_macaddr
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
bool callCommand(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
bool getIsIncomplete() const
std::string dev_serialno
std::string gev_userid
GENICAM_INTERFACE GENAPI_DECL_ABSTRACT IFloat
Specific implementation for roboception::msgs::Dynamics messages.
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
bool setInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t value, bool exception=false)
std::thread recoverThread
GENICAM_INTERFACE INode
void setDepthRange(double _mindepth, double _maxdepth)
Set the depth range of the disparity images.
void add(const std::string &key, const T &val)
#define ROS_ERROR_STREAM(args)
RW
bool saveSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Save the onboard SLAM map.
unsigned int totalConnectionLosses
void sendTransform(const geometry_msgs::TransformStamped &transform)
std::shared_ptr< GenApi::CNodeMapRef > rcgnodemap
ros::Time toRosTime(const roboception::msgs::Time &time)
ros::ServiceServer dynamicsResetSlamService
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
boost::recursive_mutex mtx
#define ROS_ERROR(...)
bool used() override
Returns true if there are subscribers to the topic.
std::uint32_t getNumberOfParts() const
std::string getString(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
std::string dev_ipaddr
virtual ~DeviceNodelet()
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
std::string tfPrefix
all frame names must be prefixed when using more than one rc_visard
void setDepthRange(double _mindepth, double _maxdepth)
Set the depth range of the disparity images.
bool loadSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Load the onboard SLAM map.
ros::ServiceServer slamRemoveMapService


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sun May 15 2022 03:06:09