SickSafetyscannersRos.cpp
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 
24 // -- END LICENSE BLOCK ------------------------------------------------
25 
26 //----------------------------------------------------------------------
33 //----------------------------------------------------------------------
34 
35 
37 
38 
39 namespace sick {
40 
42  : m_private_nh("~")
43  , m_initialised(false)
44  , m_time_offset(0.0)
45  , m_range_min(0.0)
46  , m_range_max(0.0)
47  , m_angle_offset(-90.0)
48  , m_use_pers_conf(false)
49 {
50  dynamic_reconfigure::Server<
51  sick_safetyscanners::SickSafetyscannersConfigurationConfig>::CallbackType reconf_callback =
52  boost::bind(&SickSafetyscannersRos::reconfigureCallback, this, _1, _2);
53  m_dynamic_reconfiguration_server.setCallback(reconf_callback);
54  if (!readParameters())
55  {
56  ROS_ERROR("Could not read parameters.");
58  }
59  // tcp port can not be changed in the sensor configuration, therefore it is hardcoded
61  m_laser_scan_publisher = m_nh.advertise<sensor_msgs::LaserScan>("scan", 100);
63  m_nh.advertise<sick_safetyscanners::ExtendedLaserScanMsg>("extended_laser_scan", 100);
64  m_raw_data_publisher = m_nh.advertise<sick_safetyscanners::RawMicroScanDataMsg>("raw_data", 100);
66  m_nh.advertise<sick_safetyscanners::OutputPathsMsg>("output_paths", 100);
69 
74 
75  // Diagnostics for frequency
77 
83  m_laser_scan_publisher, m_diagnostic_updater, frequency_param, timestamp_param));
85 
86  m_device = std::make_shared<sick::SickSafetyscanners>(
87  boost::bind(&SickSafetyscannersRos::receivedUDPPacket, this, _1),
90  m_device->run();
92 
93  if (m_use_pers_conf)
94  {
96  }
97 
98  m_device->changeSensorSettings(m_communication_settings);
99  m_device->requestConfigMetadata(m_communication_settings, config_meta_data);
100  m_device->requestFirmwareVersion(m_communication_settings, firmware_version);
101 
102  m_initialised = true;
103  ROS_INFO("Successfully launched node.");
104 }
105 
107 {
108  ROS_INFO("Reading Type code settings");
110  m_device->requestTypeCode(m_communication_settings, type_code);
112  m_range_min = 0.1;
113  m_range_max = type_code.getMaxRange();
114 }
115 
117 {
118  ROS_INFO("Reading Persistent Configuration");
120  m_device->requestPersistentConfig(m_communication_settings, config_data);
123 }
124 
126  const sick_safetyscanners::SickSafetyscannersConfigurationConfig& config, const uint32_t& level)
127 {
128  if (isInitialised())
129  {
130  m_communication_settings.setEnabled(config.channel_enabled);
132  if (config.angle_start == config.angle_end)
133  {
136  }
137  else
138  {
141  }
142  m_communication_settings.setFeatures(config.general_system_state,
143  config.derived_settings,
144  config.measurement_data,
145  config.intrusion_data,
146  config.application_io_data);
147  m_device->changeSensorSettings(m_communication_settings);
148 
149  m_frame_id = config.frame_id;
150 
151  m_time_offset = config.time_offset;
152 
153  m_expected_frequency = config.expected_frequency;
154 
155  m_min_intensities = config.min_intensities;
156  }
157 }
158 
160 {
161  return m_initialised;
162 }
163 
164 
166 
168 {
169  std::string sensor_ip_adress = "192.168.1.10";
170  if (!m_private_nh.getParam("sensor_ip", sensor_ip_adress))
171  {
172  // sensor_ip_adress = sick_safetyscanners::SickSafetyscannersConfiguration_sensor_ip;
173  ROS_WARN("Using default sensor IP: %s", sensor_ip_adress.c_str());
174  }
175  m_communication_settings.setSensorIp(sensor_ip_adress);
176 
177 
178  std::string host_ip_adress = "192.168.1.9";
179  if (!m_private_nh.getParam("host_ip", host_ip_adress))
180  {
181  ROS_WARN("Using default host IP: %s", host_ip_adress.c_str());
182  }
183  m_communication_settings.setHostIp(host_ip_adress);
184 
185  std::string interface_ip_adress = "0.0.0.0";
186  if (!m_private_nh.getParam("interface_ip", interface_ip_adress))
187  {
188  ROS_WARN("Using default interface IP: %s", interface_ip_adress.c_str());
189  }
190  m_interface_ip = boost::asio::ip::address_v4::from_string(interface_ip_adress);
191 
192  int host_udp_port = 0;
193  if (!m_private_nh.getParam("host_udp_port", host_udp_port))
194  {
195  ROS_WARN("Using default host UDP Port: %i", host_udp_port);
196  }
198 
199  ROS_WARN("If not further specified the default values for the dynamic reconfigurable parameters "
200  "will be loaded.");
201 
202 
203  int channel = 0;
204  m_private_nh.getParam("channel", channel);
206 
207  bool enabled;
208  m_private_nh.getParam("channel_enabled", enabled);
210 
211  int skip;
212  m_private_nh.getParam("skip", skip);
214 
215  float angle_start;
216  m_private_nh.getParam("angle_start", angle_start);
217 
218  float angle_end;
219  m_private_nh.getParam("angle_end", angle_end);
220 
221  m_private_nh.getParam("frequency_tolerance", m_frequency_tolerance);
222  m_private_nh.getParam("expected_frequency", m_expected_frequency);
223  m_private_nh.getParam("timestamp_min_acceptable", m_timestamp_min_acceptable);
224  m_private_nh.getParam("timestamp_max_acceptable", m_timestamp_max_acceptable);
225 
226  // Included check before calculations to prevent rounding errors while calculating
227  if (angle_start == angle_end)
228  {
231  }
232  else
233  {
236  }
237 
238  m_private_nh.getParam("time_offset", m_time_offset);
239 
240  bool general_system_state;
241  m_private_nh.getParam("general_system_state", general_system_state);
242 
243  bool derived_settings;
244  m_private_nh.getParam("derived_settings", derived_settings);
245 
246  bool measurement_data;
247  m_private_nh.getParam("measurement_data", measurement_data);
248 
249  bool intrusion_data;
250  m_private_nh.getParam("intrusion_data", intrusion_data);
251 
252  bool application_io_data;
253  m_private_nh.getParam("application_io_data", application_io_data);
254 
256  general_system_state, derived_settings, measurement_data, intrusion_data, application_io_data);
257 
258  m_private_nh.getParam("frame_id", m_frame_id);
259 
260  m_private_nh.getParam("use_persistent_config", m_use_pers_conf);
261 
262  m_private_nh.getParam("min_intensities", m_min_intensities);
263 
264  return true;
265 }
266 
268 {
269  if (!data.getMeasurementDataPtr()->isEmpty() && !data.getDerivedValuesPtr()->isEmpty())
270  {
271  sensor_msgs::LaserScan scan = createLaserScanMessage(data);
272 
273  m_diagnosed_laser_scan_publisher->publish(scan);
274  }
275 
276 
277  if (!data.getMeasurementDataPtr()->isEmpty() && !data.getDerivedValuesPtr()->isEmpty())
278  {
279  sick_safetyscanners::ExtendedLaserScanMsg extended_scan = createExtendedLaserScanMessage(data);
280 
282 
283  sick_safetyscanners::OutputPathsMsg output_paths = createOutputPathsMessage(data);
284  m_output_path_publisher.publish(output_paths);
285  }
286 
289 
291 }
292 
293 std::string boolToString(bool b)
294 {
295  return b ? "true" : "false";
296 }
297 
300 {
301  const sick_safetyscanners::DataHeaderMsg& header = m_last_raw_data.header;
302  if (header.timestamp_time == 0 && header.timestamp_date == 0)
303  {
304  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::STALE,
305  "Could not get sensor state");
306  return;
307  }
308 
309  diagnostic_status.addf("Version version", "%c", header.version_version);
310  diagnostic_status.addf("Version major version", "%u", header.version_major_version);
311  diagnostic_status.addf("Version minor version", "%u", header.version_minor_version);
312  diagnostic_status.addf("Version release", "%u", header.version_release);
313  diagnostic_status.addf("Firmware version", "%s", firmware_version.getFirmwareVersion().c_str());
314  diagnostic_status.addf("Serial number of device", "%u", header.serial_number_of_device);
315  diagnostic_status.addf(
316  "Serial number of channel plug", "%u", header.serial_number_of_channel_plug);
317  diagnostic_status.addf("App checksum", "%X", config_meta_data.getAppChecksum());
318  diagnostic_status.addf("Overall checksum", "%X", config_meta_data.getOverallChecksum());
319 
320  diagnostic_status.addf("Channel number", "%u", header.channel_number);
321  diagnostic_status.addf("Sequence number", "%u", header.sequence_number);
322  diagnostic_status.addf("Scan number", "%u", header.scan_number);
323  diagnostic_status.addf("Timestamp date", "%u", header.timestamp_date);
324  diagnostic_status.addf("Timestamp time", "%u", header.timestamp_time);
325 
326  const sick_safetyscanners::GeneralSystemStateMsg& state = m_last_raw_data.general_system_state;
327  diagnostic_status.add("Run mode active", boolToString(state.run_mode_active));
328  diagnostic_status.add("Standby mode active", boolToString(state.standby_mode_active));
329  diagnostic_status.add("Contamination warning", boolToString(state.contamination_warning));
330  diagnostic_status.add("Contamination error", boolToString(state.contamination_error));
331  diagnostic_status.add("Reference contour status", boolToString(state.reference_contour_status));
332  diagnostic_status.add("Manipulation status", boolToString(state.manipulation_status));
333  diagnostic_status.addf(
334  "Current monitoring case no table 1", "%u", state.current_monitoring_case_no_table_1);
335  diagnostic_status.addf(
336  "Current monitoring case no table 2", "%u", state.current_monitoring_case_no_table_2);
337  diagnostic_status.addf(
338  "Current monitoring case no table 3", "%u", state.current_monitoring_case_no_table_3);
339  diagnostic_status.addf(
340  "Current monitoring case no table 4", "%u", state.current_monitoring_case_no_table_4);
341  diagnostic_status.add("Application error", boolToString(state.application_error));
342  diagnostic_status.add("Device error", boolToString(state.device_error));
343 
344  if (state.device_error)
345  {
346  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Device error");
347  }
348  else if (state.application_error)
349  {
350  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Application error");
351  }
352  else if (state.contamination_error)
353  {
354  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Contamination error");
355  }
356  else if (state.contamination_warning)
357  {
358  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Contamination warning");
359  }
360  else
361  {
362  diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::OK, "OK");
363  }
364 }
365 
366 sick_safetyscanners::ExtendedLaserScanMsg
368 {
369  sensor_msgs::LaserScan scan = createLaserScanMessage(data);
370  sick_safetyscanners::ExtendedLaserScanMsg msg;
371  msg.laser_scan = scan;
372 
373  std::vector<sick::datastructure::ScanPoint> scan_points =
374  data.getMeasurementDataPtr()->getScanPointsVector();
375  uint32_t num_scan_points = scan_points.size();
376 
377 
378  msg.reflektor_status.resize(num_scan_points);
379  msg.intrusion.resize(num_scan_points);
380  msg.reflektor_median.resize(num_scan_points);
381  std::vector<bool> medians = getMedianReflectors(scan_points);
382  for (uint32_t i = 0; i < num_scan_points; ++i)
383  {
384  const sick::datastructure::ScanPoint scan_point = scan_points.at(i);
385  msg.reflektor_status[i] = scan_point.getReflectorBit();
386  msg.intrusion[i] = scan_point.getContaminationBit();
387  msg.reflektor_median[i] = medians.at(i);
388  }
389  return msg;
390 }
391 
393  const std::vector<sick::datastructure::ScanPoint> scan_points)
394 {
395  std::vector<bool> res;
396  res.resize(scan_points.size());
397  bool last = false;
398  int start = -1;
399  for (size_t i = 0; i < scan_points.size(); i++)
400  {
401  res.at(i) = false;
402  if (!last && scan_points.at(i).getReflectorBit())
403  {
404  last = true;
405  start = i;
406  }
407  else if (last && (!scan_points.at(i).getReflectorBit() || i == scan_points.size() - 1))
408  {
409  last = false;
410  res.at(start + ((i - start) / 2)) = true;
411  }
412  }
413 
414  return res;
415 }
416 
417 sensor_msgs::LaserScan
419 {
420  sensor_msgs::LaserScan scan;
421  scan.header.frame_id = m_frame_id;
422  scan.header.stamp = ros::Time::now();
423  // Add time offset (to account for network latency etc.)
424  scan.header.stamp += ros::Duration().fromSec(m_time_offset);
425 
426  std::vector<sick::datastructure::ScanPoint> scan_points =
427  data.getMeasurementDataPtr()->getScanPointsVector();
428  uint32_t num_scan_points = scan_points.size();
429 
430  scan.angle_min = sick::degToRad(data.getDerivedValuesPtr()->getStartAngle() + m_angle_offset);
431  // if the scan points vector is empty, the angle max is set to the angle min
432  scan.angle_max = scan_points.empty()
433  ? scan.angle_min
434  : sick::degToRad(scan_points.back().getAngle() + m_angle_offset);
435  scan.angle_increment = sick::degToRad(data.getDerivedValuesPtr()->getAngularBeamResolution());
436  boost::posix_time::microseconds time_increment =
437  boost::posix_time::microseconds(data.getDerivedValuesPtr()->getInterbeamPeriod());
438  scan.time_increment = time_increment.total_microseconds() * 1e-6;
439  boost::posix_time::milliseconds scan_time =
440  boost::posix_time::milliseconds(data.getDerivedValuesPtr()->getScanTime());
441  scan.scan_time = scan_time.total_microseconds() * 1e-6;
442  scan.range_min = m_range_min;
443  scan.range_max = m_range_max;
444  scan.ranges.resize(num_scan_points);
445  scan.intensities.resize(num_scan_points);
446 
447 
448  for (uint32_t i = 0; i < num_scan_points; ++i)
449  {
450  const sick::datastructure::ScanPoint scan_point = scan_points.at(i);
451  // Filter for intensities
452  if (m_min_intensities < static_cast<double>(scan_point.getReflectivity()))
453  {
454  scan.ranges[i] = static_cast<float>(scan_point.getDistance()) *
455  data.getDerivedValuesPtr()->getMultiplicationFactor() * 1e-3; // mm -> m
456  // Set values close to/greater than max range to infinity according to REP 117
457  // https://www.ros.org/reps/rep-0117.html
458  if (scan.ranges[i] >= (0.999 * m_range_max))
459  {
460  scan.ranges[i] = std::numeric_limits<double>::infinity();
461  }
462  }
463  else
464  {
465  scan.ranges[i] = std::numeric_limits<double>::infinity();
466  }
467  scan.intensities[i] = static_cast<float>(scan_point.getReflectivity());
468  }
469  return scan;
470 }
471 
472 sick_safetyscanners::OutputPathsMsg
474 {
475  sick_safetyscanners::OutputPathsMsg msg;
476 
477  std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
478  sick::datastructure::ApplicationOutputs outputs = app_data->getOutputs();
479 
480  std::vector<bool> eval_out = outputs.getEvalOutVector();
481  std::vector<bool> eval_out_is_safe = outputs.getEvalOutIsSafeVector();
482  std::vector<bool> eval_out_valid = outputs.getEvalOutIsValidVector();
483 
484  std::vector<uint16_t> monitoring_case_numbers = outputs.getMonitoringCaseVector();
485  std::vector<bool> monitoring_case_number_flags = outputs.getMonitoringCaseFlagsVector();
486 
487  // Fix according to issue #46, however why this appears is not clear
488  if (monitoring_case_number_flags.size() > 0)
489  {
490  msg.active_monitoring_case = monitoring_case_numbers.at(0);
491  }
492  else
493  {
494  msg.active_monitoring_case = 0;
495  }
496 
497  for (size_t i = 0; i < eval_out.size(); i++)
498  {
499  msg.status.push_back(eval_out.at(i));
500  msg.is_safe.push_back(eval_out_is_safe.at(i));
501  msg.is_valid.push_back(eval_out_valid.at(i));
502  }
503  return msg;
504 }
505 
506 sick_safetyscanners::RawMicroScanDataMsg
508 {
509  sick_safetyscanners::RawMicroScanDataMsg msg;
510 
511  msg.header = createDataHeaderMessage(data);
512  msg.derived_values = createDerivedValuesMessage(data);
513  msg.general_system_state = createGeneralSystemStateMessage(data);
514  msg.measurement_data = createMeasurementDataMessage(data);
515  msg.intrusion_data = createIntrusionDataMessage(data);
516  msg.application_data = createApplicationDataMessage(data);
517 
518  return msg;
519 }
520 
521 sick_safetyscanners::DataHeaderMsg
523 {
524  sick_safetyscanners::DataHeaderMsg msg;
525 
526  if (!data.getDataHeaderPtr()->isEmpty())
527  {
528  std::shared_ptr<sick::datastructure::DataHeader> data_header = data.getDataHeaderPtr();
529 
530  msg.version_version = data_header->getVersionIndicator();
531  msg.version_release = data_header->getVersionRelease();
532  msg.version_major_version = data_header->getVersionMajorVersion();
533  msg.version_minor_version = data_header->getVersionMinorVersion();
534 
535  msg.scan_number = data_header->getScanNumber();
536  msg.sequence_number = data_header->getSequenceNumber();
537 
538  msg.serial_number_of_device = data_header->getSerialNumberOfDevice();
539  msg.serial_number_of_channel_plug = data_header->getSerialNumberOfSystemPlug();
540 
541  msg.channel_number = data_header->getChannelNumber();
542 
543  msg.timestamp_date = data_header->getTimestampDate();
544  msg.timestamp_time = data_header->getTimestampTime();
545  }
546  return msg;
547 }
548 
549 sick_safetyscanners::DerivedValuesMsg
551 {
552  sick_safetyscanners::DerivedValuesMsg msg;
553 
554  if (!data.getDerivedValuesPtr()->isEmpty())
555  {
556  std::shared_ptr<sick::datastructure::DerivedValues> derived_values = data.getDerivedValuesPtr();
557 
558  msg.multiplication_factor = derived_values->getMultiplicationFactor();
559  msg.scan_time = derived_values->getScanTime();
560  msg.interbeam_period = derived_values->getInterbeamPeriod();
561  msg.number_of_beams = derived_values->getNumberOfBeams();
562  msg.start_angle = derived_values->getStartAngle() + m_angle_offset;
563  msg.angular_beam_resolution = derived_values->getAngularBeamResolution();
564  }
565  return msg;
566 }
567 
568 sick_safetyscanners::GeneralSystemStateMsg
570 {
571  sick_safetyscanners::GeneralSystemStateMsg msg;
572 
573  if (!data.getGeneralSystemStatePtr()->isEmpty())
574  {
575  std::shared_ptr<sick::datastructure::GeneralSystemState> general_system_state =
576  data.getGeneralSystemStatePtr();
577 
578  msg.run_mode_active = general_system_state->getRunModeActive();
579  msg.standby_mode_active = general_system_state->getStandbyModeActive();
580  msg.contamination_warning = general_system_state->getContaminationWarning();
581  msg.contamination_error = general_system_state->getContaminationError();
582  msg.reference_contour_status = general_system_state->getReferenceContourStatus();
583  msg.manipulation_status = general_system_state->getManipulationStatus();
584 
585  std::vector<bool> safe_cut_off_path = general_system_state->getSafeCutOffPathVector();
586  for (size_t i = 0; i < safe_cut_off_path.size(); i++)
587  {
588  msg.safe_cut_off_path.push_back(safe_cut_off_path.at(i));
589  }
590 
591  std::vector<bool> non_safe_cut_off_path = general_system_state->getNonSafeCutOffPathVector();
592  for (size_t i = 0; i < non_safe_cut_off_path.size(); i++)
593  {
594  msg.non_safe_cut_off_path.push_back(non_safe_cut_off_path.at(i));
595  }
596 
597  std::vector<bool> reset_required_cut_off_path =
598  general_system_state->getResetRequiredCutOffPathVector();
599  for (size_t i = 0; i < reset_required_cut_off_path.size(); i++)
600  {
601  msg.reset_required_cut_off_path.push_back(reset_required_cut_off_path.at(i));
602  }
603 
604  msg.current_monitoring_case_no_table_1 =
605  general_system_state->getCurrentMonitoringCaseNoTable1();
606  msg.current_monitoring_case_no_table_2 =
607  general_system_state->getCurrentMonitoringCaseNoTable2();
608  msg.current_monitoring_case_no_table_3 =
609  general_system_state->getCurrentMonitoringCaseNoTable3();
610  msg.current_monitoring_case_no_table_4 =
611  general_system_state->getCurrentMonitoringCaseNoTable4();
612 
613  msg.application_error = general_system_state->getApplicationError();
614  msg.device_error = general_system_state->getDeviceError();
615  }
616  return msg;
617 }
618 
619 sick_safetyscanners::MeasurementDataMsg
621 {
622  sick_safetyscanners::MeasurementDataMsg msg;
623 
624  if (!data.getMeasurementDataPtr()->isEmpty())
625  {
626  msg.number_of_beams = data.getMeasurementDataPtr()->getNumberOfBeams();
627  msg.scan_points = createScanPointMessageVector(data);
628  }
629  return msg;
630 }
631 
632 std::vector<sick_safetyscanners::ScanPointMsg>
634 {
635  std::vector<sick_safetyscanners::ScanPointMsg> msg_vector;
636 
637  std::shared_ptr<sick::datastructure::MeasurementData> measurement_data =
638  data.getMeasurementDataPtr();
639  std::vector<sick::datastructure::ScanPoint> scan_points = measurement_data->getScanPointsVector();
640  // uint32_t num_points = measurement_data->getNumberOfBeams();
641  uint32_t num_points = scan_points.size();
642  for (uint32_t i = 0; i < num_points; i++)
643  {
644  sick::datastructure::ScanPoint scan_point = scan_points.at(i);
645  sick_safetyscanners::ScanPointMsg msg;
646  msg.distance = scan_point.getDistance();
647  msg.reflectivity = scan_point.getReflectivity();
648  msg.angle = scan_point.getAngle() + m_angle_offset;
649  msg.valid = scan_point.getValidBit();
650  msg.infinite = scan_point.getInfiniteBit();
651  msg.glare = scan_point.getGlareBit();
652  msg.reflector = scan_point.getReflectorBit();
653  msg.contamination_warning = scan_point.getContaminationWarningBit();
654  msg.contamination = scan_point.getContaminationBit();
655 
656  msg_vector.push_back(msg);
657  }
658  return msg_vector;
659 }
660 
661 sick_safetyscanners::IntrusionDataMsg
663 {
664  sick_safetyscanners::IntrusionDataMsg msg;
665 
666  if (!data.getIntrusionDataPtr()->isEmpty())
667  {
669  }
670  return msg;
671 }
672 
673 std::vector<sick_safetyscanners::IntrusionDatumMsg>
675 {
676  std::vector<sick_safetyscanners::IntrusionDatumMsg> msg_vector;
677 
678  std::shared_ptr<sick::datastructure::IntrusionData> intrusion_data = data.getIntrusionDataPtr();
679  std::vector<sick::datastructure::IntrusionDatum> intrusion_datums =
680  intrusion_data->getIntrusionDataVector();
681 
682  for (size_t i = 0; i < intrusion_datums.size(); i++)
683  {
684  sick_safetyscanners::IntrusionDatumMsg msg;
685  sick::datastructure::IntrusionDatum intrusion_datum = intrusion_datums.at(i);
686  msg.size = intrusion_datum.getSize();
687  std::vector<bool> flags = intrusion_datum.getFlagsVector();
688  for (size_t j = 0; j < flags.size(); j++)
689  {
690  msg.flags.push_back(flags.at(j));
691  }
692  msg_vector.push_back(msg);
693  }
694  return msg_vector;
695 }
696 
697 sick_safetyscanners::ApplicationDataMsg
699 {
700  sick_safetyscanners::ApplicationDataMsg msg;
701 
702  if (!data.getApplicationDataPtr()->isEmpty())
703  {
706  }
707  return msg;
708 }
709 
710 sick_safetyscanners::ApplicationInputsMsg
712 {
713  sick_safetyscanners::ApplicationInputsMsg msg;
714 
715  std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
716  sick::datastructure::ApplicationInputs inputs = app_data->getInputs();
717  std::vector<bool> unsafe_inputs = inputs.getUnsafeInputsInputSourcesVector();
718  std::vector<bool> unsafe_inputs_flags = inputs.getUnsafeInputsFlagsVector();
719  for (size_t i = 0; i < unsafe_inputs.size(); i++)
720  {
721  msg.unsafe_inputs_input_sources.push_back(unsafe_inputs.at(i));
722  msg.unsafe_inputs_flags.push_back(unsafe_inputs_flags.at(i));
723  }
724  std::vector<uint16_t> monitoring_case = inputs.getMonitoringCasevector();
725  std::vector<bool> monitoring_case_flags = inputs.getMonitoringCaseFlagsVector();
726  for (size_t i = 0; i < monitoring_case.size(); i++)
727  {
728  msg.monitoring_case_number_inputs.push_back(monitoring_case.at(i));
729  msg.monitoring_case_number_inputs_flags.push_back(monitoring_case_flags.at(i));
730  }
731  msg.linear_velocity_inputs_velocity_0 = inputs.getVelocity0();
732  msg.linear_velocity_inputs_velocity_0_transmitted_safely = inputs.getVelocity0TransmittedSafely();
733  msg.linear_velocity_inputs_velocity_0_valid = inputs.getVelocity0Valid();
734  msg.linear_velocity_inputs_velocity_1 = inputs.getVelocity1();
735  msg.linear_velocity_inputs_velocity_1_transmitted_safely = inputs.getVelocity1TransmittedSafely();
736  msg.linear_velocity_inputs_velocity_1_valid = inputs.getVelocity1Valid();
737 
738  msg.sleep_mode_input = inputs.getSleepModeInput();
739 
740  return msg;
741 }
742 
743 sick_safetyscanners::ApplicationOutputsMsg
745 {
746  sick_safetyscanners::ApplicationOutputsMsg msg;
747 
748  std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
749  sick::datastructure::ApplicationOutputs outputs = app_data->getOutputs();
750 
751  std::vector<bool> eval_out = outputs.getEvalOutVector();
752  std::vector<bool> eval_out_is_safe = outputs.getEvalOutIsSafeVector();
753  std::vector<bool> eval_out_valid = outputs.getEvalOutIsValidVector();
754  for (size_t i = 0; i < eval_out.size(); i++)
755  {
756  msg.evaluation_path_outputs_eval_out.push_back(eval_out.at(i));
757  msg.evaluation_path_outputs_is_safe.push_back(eval_out_is_safe.at(i));
758  msg.evaluation_path_outputs_is_valid.push_back(eval_out_valid.at(i));
759  }
760 
761  std::vector<uint16_t> monitoring_case = outputs.getMonitoringCaseVector();
762  std::vector<bool> monitoring_case_flags = outputs.getMonitoringCaseFlagsVector();
763  for (size_t i = 0; i < monitoring_case.size(); i++)
764  {
765  msg.monitoring_case_number_outputs.push_back(monitoring_case.at(i));
766  msg.monitoring_case_number_outputs_flags.push_back(monitoring_case_flags.at(i));
767  }
768 
769  msg.sleep_mode_output = outputs.getSleepModeOutput();
770  msg.sleep_mode_output_valid = outputs.getFlagsSleepModeOutputIsValid();
771 
772  msg.error_flag_contamination_warning = outputs.getHostErrorFlagContaminationWarning();
773  msg.error_flag_contamination_error = outputs.getHostErrorFlagContaminationError();
774  msg.error_flag_manipulation_error = outputs.getHostErrorFlagManipulationError();
775  msg.error_flag_glare = outputs.getHostErrorFlagGlare();
776  msg.error_flag_reference_contour_intruded = outputs.getHostErrorFlagReferenceContourIntruded();
777  msg.error_flag_critical_error = outputs.getHostErrorFlagCriticalError();
778  msg.error_flags_are_valid = outputs.getFlagsHostErrorFlagsAreValid();
779 
780  msg.linear_velocity_outputs_velocity_0 = outputs.getVelocity0();
781  msg.linear_velocity_outputs_velocity_0_transmitted_safely =
783  msg.linear_velocity_outputs_velocity_0_valid = outputs.getVelocity0Valid();
784  msg.linear_velocity_outputs_velocity_1 = outputs.getVelocity1();
785  msg.linear_velocity_outputs_velocity_1_transmitted_safely =
787  msg.linear_velocity_outputs_velocity_1_valid = outputs.getVelocity1Valid();
788 
789  std::vector<int16_t> resulting_velocities = outputs.getResultingVelocityVector();
790  std::vector<bool> resulting_velocities_flags = outputs.getResultingVelocityIsValidVector();
791 
792  for (size_t i = 0; i < resulting_velocities.size(); i++)
793  {
794  msg.resulting_velocity.push_back(resulting_velocities.at(i));
795  msg.resulting_velocity_flags.push_back(resulting_velocities_flags.at(i));
796  }
797 
798 
799  return msg;
800 }
801 
802 bool SickSafetyscannersRos::getFieldData(sick_safetyscanners::FieldData::Request& req,
803  sick_safetyscanners::FieldData::Response& res)
804 {
805  std::vector<sick::datastructure::FieldData> fields;
806  m_device->requestFieldData(m_communication_settings, fields);
807 
808  for (size_t i = 0; i < fields.size(); i++)
809  {
810  sick::datastructure::FieldData field = fields.at(i);
811  sick_safetyscanners::FieldMsg field_msg;
812 
813  field_msg.start_angle = degToRad(field.getStartAngle() + m_angle_offset);
814  field_msg.angular_resolution = degToRad(field.getAngularBeamResolution());
815  field_msg.protective_field = field.getIsProtectiveField();
816 
817  std::vector<uint16_t> ranges = field.getBeamDistances();
818  for (size_t j = 0; j < ranges.size(); j++)
819  {
820  field_msg.ranges.push_back(static_cast<float>(ranges.at(j)) * 1e-3);
821  }
822 
823  res.fields.push_back(field_msg);
824  }
825 
826  datastructure::DeviceName device_name;
827  m_device->requestDeviceName(m_communication_settings, device_name);
828  res.device_name = device_name.getDeviceName();
829 
830 
831  std::vector<sick::datastructure::MonitoringCaseData> monitoring_cases;
832  m_device->requestMonitoringCases(m_communication_settings, monitoring_cases);
833 
834  for (size_t i = 0; i < monitoring_cases.size(); i++)
835  {
836  sick::datastructure::MonitoringCaseData monitoring_case_data = monitoring_cases.at(i);
837  sick_safetyscanners::MonitoringCaseMsg monitoring_case_msg;
838 
839  monitoring_case_msg.monitoring_case_number = monitoring_case_data.getMonitoringCaseNumber();
840  std::vector<uint16_t> mon_fields = monitoring_case_data.getFieldIndices();
841  std::vector<bool> mon_fields_valid = monitoring_case_data.getFieldsValid();
842  for (size_t j = 0; j < mon_fields.size(); j++)
843  {
844  monitoring_case_msg.fields.push_back(mon_fields.at(j));
845  monitoring_case_msg.fields_valid.push_back(mon_fields_valid.at(j));
846  }
847  res.monitoring_cases.push_back(monitoring_case_msg);
848  }
849 
850  return true;
851 }
852 
853 bool SickSafetyscannersRos::getConfigMetadata(sick_safetyscanners::ConfigMetadata::Request& req,
854  sick_safetyscanners::ConfigMetadata::Response& res)
855 {
856  static_cast<void>(req);
857  sick::datastructure::ConfigMetadata config_metadata;
858  m_device->requestConfigMetadata(m_communication_settings, config_metadata);
859 
860  res.app_checksum = getCheckSumString(config_metadata.getAppChecksum());
861  res.integrity_hash.clear();
862  std::vector<uint32_t> integrity_hash = config_metadata.getIntegrityHash();
863  for (const auto& hash : integrity_hash)
864  {
865  res.integrity_hash.push_back(hash);
866  }
867  res.modification_time_date = config_metadata.getModificationTimeDate();
868  res.modification_time_time = config_metadata.getModificationTimeTime();
869  res.modification_time = getDateString(res.modification_time_date, res.modification_time_time);
870  res.overall_checksum = getCheckSumString(config_metadata.getOverallChecksum());
871  res.transfer_time_date = config_metadata.getModificationTimeDate();
872  res.transfer_time_time = config_metadata.getModificationTimeTime();
873  res.transfer_time = getDateString(res.transfer_time_date, res.transfer_time_time);
874  res.version_c_version = config_metadata.getVersionCVersion();
875  res.version_major_version_number = config_metadata.getVersionMajorVersionNumber();
876  res.version_minor_version_number = config_metadata.getVersionMinorVersionNumber();
877  res.version_release_number = config_metadata.getVersionReleaseNumber();
878 
879  return true;
880 }
881 
882 bool SickSafetyscannersRos::getStatusOverview(sick_safetyscanners::StatusOverview::Request& req,
883  sick_safetyscanners::StatusOverview::Response& res)
884 {
885  static_cast<void>(req);
886 
887  sick::datastructure::StatusOverview status_overview;
888  m_device->requestStatusOverview(m_communication_settings, status_overview);
889 
890  res.version_c_version = status_overview.getVersionCVersion();
891  res.version_major_version_number = status_overview.getVersionMajorVersionNumber();
892  res.version_minor_version_number = status_overview.getVersionMinorVersionNumber();
893  res.version_release_number = status_overview.getVersionReleaseNumber();
894 
895  res.device_state = status_overview.getDeviceState();
896  res.config_state = status_overview.getConfigState();
897  res.application_state = status_overview.getApplicationState();
898  res.current_time_power_on_count = status_overview.getCurrentTimePowerOnCount();
899 
900  res.current_time_date = status_overview.getCurrentTimeDate();
901  res.current_time_time = status_overview.getCurrentTimeTime();
902  res.current_time = getDateString(res.current_time_date, res.current_time_time);
903 
904  res.error_info_code = status_overview.getErrorInfoCode();
905 
906  res.error_info_time_date = status_overview.getErrorInfoDate();
907  res.error_info_time_time = status_overview.getErrorInfoTime();
908  res.error_info_time = getDateString(res.error_info_time_date, res.error_info_time_time);
909 
910  return true;
911 }
912 
913 std::string SickSafetyscannersRos::getCheckSumString(uint32_t checksum)
914 {
915  std::stringstream ss;
916  ss << "0x" << std::hex << (checksum & 0xFF) << ((checksum & 0xFF00) >> 8)
917  << ((checksum & 0xFF0000) >> 16) << ((checksum & 0xFF000000) >> 24);
918  return ss.str();
919 }
920 
921 std::string SickSafetyscannersRos::getDateString(uint32_t days_since_1972, uint32_t milli_seconds)
922 {
923  std::time_t t = static_cast<std::time_t>((730 /* = days from Jan 1 1970 to Jan 1 1972*/
924  + days_since_1972) *
925  24 * 3600 +
926  milli_seconds * 0.001);
927  char buffer[40];
928  std::string retval;
929  strftime(buffer, 40, "%F %X", gmtime(&t));
930  retval = buffer;
931  return retval;
932 }
933 
934 
935 } // namespace sick
sick::datastructure::ApplicationOutputs::getSleepModeOutput
int8_t getSleepModeOutput() const
Gets the state of the sleep mode.
Definition: ApplicationOutputs.cpp:94
sick::datastructure::MonitoringCaseData::getFieldsValid
std::vector< bool > getFieldsValid() const
Returns if the fields are configured and valid.
Definition: MonitoringCaseData.cpp:72
sick::datastructure::ApplicationOutputs::getVelocity0Valid
bool getVelocity0Valid() const
Gets if the first linear velocity output is valid.
Definition: ApplicationOutputs.cpp:187
sick::SickSafetyscannersRos::m_frame_id
std::string m_frame_id
Definition: SickSafetyscannersRos.h:160
sick::datastructure::StatusOverview::getApplicationState
uint8_t getApplicationState() const
Gets the application state for the scanner.
Definition: StatusOverview.cpp:102
sick::SickSafetyscannersRos::m_nh
ros::NodeHandle m_nh
ROS node handle.
Definition: SickSafetyscannersRos.h:127
sick::datastructure::ConfigData::getStartAngle
float getStartAngle() const
Gets the start angle of the scan.
Definition: ConfigData.cpp:171
SickSafetyscannersRos.h
sick::datastructure::StatusOverview::getVersionCVersion
std::string getVersionCVersion() const
Gets the version indicator for the scanner.
Definition: StatusOverview.cpp:42
sick::SickSafetyscannersRos::createGeneralSystemStateMessage
sick_safetyscanners::GeneralSystemStateMsg createGeneralSystemStateMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:569
msg
msg
sick::datastructure::CommSettings::setHostIp
void setHostIp(const boost::asio::ip::address_v4 &host_ip)
Sets the IP-address of the host from an IP-address.
Definition: CommSettings.cpp:47
DurationBase< Duration >::fromSec
Duration & fromSec(double t)
sick::datastructure::StatusOverview::getVersionMinorVersionNumber
uint8_t getVersionMinorVersionNumber() const
Gets the minor version number for the scanner.
Definition: StatusOverview.cpp:62
sick::datastructure::ApplicationOutputs::getEvalOutIsSafeVector
std::vector< bool > getEvalOutIsSafeVector() const
Gets if a cut-off path from the output paths is safe.
Definition: ApplicationOutputs.cpp:52
sick::SickSafetyscannersRos::createMeasurementDataMessage
sick_safetyscanners::MeasurementDataMsg createMeasurementDataMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:620
sick::datastructure::TypeCode::getInterfaceType
uint8_t getInterfaceType() const
Gets the interface type for the scanner.
Definition: TypeCode.cpp:51
sick::datastructure::ApplicationOutputs::getVelocity0
int16_t getVelocity0() const
Gets the first linear velocity output.
Definition: ApplicationOutputs.cpp:167
sick::datastructure::ConfigMetadata::getAppChecksum
uint32_t getAppChecksum() const
Gets the application checksum for the scanner.
Definition: ConfigMetadata.cpp:122
sick::SickSafetyscannersRos::createScanPointMessageVector
std::vector< sick_safetyscanners::ScanPointMsg > createScanPointMessageVector(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:633
sick::datastructure::ApplicationOutputs::getResultingVelocityVector
std::vector< int16_t > getResultingVelocityVector() const
Gets the resulting velocity for each monitoring case table.
Definition: ApplicationOutputs.cpp:227
sick::datastructure::ApplicationInputs::getMonitoringCasevector
std::vector< uint16_t > getMonitoringCasevector() const
Gets the monitoring case numbers.
Definition: ApplicationInputs.cpp:64
sick::datastructure::ConfigMetadata
Class containing the serial number of a laser scanner.
Definition: ConfigMetadata.h:48
sick::datastructure::IntrusionDatum::getSize
int32_t getSize() const
Returns size of flag vector.
Definition: IntrusionDatum.cpp:43
sick::SickSafetyscannersRos::m_min_intensities
double m_min_intensities
Definition: SickSafetyscannersRos.h:168
sick::datastructure::ConfigMetadata::getVersionMinorVersionNumber
uint8_t getVersionMinorVersionNumber() const
Gets the minor version number for the scanner.
Definition: ConfigMetadata.cpp:62
sick::SickSafetyscannersRos::SickSafetyscannersRos
SickSafetyscannersRos()
Constructor of the SickSafetyscannersRos.
Definition: SickSafetyscannersRos.cpp:41
diagnostic_updater::TimeStampStatusParam
sick::SickSafetyscannersRos::m_config_metadata_server
ros::ServiceServer m_config_metadata_server
Definition: SickSafetyscannersRos.h:147
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
sick
Definition: ApplicationNameVariableCommand.h:43
sick::datastructure::FieldData
Field data for warning and protective fields.
Definition: FieldData.h:48
sick::datastructure::ConfigMetadata::getModificationTimeDate
uint16_t getModificationTimeDate() const
Gets the modification time date for the scanner.
Definition: ConfigMetadata.cpp:82
sick::SickSafetyscannersRos::m_field_service_server
ros::ServiceServer m_field_service_server
Definition: SickSafetyscannersRos.h:146
sick::boolToString
std::string boolToString(bool b)
Definition: SickSafetyscannersRos.cpp:293
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
sick::datastructure::ApplicationOutputs::getResultingVelocityIsValidVector
std::vector< bool > getResultingVelocityIsValidVector() const
Gets if the resulting velocities are valid.
Definition: ApplicationOutputs.cpp:238
sick::datastructure::ScanPoint::getContaminationBit
bool getContaminationBit() const
Returns if the scanpoint is contaminated.
Definition: ScanPoint.cpp:98
sick::datastructure::CommSettings::setHostUdpPort
void setHostUdpPort(const uint16_t &host_udp_port)
Sets the host udp port.
Definition: CommSettings.cpp:62
sick::datastructure::ApplicationOutputs::getHostErrorFlagContaminationWarning
bool getHostErrorFlagContaminationWarning() const
Gets if a contamination warning is present.
Definition: ApplicationOutputs.cpp:104
sick::SickSafetyscannersRos::createApplicationDataMessage
sick_safetyscanners::ApplicationDataMsg createApplicationDataMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:698
sick::datastructure::ScanPoint::getDistance
uint16_t getDistance() const
Getter for the distance of the scanpoint.
Definition: ScanPoint.cpp:68
sick::datastructure::ApplicationInputs::getVelocity0Valid
bool getVelocity0Valid() const
Gets if first linear velocity input is valid.
Definition: ApplicationInputs.cpp:105
sick::SickSafetyscannersRos::m_diagnostic_updater
diagnostic_updater::Updater m_diagnostic_updater
Definition: SickSafetyscannersRos.h:139
sick::datastructure::ScanPoint::getAngle
float getAngle() const
Getter for the angle in sensor coordinates.
Definition: ScanPoint.cpp:63
sick::datastructure::DeviceName
Class containing the device name of a laser scanner.
Definition: DeviceName.h:47
sick::datastructure::ApplicationInputs::getVelocity1
int16_t getVelocity1() const
Gets the second linear velocity input.
Definition: ApplicationInputs.cpp:95
sick::SickSafetyscannersRos::createDataHeaderMessage
sick_safetyscanners::DataHeaderMsg createDataHeaderMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:522
sick::SickSafetyscannersRos::m_dynamic_reconfiguration_server
dynamic_reconfigure::Server< sick_safetyscanners::SickSafetyscannersConfigurationConfig > m_dynamic_reconfiguration_server
Definition: SickSafetyscannersRos.h:158
sick::datastructure::CommSettings::setFeatures
void setFeatures(const uint16_t &features)
Set the enabled features.
Definition: CommSettings.cpp:132
sick::datastructure::ApplicationInputs::getUnsafeInputsInputSourcesVector
std::vector< bool > getUnsafeInputsInputSourcesVector() const
Gets the unsafe input sources.
Definition: ApplicationInputs.cpp:42
sick::datastructure::ScanPoint::getReflectorBit
bool getReflectorBit() const
Returns if the scanpoint detects a reflector.
Definition: ScanPoint.cpp:93
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
sick::datastructure::ApplicationOutputs::getVelocity1Valid
bool getVelocity1Valid() const
Gets if the second linear velocity output is valid.
Definition: ApplicationOutputs.cpp:197
sick::datastructure::Data
The data class containing all data blocks of a measurement.
Definition: Data.h:55
sick::datastructure::ApplicationInputs::getUnsafeInputsFlagsVector
std::vector< bool > getUnsafeInputsFlagsVector() const
Gets the flags for the unsafe input sources.
Definition: ApplicationInputs.cpp:53
sick::SickSafetyscannersRos::reconfigureCallback
void reconfigureCallback(const sick_safetyscanners::SickSafetyscannersConfigurationConfig &config, const uint32_t &level)
Function which is triggered when a dynamic reconfiguration is performed.
Definition: SickSafetyscannersRos.cpp:125
sick::SickSafetyscannersRos::m_use_pers_conf
bool m_use_pers_conf
Definition: SickSafetyscannersRos.h:172
sick::datastructure::FieldData::getAngularBeamResolution
float getAngularBeamResolution() const
Returns the angular resolution between the beams.
Definition: FieldData.cpp:223
sick::SickSafetyscannersRos::createDerivedValuesMessage
sick_safetyscanners::DerivedValuesMsg createDerivedValuesMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:550
sick::SickSafetyscannersRos::createIntrusionDatumMessageVector
std::vector< sick_safetyscanners::IntrusionDatumMsg > createIntrusionDatumMessageVector(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:674
sick::datastructure::CommSettings::setEInterfaceType
void setEInterfaceType(const uint8_t &e_interface_type)
Sets the eInterface type.
Definition: CommSettings.cpp:92
sick::SickSafetyscannersRos::m_diagnosed_laser_scan_publisher
std::shared_ptr< DiagnosedLaserScanPublisher > m_diagnosed_laser_scan_publisher
Definition: SickSafetyscannersRos.h:140
sick::datastructure::ApplicationOutputs::getVelocity1TransmittedSafely
bool getVelocity1TransmittedSafely() const
Gets if the second linear velocity output is transmitted safely.
Definition: ApplicationOutputs.cpp:217
sick::datastructure::ApplicationInputs::getVelocity1Valid
bool getVelocity1Valid() const
Gets if second linear velocity input is valid.
Definition: ApplicationInputs.cpp:115
sick::datastructure::IntrusionDatum
Class containing a single IntrusionDatum.
Definition: IntrusionDatum.h:47
sick::datastructure::StatusOverview::getErrorInfoTime
uint32_t getErrorInfoTime() const
Gets the error info time for the scanner.
Definition: StatusOverview.cpp:152
sick::datastructure::ApplicationOutputs::getHostErrorFlagContaminationError
bool getHostErrorFlagContaminationError() const
Gets if a contamination error is present.
Definition: ApplicationOutputs.cpp:115
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::requestShutdown
ROSCPP_DECL void requestShutdown()
sick::SickSafetyscannersRos::firmware_version
sick::datastructure::FirmwareVersion firmware_version
Definition: SickSafetyscannersRos.h:143
sick::datastructure::ApplicationOutputs::getEvalOutVector
std::vector< bool > getEvalOutVector() const
Gets the state of the non safe cut-off paths.
Definition: ApplicationOutputs.cpp:42
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
data
data
sick::skipToPublishFrequency
uint16_t skipToPublishFrequency(int skip)
Converts a skip value into a "publish frequency" value.
Definition: SickSafetyscannersRos.h:95
sick::datastructure::StatusOverview::getDeviceState
uint8_t getDeviceState() const
Gets the device state for the scanner.
Definition: StatusOverview.cpp:82
sick::datastructure::CommSettings::setPublishingFrequency
void setPublishingFrequency(const uint16_t &publishing_frequency)
Sets the publishing frequency.
Definition: CommSettings.cpp:102
sick::datastructure::StatusOverview::getCurrentTimeTime
uint32_t getCurrentTimeTime() const
Gets the current time time for the scanner.
Definition: StatusOverview.cpp:122
sick::datastructure::ConfigData::getEndAngle
float getEndAngle() const
Gets the end angle of the scan.
Definition: ConfigData.cpp:186
sick::SickSafetyscannersRos::createRawDataMessage
sick_safetyscanners::RawMicroScanDataMsg createRawDataMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:507
sick::datastructure::MonitoringCaseData::getFieldIndices
std::vector< uint16_t > getFieldIndices() const
Returns the field indices.
Definition: MonitoringCaseData.cpp:62
sick::datastructure::ApplicationOutputs::getHostErrorFlagManipulationError
bool getHostErrorFlagManipulationError() const
Gets if a manipulation error is present.
Definition: ApplicationOutputs.cpp:126
sick::SickSafetyscannersRos::m_laser_scan_publisher
ros::Publisher m_laser_scan_publisher
ROS topic publisher.
Definition: SickSafetyscannersRos.h:133
sick::SickSafetyscannersRos::m_private_nh
ros::NodeHandle m_private_nh
ROS private node handle.
Definition: SickSafetyscannersRos.h:130
sick::SickSafetyscannersRos::getFieldData
bool getFieldData(sick_safetyscanners::FieldData::Request &req, sick_safetyscanners::FieldData::Response &res)
Definition: SickSafetyscannersRos.cpp:802
sick::SickSafetyscannersRos::m_time_offset
double m_time_offset
Definition: SickSafetyscannersRos.h:161
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
sick::SickSafetyscannersRos::m_output_path_publisher
ros::Publisher m_output_path_publisher
Definition: SickSafetyscannersRos.h:136
sick::SickSafetyscannersRos::getMedianReflectors
std::vector< bool > getMedianReflectors(const std::vector< sick::datastructure::ScanPoint > scan_points)
Definition: SickSafetyscannersRos.cpp:392
sick::datastructure::ApplicationOutputs::getVelocity1
int16_t getVelocity1() const
Gets the second linear velocity output.
Definition: ApplicationOutputs.cpp:177
sick::SickSafetyscannersRos::m_status_overview_server
ros::ServiceServer m_status_overview_server
Definition: SickSafetyscannersRos.h:148
sick::SickSafetyscannersRos::m_frequency_tolerance
double m_frequency_tolerance
Definition: SickSafetyscannersRos.h:164
sick::datastructure::ScanPoint
Class containing the data of a single scan point.
Definition: ScanPoint.h:46
sick::datastructure::ApplicationOutputs::getMonitoringCaseVector
std::vector< uint16_t > getMonitoringCaseVector() const
Gets the currently active monitoring case numbers.
Definition: ApplicationOutputs.cpp:72
sick::SickSafetyscannersRos::sensorDiagnostics
void sensorDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &diagnostic_status)
Definition: SickSafetyscannersRos.cpp:298
sick::datastructure::ApplicationOutputs::getVelocity0TransmittedSafely
bool getVelocity0TransmittedSafely() const
Gets if the first linear velocity output is transmitted safely.
Definition: ApplicationOutputs.cpp:207
sick::datastructure::ApplicationOutputs::getHostErrorFlagCriticalError
bool getHostErrorFlagCriticalError() const
Gets if a critical error is present.
Definition: ApplicationOutputs.cpp:157
sick::datastructure::ScanPoint::getReflectivity
uint8_t getReflectivity() const
Getter for the reflectivity value.
Definition: ScanPoint.cpp:73
sick::SickSafetyscannersRos::m_communication_settings
sick::datastructure::CommSettings m_communication_settings
Definition: SickSafetyscannersRos.h:154
sick::SickSafetyscannersRos::isInitialised
bool isInitialised()
Definition: SickSafetyscannersRos.cpp:159
sick::SickSafetyscannersRos::createExtendedLaserScanMessage
sick_safetyscanners::ExtendedLaserScanMsg createExtendedLaserScanMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:367
sick::degToRad
float degToRad(float deg)
Converts degrees to radians.
Definition: SickSafetyscannersRos.h:73
sick::datastructure::StatusOverview
Class containing the serial number of a laser scanner.
Definition: StatusOverview.h:47
sick::radToDeg
float radToDeg(float rad)
Converts radians to degrees.
Definition: SickSafetyscannersRos.h:83
sick::datastructure::ApplicationInputs::getSleepModeInput
int8_t getSleepModeInput() const
Gets the state of the sleep mode.
Definition: ApplicationInputs.cpp:145
sick::SickSafetyscannersRos::m_raw_data_publisher
ros::Publisher m_raw_data_publisher
Definition: SickSafetyscannersRos.h:135
sick::datastructure::FieldData::getBeamDistances
std::vector< uint16_t > getBeamDistances() const
Returns vector with beam distances.
Definition: FieldData.cpp:183
sick::datastructure::ApplicationOutputs::getEvalOutIsValidVector
std::vector< bool > getEvalOutIsValidVector() const
If the output path is valid.
Definition: ApplicationOutputs.cpp:62
sick::datastructure::CommSettings::setSensorIp
void setSensorIp(const boost::asio::ip::address_v4 &sensor_ip)
Sets the sensor IP-address.
Definition: CommSettings.cpp:156
ROS_WARN
#define ROS_WARN(...)
sick::SickSafetyscannersRos::m_device
std::shared_ptr< sick::SickSafetyscanners > m_device
Definition: SickSafetyscannersRos.h:152
sick::datastructure::ApplicationOutputs
The application outputs from a udp data packet.
Definition: ApplicationOutputs.h:48
sick::datastructure::ApplicationInputs
The applications inputs from a udp data packet.
Definition: ApplicationInputs.h:47
sick::datastructure::ApplicationOutputs::getFlagsSleepModeOutputIsValid
bool getFlagsSleepModeOutputIsValid() const
Gets if the sleep mode is valid.
Definition: ApplicationOutputs.cpp:249
sick::SickSafetyscannersRos::getConfigMetadata
bool getConfigMetadata(sick_safetyscanners::ConfigMetadata::Request &req, sick_safetyscanners::ConfigMetadata::Response &res)
Definition: SickSafetyscannersRos.cpp:853
sick::SickSafetyscannersRos::createIntrusionDataMessage
sick_safetyscanners::IntrusionDataMsg createIntrusionDataMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:662
sick::datastructure::ScanPoint::getGlareBit
bool getGlareBit() const
Returns if the scanpoint has glare.
Definition: ScanPoint.cpp:88
sick::datastructure::CommSettings::setStartAngle
void setStartAngle(const int32_t &start_angle)
Sets the start angle of the scan.
Definition: CommSettings.cpp:112
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
sick::datastructure::StatusOverview::getErrorInfoDate
uint16_t getErrorInfoDate() const
Gets the error info date for the scanner.
Definition: StatusOverview.cpp:162
sick::datastructure::ApplicationInputs::getMonitoringCaseFlagsVector
std::vector< bool > getMonitoringCaseFlagsVector() const
Gets the monitoring case flags.
Definition: ApplicationInputs.cpp:74
sick::SickSafetyscannersRos::receivedUDPPacket
void receivedUDPPacket(const datastructure::Data &data)
Function which is called when a new complete UDP Packet is received.
Definition: SickSafetyscannersRos.cpp:267
sick::SickSafetyscannersRos::m_timestamp_max_acceptable
double m_timestamp_max_acceptable
Definition: SickSafetyscannersRos.h:167
sick::DiagnosedLaserScanPublisher
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > DiagnosedLaserScanPublisher
Definition: SickSafetyscannersRos.h:100
sick::datastructure::ApplicationOutputs::getHostErrorFlagGlare
bool getHostErrorFlagGlare() const
Gets if glare is present.
Definition: ApplicationOutputs.cpp:136
sick::SickSafetyscannersRos::m_range_max
double m_range_max
Definition: SickSafetyscannersRos.h:163
sick::SickSafetyscannersRos::createApplicationInputsMessage
sick_safetyscanners::ApplicationInputsMsg createApplicationInputsMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:711
sick::datastructure::ConfigMetadata::getVersionReleaseNumber
uint8_t getVersionReleaseNumber() const
Gets the version release number for the scanner.
Definition: ConfigMetadata.cpp:72
sick::SickSafetyscannersRos::createOutputPathsMessage
sick_safetyscanners::OutputPathsMsg createOutputPathsMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:473
start
ROSCPP_DECL void start()
diagnostic_updater::Updater::update
void update()
sick::datastructure::StatusOverview::getConfigState
uint8_t getConfigState() const
Gets the config state for the scanner.
Definition: StatusOverview.cpp:92
sick::datastructure::CommSettings::setEnabled
void setEnabled(bool enabled)
Sets if the channel is enabled.
Definition: CommSettings.cpp:82
sick::datastructure::FieldData::getStartAngle
float getStartAngle() const
Get the start angle of the scan.
Definition: FieldData.cpp:193
sick::SickSafetyscannersRos::m_expected_frequency
double m_expected_frequency
Definition: SickSafetyscannersRos.h:165
sick::datastructure::TypeCode::getMaxRange
float getMaxRange() const
Gets the max range for the scanner.
Definition: TypeCode.cpp:61
sick::SickSafetyscannersRos::createLaserScanMessage
sensor_msgs::LaserScan createLaserScanMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:418
sick::SickSafetyscannersRos::m_angle_offset
float m_angle_offset
Definition: SickSafetyscannersRos.h:171
sick::SickSafetyscannersRos::m_extended_laser_scan_publisher
ros::Publisher m_extended_laser_scan_publisher
Definition: SickSafetyscannersRos.h:134
sick::SickSafetyscannersRos::getStatusOverview
bool getStatusOverview(sick_safetyscanners::StatusOverview::Request &req, sick_safetyscanners::StatusOverview::Response &res)
Definition: SickSafetyscannersRos.cpp:882
sick::SickSafetyscannersRos::config_meta_data
sick::datastructure::ConfigMetadata config_meta_data
Definition: SickSafetyscannersRos.h:142
sick::datastructure::CommSettings::setChannel
void setChannel(const uint8_t &channel)
Sets the channel of the data.
Definition: CommSettings.cpp:72
sick::datastructure::StatusOverview::getCurrentTimePowerOnCount
uint32_t getCurrentTimePowerOnCount() const
Gets the current time power on count for the scanner.
Definition: StatusOverview.cpp:112
sick::SickSafetyscannersRos::m_last_raw_data
sick_safetyscanners::RawMicroScanDataMsg m_last_raw_data
Definition: SickSafetyscannersRos.h:141
sick::datastructure::ApplicationOutputs::getHostErrorFlagReferenceContourIntruded
bool getHostErrorFlagReferenceContourIntruded() const
Gets if a reference contour is intruded.
Definition: ApplicationOutputs.cpp:146
sick::SickSafetyscannersRos::readTypeCodeSettings
void readTypeCodeSettings()
Definition: SickSafetyscannersRos.cpp:106
sick::SickSafetyscannersRos::m_timestamp_min_acceptable
double m_timestamp_min_acceptable
Definition: SickSafetyscannersRos.h:166
sick::datastructure::ConfigData
Config data for current and persistent sensor config.
Definition: ConfigData.h:50
ROS_ERROR
#define ROS_ERROR(...)
sick::datastructure::StatusOverview::getCurrentTimeDate
uint16_t getCurrentTimeDate() const
Gets the current time date for the scanner.
Definition: StatusOverview.cpp:132
sick::SickSafetyscannersRos::m_initialised
bool m_initialised
Definition: SickSafetyscannersRos.h:150
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
sick::datastructure::StatusOverview::getVersionReleaseNumber
uint8_t getVersionReleaseNumber() const
Gets the version release number for the scanner.
Definition: StatusOverview.cpp:72
sick::datastructure::ApplicationInputs::getVelocity1TransmittedSafely
bool getVelocity1TransmittedSafely() const
Gets if second linear velocity input is transmitted safely.
Definition: ApplicationInputs.cpp:135
sick::datastructure::IntrusionDatum::getFlagsVector
std::vector< bool > getFlagsVector() const
Getter for the flags vector.
Definition: IntrusionDatum.cpp:53
sick::datastructure::CommSettings::setSensorTcpPort
void setSensorTcpPort(const uint16_t &sensor_tcp_port)
Sets the sensor tcp port.
Definition: CommSettings.cpp:171
sick::SickSafetyscannersRos::m_range_min
double m_range_min
Definition: SickSafetyscannersRos.h:162
diagnostic_updater::DiagnosticStatusWrapper
sick::datastructure::MonitoringCaseData
Stores the data for the different monitoring cases.
Definition: MonitoringCaseData.h:48
sick::datastructure::ApplicationOutputs::getMonitoringCaseFlagsVector
std::vector< bool > getMonitoringCaseFlagsVector() const
Gets if the corresponding monitoring case number is valid.
Definition: ApplicationOutputs.cpp:83
sick::datastructure::ScanPoint::getInfiniteBit
bool getInfiniteBit() const
Returns if the scanpoint is infinite.
Definition: ScanPoint.cpp:83
sick::SickSafetyscannersRos::m_interface_ip
boost::asio::ip::address_v4 m_interface_ip
Definition: SickSafetyscannersRos.h:155
sick::SickSafetyscannersRos::createApplicationOutputsMessage
sick_safetyscanners::ApplicationOutputsMsg createApplicationOutputsMessage(const sick::datastructure::Data &data)
Definition: SickSafetyscannersRos.cpp:744
sick::datastructure::TypeCode
Class containing the type code of a laser scanner.
Definition: TypeCode.h:62
sick::datastructure::CommSettings::setEndAngle
void setEndAngle(const int32_t &end_angle)
Sets the end angle of the scan.
Definition: CommSettings.cpp:122
sick::datastructure::ConfigMetadata::getIntegrityHash
std::vector< uint32_t > getIntegrityHash() const
Gets the integrity hash for the scanner.
Definition: ConfigMetadata.cpp:142
sick::datastructure::StatusOverview::getErrorInfoCode
uint32_t getErrorInfoCode() const
Gets the error info code for the scanner.
Definition: StatusOverview.cpp:142
header
const std::string header
sick::datastructure::ConfigMetadata::getVersionCVersion
std::string getVersionCVersion() const
Gets the version indicator for the scanner.
Definition: ConfigMetadata.cpp:42
sick::datastructure::ConfigMetadata::getVersionMajorVersionNumber
uint8_t getVersionMajorVersionNumber() const
Gets the major version number for the scanner.
Definition: ConfigMetadata.cpp:52
sick::datastructure::ApplicationOutputs::getFlagsHostErrorFlagsAreValid
bool getFlagsHostErrorFlagsAreValid() const
Gets if the error flags are valid.
Definition: ApplicationOutputs.cpp:259
sick::datastructure::ApplicationInputs::getVelocity0
int16_t getVelocity0() const
Gets the first linear velocity input.
Definition: ApplicationInputs.cpp:85
sick::SickSafetyscannersRos::~SickSafetyscannersRos
virtual ~SickSafetyscannersRos()
~SickSafetyscannersRos Destructor if the SickSafetyscanners ROS
Definition: SickSafetyscannersRos.cpp:165
ROS_INFO
#define ROS_INFO(...)
sick::datastructure::ScanPoint::getContaminationWarningBit
bool getContaminationWarningBit() const
Returns if there is a contamination warning.
Definition: ScanPoint.cpp:103
sick::datastructure::StatusOverview::getVersionMajorVersionNumber
uint8_t getVersionMajorVersionNumber() const
Gets the major version number for the scanner.
Definition: StatusOverview.cpp:52
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
sick::datastructure::ConfigMetadata::getModificationTimeTime
uint32_t getModificationTimeTime() const
Gets the modification time time for the scanner.
Definition: ConfigMetadata.cpp:92
sick::datastructure::FieldData::getIsProtectiveField
bool getIsProtectiveField() const
Returns if a field is a protective field.
Definition: FieldData.cpp:173
ros::Duration
sick::datastructure::ApplicationInputs::getVelocity0TransmittedSafely
bool getVelocity0TransmittedSafely() const
Gets if first linear velocity input is transmitted safely.
Definition: ApplicationInputs.cpp:125
sick::datastructure::CommSettings::getSensorIp
boost::asio::ip::address_v4 getSensorIp() const
Gets the sensor IP-address.
Definition: CommSettings.cpp:151
sick::datastructure::ConfigMetadata::getOverallChecksum
uint32_t getOverallChecksum() const
Gets the overall checksum for the scanner.
Definition: ConfigMetadata.cpp:132
sick::SickSafetyscannersRos::getDateString
std::string getDateString(uint32_t days_since_1972, uint32_t milli_seconds)
getDateString converts the date representation received as days since 1972-01-01 and milliseconds sin...
Definition: SickSafetyscannersRos.cpp:921
sick::SickSafetyscannersRos::readPersistentConfig
void readPersistentConfig()
Definition: SickSafetyscannersRos.cpp:116
sick::datastructure::MonitoringCaseData::getMonitoringCaseNumber
uint16_t getMonitoringCaseNumber() const
Returns the number of the monitoring case.
Definition: MonitoringCaseData.cpp:52
sick::SickSafetyscannersRos::getCheckSumString
std::string getCheckSumString(uint32_t checksum)
getCheckSumString converts the uint32 value received as checksum such that the hexadecimal representa...
Definition: SickSafetyscannersRos.cpp:913
sick::datastructure::ScanPoint::getValidBit
bool getValidBit() const
Returns if the scanpoint is valid.
Definition: ScanPoint.cpp:78
ros::Time::now
static Time now()
sick::datastructure::FirmwareVersion::getFirmwareVersion
std::string getFirmwareVersion() const
Gets the firmware version for the scanner.
Definition: FirmwareVersion.cpp:42
diagnostic_updater::FrequencyStatusParam
sick::datastructure::DeviceName::getDeviceName
std::string getDeviceName() const
Gets the device name for the scanner.
Definition: DeviceName.cpp:42
sick::SickSafetyscannersRos::readParameters
bool readParameters()
Reads and verifies the ROS parameters.
Definition: SickSafetyscannersRos.cpp:167


sick_safetyscanners
Author(s): Lennart Puck
autogenerated on Fri Jun 21 2024 02:40:51