51 #include <rc_genicam_api/config.h> 63 #include <geometry_msgs/PoseWithCovarianceStamped.h> 65 #include <rc_common_msgs/ReturnCodeConstants.h> 66 #include <rc_common_msgs/CameraParam.h> 71 bool isRcVisardDevice(
const std::string& vendor,
const std::string& model)
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;
79 std::vector<std::string> discoverRcVisardDevices()
81 std::vector<std::string> device_ids;
85 for (
auto interf : system->getInterfaces())
88 for (
auto dev : interf->getDevices())
90 if (isRcVisardDevice(dev->getVendor(), dev->getModel()))
92 device_ids.push_back(dev->getID());
102 void split(std::vector<std::string>& list,
const std::string& s,
char delim,
bool skip_empty =
true)
104 std::stringstream in(s);
107 while (
getline(in, elem, delim))
109 if (!skip_empty || elem.size() > 0)
111 list.push_back(elem);
119 namespace rcd = dynamics;
120 using rc_common_msgs::ReturnCodeConstants;
124 const std::string& frame_id_prefix,
bool tfEnabled,
125 bool staticImu2CamTf)
127 if (stream ==
"pose")
131 if (stream ==
"pose_ins" || stream ==
"pose_rt" || stream ==
"pose_rt_ins" || stream ==
"imu")
135 if (stream ==
"dynamics" || stream ==
"dynamics_ins")
140 throw std::runtime_error(std::string(
"Not yet implemented! Stream type: ") + stream);
172 std::cout <<
"rc_visard_driver: Shutting down" << std::endl;
209 std::string device =
"";
210 std::string access =
"control";
216 tfPrefix = (ns !=
"") ? ns +
"_" :
"";
218 pnh.
param(
"device", device, device);
219 pnh.
param(
"gev_access", access, access);
228 if (access ==
"exclusive")
232 else if (access ==
"control")
236 else if (access ==
"off")
242 ROS_FATAL_STREAM(
"rc_visard_driver: Access must be 'control', 'exclusive' or 'off': " << access);
285 ROS_INFO(
"rc_visard_driver: Device successfully recovered from previous fail(s)!");
312 bool successfullyOpened =
false;
322 ROS_ERROR_STREAM(
"rc_visard_driver: Failed or lost connection. Trying to recover" 323 " rc_visard_driver from failed state (" 337 if (device.size() == 0)
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)
344 throw std::runtime_error(
"Auto-connection with rc_visard device failed because none or multiple devices were found!");
355 throw std::invalid_argument(
"Unknown or non-unique device '" + device +
"'");
366 std::vector<std::string> list;
369 if (list.size() < 3 || std::stoi(list[0]) < 20 || (std::stoi(list[0]) == 20 && std::stoi(list[1]) < 4))
371 throw std::invalid_argument(
"Device version must be 20.04 or higher: " +
dev_version);
378 ROS_INFO_STREAM(
"rc_visard_driver: rc_visard device not yet ready (GEV). Trying again...");
398 ROS_INFO_STREAM(
"rc_visard_driver: rc_visard device not yet ready (REST). Trying again...");
401 }
catch (std::exception& e)
403 ROS_ERROR_STREAM(
"rc_visard_driver: checking system ready failed: " << e.what());
412 rc_common_msgs::Trigger::Request dummyreq;
413 rc_common_msgs::Trigger::Response dummyresp;
415 bool autostart_failed =
false;
418 autostart_failed |= dummyresp.return_code.value < ReturnCodeConstants::SUCCESS;
420 if (autostart_failed)
422 ROS_WARN_STREAM(
"rc_visard_driver: Could not auto-start dynamics module! " << dummyresp.return_code.message);
430 bool staticImu2CamTf =
false;
435 pbFrame.set_name(
tfPrefix + pbFrame.name());
436 pbFrame.set_parent(
tfPrefix + pbFrame.parent());
442 pbFrame.name(), pbFrame.parent());
444 geometry_msgs::TransformStamped
msg;
447 staticImu2CamTf =
true;
449 }
catch (rcd::RemoteInterface::NotAvailable& e)
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.");
460 for (
const auto& streamName : availStreams)
468 catch (
const std::exception& e)
470 ROS_WARN_STREAM(
"rc_visard_driver: Unable to create dynamics stream of type " << streamName <<
": " 475 successfullyOpened =
true;
478 catch (std::exception& ex)
506 rc_common_msgs::Trigger::Request dummyreq;
507 rc_common_msgs::Trigger::Response dummyresp;
508 ROS_INFO(
"rc_visard_driver: Autostop dynamics ...");
511 ROS_WARN(
"rc_visard_driver: Could not auto-stop dynamics module!");
514 std::cout <<
"rc_visard_driver: stopped." << std::endl;
524 cfg.camera_fps =
rcg::getFloat(nodemap,
"AcquisitionFrameRate", 0, 0,
true);
526 std::string v =
rcg::getEnum(nodemap,
"ExposureAuto",
true);
527 cfg.camera_exp_auto = (v !=
"Off");
529 if (cfg.camera_exp_auto)
531 if (v ==
"Continuous")
533 cfg.camera_exp_auto_mode =
"Normal";
537 cfg.camera_exp_auto_mode = v;
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;
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);
564 cfg.camera_gain_value =
rcg::getFloat(nodemap,
"Gain", 0, 0,
true);
569 ROS_WARN(
"rc_visard_driver: Device does not support setting gain. gain_value is without function.");
572 cfg.camera_gain_value = 0;
577 std::vector<std::string> formats;
580 for (
auto&& format : formats)
582 if (format ==
"YCbCr411_8")
588 if (format ==
"RGB8")
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);
611 ROS_WARN(
"rc_visard_driver: Not a color camera. wb_auto, wb_ratio_red and wb_ratio_blue are without function.");
614 cfg.camera_wb_auto =
true;
615 cfg.camera_wb_ratio_red = 1;
616 cfg.camera_wb_ratio_blue = 1;
621 v =
rcg::getEnum(nodemap,
"DepthAcquisitionMode",
false);
625 cfg.depth_acquisition_mode = v;
629 ROS_WARN(
"rc_visard_driver: Device does not support triggering depth images. depth_acquisition_mode is without function.");
632 cfg.depth_acquisition_mode =
"Continuous";
636 cfg.depth_quality = v;
638 cfg.depth_static_scene =
rcg::getBoolean(nodemap,
"DepthStaticScene",
false);
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);
657 ROS_INFO(
"rc_visard_driver: License for stereo_plus not available, disabling depth_quality=Full and depth_smooth.");
660 catch (
const std::exception&)
662 ROS_WARN(
"rc_visard_driver: rc_visard has an older firmware, disabling depth_quality=Full and depth_smooth.");
668 cfg.depth_double_shot =
rcg::getBoolean(nodemap,
"DepthDoubleShot",
true);
671 catch (
const std::exception&)
674 ROS_WARN(
"rc_visard_driver: rc_visard has an older firmware, depth_double_shot is not available.");
695 ROS_INFO(
"rc_visard_driver: License for iocontrol module not available, disabling out1_mode and out2_mode.");
698 catch (
const std::exception&)
700 ROS_WARN(
"rc_visard_driver: rc_visard has an older firmware, IO control functions are not available.");
702 cfg.out1_mode =
"ExposureActive";
703 cfg.out2_mode =
"Low";
711 rcg::setEnum(nodemap,
"AcquisitionAlternateFilter",
"Off",
false);
712 rcg::setEnum(nodemap,
"AcquisitionMultiPartMode",
"SingleComponent",
true);
717 cfg.depth_exposure_adapt_timeout =
rcg::getFloat(nodemap,
"DepthExposureAdaptTimeout", 0, 0,
true);
720 catch (
const std::exception&)
723 NODELET_WARN(
"rc_visard_driver: rc_visard has an older firmware, depth_exposure_adapt_timeout is not available.");
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);
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);
791 reconfig =
new dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>(
mtx, pnh);
794 dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>::CallbackType cb;
801 boost::recursive_mutex::scoped_lock lock(
mtx);
807 c.camera_gain_value = 0;
813 c.depth_double_shot =
false;
817 c.camera_gain_value =
round(c.camera_gain_value / 6) * 6;
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);
829 c.depth_acquisition_mode =
"Continuous";
833 if (c.depth_quality[0] ==
'L')
835 c.depth_quality =
"Low";
837 else if (c.depth_quality[0] ==
'M')
839 c.depth_quality =
"Medium";
843 c.depth_quality =
"Full";
847 c.depth_quality =
"High";
852 c.depth_smooth=
false;
858 if (c.out1_mode !=
"Low" && c.out1_mode !=
"High" && c.out1_mode !=
"ExposureActive" &&
859 c.out1_mode !=
"ExposureAlternateActive")
864 if (c.out2_mode !=
"Low" && c.out2_mode !=
"High" && c.out2_mode !=
"ExposureActive" &&
865 c.out2_mode !=
"ExposureAlternateActive")
878 c.depth_exposure_adapt_timeout = 0.0;
918 if (c.camera_exp_auto)
920 std::string mode = c.camera_exp_auto_mode;
921 if (mode ==
"Normal") mode =
"Continuous";
925 c.camera_exp_auto_mode =
"Normal";
935 if (!c.camera_exp_auto)
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)
961 uint32_t prev_lvl = 0;
963 while (lvl != 0 && prev_lvl != lvl)
976 rcg::setFloat(nodemap,
"AcquisitionFrameRate", cfg.camera_fps,
true);
985 rcg::setFloat(nodemap,
"ExposureTime", 1000000 * cfg.camera_exp_value,
true);
999 rcg::setFloat(nodemap,
"ExposureTimeAutoMax", 1000000 * cfg.camera_exp_max,
true);
1006 rcg::setInteger(nodemap,
"ExposureRegionWidth", cfg.camera_exp_width,
false);
1013 rcg::setInteger(nodemap,
"ExposureRegionHeight", cfg.camera_exp_height,
false);
1020 rcg::setInteger(nodemap,
"ExposureRegionOffsetX", cfg.camera_exp_offset_x,
false);
1021 ROS_DEBUG_STREAM(
"Set ExposureRegionOffsetX to " << cfg.camera_exp_offset_x);
1027 rcg::setInteger(nodemap,
"ExposureRegionOffsetY", cfg.camera_exp_offset_y,
false);
1028 ROS_DEBUG_STREAM(
"Set ExposureRegionOffsetY to " << cfg.camera_exp_offset_y);
1035 if (cfg.camera_wb_auto)
1037 rcg::setEnum(nodemap,
"BalanceWhiteAuto",
"Continuous",
false);
1042 rcg::setEnum(nodemap,
"BalanceWhiteAuto",
"Off",
false);
1051 rcg::setEnum(nodemap,
"BalanceRatioSelector",
"Red",
false);
1052 rcg::setFloat(nodemap,
"BalanceRatio", cfg.camera_wb_ratio_red,
false);
1060 rcg::setEnum(nodemap,
"BalanceRatioSelector",
"Blue",
false);
1061 rcg::setFloat(nodemap,
"BalanceRatio", cfg.camera_wb_ratio_blue,
false);
1069 std::vector<std::string> list;
1070 rcg::getEnum(nodemap,
"DepthAcquisitionMode", list,
true);
1073 for (
size_t i = 0; i < list.size(); i++)
1075 if (list[i].compare(cfg.depth_acquisition_mode) == 0)
1083 rcg::setEnum(nodemap,
"DepthAcquisitionMode", val.c_str(),
true);
1088 ROS_WARN_STREAM(
"DepthAcquisitionMode " << cfg.depth_acquisition_mode <<
" not supported by rc_visard");
1097 std::vector<std::string> list;
1102 if (cfg.depth_quality ==
"High" && cfg.depth_static_scene)
1106 for (
size_t i = 0; i < list.size() && val.size() == 0; i++)
1108 if (list[i].compare(0, 1,
"StaticHigh", 0, 1) == 0)
1115 for (
size_t i = 0; i < list.size() && val.size() == 0; i++)
1117 if (list[i].compare(0, 1, cfg.depth_quality, 0, 1) == 0)
1125 rcg::setEnum(nodemap,
"DepthQuality", val.c_str(),
true);
1133 rcg::setBoolean(nodemap,
"DepthDoubleShot", cfg.depth_double_shot,
false);
1141 if (!
rcg::setBoolean(nodemap,
"DepthStaticScene", cfg.depth_static_scene,
false))
1145 std::string quality = cfg.depth_quality;
1147 if (cfg.depth_static_scene && quality ==
"High")
1149 quality =
"StaticHigh";
1152 std::vector<std::string> list;
1156 for (
size_t i = 0; i < list.size() && val.size() == 0; i++)
1158 if (list[i].compare(0, 1, quality, 0, 1) == 0)
1166 rcg::setEnum(nodemap,
"DepthQuality", val.c_str(),
true);
1196 rcg::setFloat(nodemap,
"DepthMinConf", cfg.depth_minconf,
true);
1203 rcg::setFloat(nodemap,
"DepthMinDepth", cfg.depth_mindepth,
true);
1210 rcg::setFloat(nodemap,
"DepthMaxDepth", cfg.depth_maxdepth,
true);
1217 rcg::setFloat(nodemap,
"DepthMaxDepthErr", cfg.depth_maxdeptherr,
true);
1221 if (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);
1239 catch (
const std::exception& ex)
1252 void disableAll(
const std::shared_ptr<GenApi::CNodeMapRef>& nodemap)
1254 std::vector<std::string> component;
1256 rcg::getEnum(nodemap,
"ComponentSelector", component,
true);
1258 for (
size_t i = 0; i < component.size(); i++)
1260 rcg::setEnum(nodemap,
"ComponentSelector", component[i].c_str(),
true);
1264 rcg::setEnum(nodemap,
"ComponentSelector",
"Intensity");
1268 rcg::setEnum(nodemap,
"AcquisitionMultiPartMode",
"SingleComponent");
1280 int enable(
const std::shared_ptr<GenApi::CNodeMapRef>& nodemap,
const char* component,
bool& en_curr,
bool en_new)
1282 if (en_new != en_curr)
1285 ROS_INFO_STREAM(
"rc_visard_driver: Enabled image stream: " << component);
1287 ROS_INFO_STREAM(
"rc_visard_driver: Disabled image stream: " << component);
1289 rcg::setEnum(nodemap,
"ComponentSelector", component,
true);
1302 inline rc_common_msgs::KeyValue getKeyValue(
const char* key, T value)
1304 rc_common_msgs::KeyValue ret;
1307 ret.value = std::to_string(value);
1312 inline rc_common_msgs::KeyValue getKeyValueString(
const char* key,
const std::string& value)
1314 rc_common_msgs::KeyValue ret;
1324 rc_common_msgs::CameraParam extractChunkData(
const std::shared_ptr<GenApi::CNodeMapRef>&
rcgnodemap)
1326 rc_common_msgs::CameraParam cam_param;
1331 std::vector<std::string> lines;
1333 uint32_t input_mask = 0;
1334 uint32_t output_mask = 0;
1335 for (
size_t i = 0; i < lines.size(); i++)
1337 rcg::setEnum(rcgnodemap,
"LineSelector", lines[i].c_str(),
true);
1342 input_mask |= 1 << i;
1347 output_mask |= 1 << i;
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);
1357 cam_param.extra_data.push_back(getKeyValue(
"input_mask", input_mask));
1358 cam_param.extra_data.push_back(getKeyValue(
"output_mask", output_mask));
1361 cam_param.line_status_all =
rcg::getInteger(rcgnodemap,
"ChunkLineStatusAll", 0, 0,
false);
1364 cam_param.gain =
rcg::getFloat(rcgnodemap,
"ChunkGain", 0, 0,
false);
1365 cam_param.exposure_time =
rcg::getFloat(rcgnodemap,
"ChunkExposureTime", 0, 0,
false) / 1000000l;
1370 float noise =
rcg::getFloat(rcgnodemap,
"ChunkRcNoise", 0, 0,
true);
1371 cam_param.extra_data.push_back(getKeyValue(
"noise", noise));
1373 catch (std::invalid_argument&)
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));
1384 cam_param.extra_data.push_back(getKeyValue(
"test", test));
1386 catch (std::invalid_argument&)
1393 float out1_reduction;
1396 out1_reduction =
rcg::getFloat(rcgnodemap,
"ChunkRcOut1Reduction", 0, 0,
true);
1398 catch (
const std::exception&)
1401 out1_reduction =
rcg::getFloat(rcgnodemap,
"ChunkRcAdaptiveOut1Reduction", 0, 0,
true);
1403 cam_param.extra_data.push_back(getKeyValue(
"out1_reduction", out1_reduction));
1405 catch (std::invalid_argument&)
1412 float brightness =
rcg::getFloat(rcgnodemap,
"ChunkRcBrightness", 0, 0,
true);
1413 cam_param.extra_data.push_back(getKeyValue(
"brightness", brightness));
1415 catch (std::invalid_argument&)
1422 bool adapting =
rcg::getBoolean(rcgnodemap,
"ChunkRcAutoExposureAdapting",
true);
1423 cam_param.extra_data.push_back(getKeyValue(
"auto_exposure_adapting", adapting));
1425 catch (
const std::exception&)
1430 cam_param.extra_data.push_back(getKeyValueString(
"model_name",
rcg::getString(rcgnodemap,
"DeviceModelName")));
1439 unsigned int maxNumConsecutiveFails = 5;
1448 unsigned int cntConsecutiveFails = 0;
1449 while (!
stopImageThread && cntConsecutiveFails < maxNumConsecutiveFails)
1462 bool ccolor =
false;
1463 bool cintensity =
false;
1464 bool cintensitycombined =
false;
1465 bool cdisparity =
false;
1466 bool cconfidence =
false;
1467 bool cerror =
false;
1469 bool firstTime =
true;
1479 throw std::runtime_error(
"Focal length not found: Neither 'FocalLength' nor 'FocalLengthFactor'!");
1489 throw std::invalid_argument(
"Feature not found or not readable: Baseline");
1494 throw std::invalid_argument(
"Feature not float: Baseline");
1496 if (val->GetUnit() ==
"mm")
1516 float mindepth =
config.depth_mindepth;
1517 float maxdepth =
config.depth_maxdepth;
1518 bool is_depth_acquisition_continuous = (
config.depth_acquisition_mode[0] ==
'C');
1522 std::shared_ptr<GenApi::CChunkAdapter> chunkadapter;
1548 std::shared_ptr<ImagePublisher> limage_color;
1549 std::shared_ptr<ImagePublisher> rimage_color;
1552 limage_color = std::make_shared<ImagePublisher>(it,
tfPrefix,
true,
true,
true);
1553 rimage_color = std::make_shared<ImagePublisher>(it,
tfPrefix,
false,
true,
true);
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);
1563 std::vector<std::shared_ptr<rcg::Stream> > stream =
rcgdev->getStreams();
1567 if (stream.size() > 0)
1570 stream[0]->startStreaming();
1574 std::string out1_mode_on_sensor;
1596 chunkadapter->AttachBuffer(reinterpret_cast<std::uint8_t*>(buffer->
getGlobalBase()),
1605 out1_mode_on_sensor = v;
1612 bool out1_alternate = (out1_mode_on_sensor ==
"ExposureAlternateActive");
1615 rc_common_msgs::CameraParam cam_param;
1622 boost::recursive_mutex::scoped_lock lock(
mtx);
1626 camera_fps =
config.camera_fps;
1630 out1 = (cam_param.line_status_all & 0x1);
1633 for (uint32_t part=0; part<npart; part++)
1639 double warn_limit = 3.0/camera_fps;
1640 if (dt > warn_limit)
1642 ROS_WARN(
"rc_visard_driver: time between image publish more than %.3fs: %.3fs.", warn_limit, dt);
1645 cntConsecutiveFails = 0;
1657 lcaminfo.
publish(buffer, part, pixelformat);
1658 rcaminfo.
publish(buffer, part, pixelformat);
1660 if (lcamparams && rcamparams)
1662 lcamparams->publish(buffer, cam_param, pixelformat);
1663 rcamparams->publish(buffer, cam_param, pixelformat);
1666 limage.
publish(buffer, part, pixelformat, out1);
1667 rimage.
publish(buffer, part, pixelformat, out1);
1669 if (limage_color && rimage_color)
1671 limage_color->publish(buffer, part, pixelformat, out1);
1672 rimage_color->publish(buffer, part, pixelformat, out1);
1675 disp.
publish(buffer, part, pixelformat);
1676 cdisp.
publish(buffer, part, pixelformat);
1677 depth.
publish(buffer, part, pixelformat);
1679 confidence.
publish(buffer, part, pixelformat);
1680 error_disp.
publish(buffer, part, pixelformat);
1681 error_depth.
publish(buffer, part, pixelformat);
1683 points2.
publish(buffer, part, pixelformat, out1);
1696 out1_mode_on_sensor =
"";
1703 if (chunkadapter) chunkadapter->DetachBuffer();
1709 ROS_WARN(
"rc_visard_driver: Received incomplete image buffer");
1711 else if (buffer == 0)
1716 if (cintensity || cintensitycombined ||
1717 (is_depth_acquisition_continuous && (cdisparity || cconfidence || cerror)))
1725 out <<
"No images received for " << t <<
" seconds!";
1726 throw std::underflow_error(out.
str());
1750 ROS_INFO(
"rc_visard_driver: Depth image acquisition triggered");
1758 if (limage_color && rimage_color && (limage_color->used() || rimage_color->used() || points2.
used()))
1782 int changed = enable(
rcgnodemap,
"IntensityCombined", cintensitycombined,
1783 rimage.
used() || (rimage_color && rimage_color->used()));
1785 changed += enable(
rcgnodemap,
"Intensity", cintensity,
1786 !cintensitycombined && (lcaminfo.
used() || rcaminfo.
used() ||
1787 (lcamparams && lcamparams->used()) ||
1788 (rcamparams && rcamparams->used()) ||
1790 (limage_color && limage_color->used()) || points2.
used()));
1792 changed += enable(
rcgnodemap,
"Disparity", cdisparity,
1795 changed += enable(
rcgnodemap,
"Confidence", cconfidence, confidence.
used());
1797 changed += enable(
rcgnodemap,
"Error", cerror, error_disp.
used() || error_depth.
used());
1802 if (changed > 0 || firstTime)
1804 if (cintensity || cintensitycombined || cdisparity || cconfidence || cerror)
1818 rc_visard_driver::rc_visard_driverConfig cfg =
config;
1819 uint32_t lvl =
level;
1825 mindepth = cfg.depth_mindepth;
1826 maxdepth = cfg.depth_maxdepth;
1832 is_depth_acquisition_continuous = (cfg.depth_acquisition_mode[0] ==
'C');
1836 if (is_depth_acquisition_continuous)
1848 if (out1_mode_on_sensor.size() == 0)
1851 out1_mode_on_sensor =
config.out1_mode;
1854 if (out1_mode_on_sensor !=
config.out1_mode)
1856 config.out1_mode = out1_mode_on_sensor;
1862 stream[0]->stopStreaming();
1867 ROS_ERROR(
"rc_visard_driver: No stream");
1868 cntConsecutiveFails++;
1871 catch (
const std::exception& ex)
1874 cntConsecutiveFails++;
1880 if (cntConsecutiveFails > 0)
1882 ROS_ERROR_STREAM(
"rc_visard_driver: Number of consecutive failures: " << cntConsecutiveFails);
1884 if (cntConsecutiveFails >= maxNumConsecutiveFails)
1893 rc_common_msgs::Trigger::Response& resp)
1897 resp.return_code.value = ReturnCodeConstants::SUCCESS;
1898 resp.return_code.message =
"";
1915 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Disconnected");
1927 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Streaming");
1930 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"No data");
1934 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Idle");
1941 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Unknown");
1943 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Info");
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.
bool autopublishTrajectory
#define NODELET_WARN(...)
bool used() override
Returns true if there are subscribers to the topic.
tf::Transform toRosTfTransform(const roboception::msgs::Pose &pose)
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.
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.
void produce_device_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publis...
bool setFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double value, bool exception=false)
ros::ServiceServer depthAcquisitionTriggerService
wrapper for REST-API calls relating to rc_visard'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
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 ¶m_name, T ¶m_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.
ROSCPP_DECL const std::string & getNamespace()
unsigned int totalCompleteBuffers
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)
ros::ServiceServer dynamicsRestartSlamService
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()
int cntConsecutiveRecoveryFails
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 dev_supports_double_shot
bool depthAcquisitionTrigger(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Trigger stereo matching in mode 'SingleFrame'.
#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
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
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
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)
bool saveSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Save the onboard SLAM map.
unsigned int totalConnectionLosses
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
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)
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