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_nh()
43  , m_private_nh("~")
44  , m_initialised(false)
45  , m_time_offset(0.0)
46  , m_range_min(0.0)
47  , m_range_max(0.0)
48  , m_angle_offset(-90.0)
49  , m_use_pers_conf(false)
50 {
51  dynamic_reconfigure::Server<
52  sick_safetyscanners::SickSafetyscannersConfigurationConfig>::CallbackType reconf_callback =
53  boost::bind(&SickSafetyscannersRos::reconfigure_callback, this, _1, _2);
54  m_dynamic_reconfiguration_server.setCallback(reconf_callback);
55  if (!readParameters())
56  {
57  ROS_ERROR("Could not read parameters.");
59  }
60  // tcp port can not be changed in the sensor configuration, therefore it is hardcoded
62  m_laser_scan_publisher = m_nh.advertise<sensor_msgs::LaserScan>("scan", 100);
64  m_nh.advertise<sick_safetyscanners::ExtendedLaserScanMsg>("extended_laser_scan", 100);
65  m_raw_data_publisher = m_nh.advertise<sick_safetyscanners::RawMicroScanDataMsg>("raw_data", 100);
67  m_nh.advertise<sick_safetyscanners::OutputPathsMsg>("output_paths", 100);
70 
71  m_device = std::make_shared<sick::SickSafetyscanners>(
73  m_device->run();
75 
76  if (m_use_pers_conf)
77  {
79  }
80 
81  m_device->changeSensorSettings(m_communication_settings);
82  m_initialised = true;
83  ROS_INFO("Successfully launched node.");
84 }
85 
87 {
88  ROS_INFO("Reading Type code settings");
90  m_device->requestTypeCode(m_communication_settings, type_code);
92  m_range_min = 0.1;
93  m_range_max = type_code.getMaxRange();
94 }
95 
97 {
98  ROS_INFO("Reading Persistent Configuration");
100  m_device->requestPersistentConfig(m_communication_settings, config_data);
103 }
104 
106  const sick_safetyscanners::SickSafetyscannersConfigurationConfig& config, const uint32_t& level)
107 {
108  if (isInitialised())
109  {
110  m_communication_settings.setEnabled(config.channel_enabled);
112  if (config.angle_start == config.angle_end)
113  {
116  }
117  else
118  {
121  }
122  m_communication_settings.setFeatures(config.general_system_state,
123  config.derived_settings,
124  config.measurement_data,
125  config.intrusion_data,
126  config.application_io_data);
127  m_device->changeSensorSettings(m_communication_settings);
128 
129  m_frame_id = config.frame_id;
130 
131  m_time_offset = config.time_offset;
132  }
133 }
134 
136 {
137  return m_initialised;
138 }
139 
140 
142 
144 {
145  std::string sensor_ip_adress = "192.168.1.10";
146  if (!m_private_nh.getParam("sensor_ip", sensor_ip_adress))
147  {
148  // sensor_ip_adress = sick_safetyscanners::SickSafetyscannersConfiguration_sensor_ip;
149  ROS_WARN("Using default sensor IP: %s", sensor_ip_adress.c_str());
150  }
151  m_communication_settings.setSensorIp(sensor_ip_adress);
152 
153 
154  std::string host_ip_adress = "192.168.1.9";
155  if (!m_private_nh.getParam("host_ip", host_ip_adress))
156  {
157  ROS_WARN("Using default host IP: %s", host_ip_adress.c_str());
158  }
159  m_communication_settings.setHostIp(host_ip_adress);
160 
161  int host_udp_port = 0;
162  if (!m_private_nh.getParam("host_udp_port", host_udp_port))
163  {
164  ROS_WARN("Using default host UDP Port: %i", host_udp_port);
165  }
167 
168  ROS_WARN("If not further specified the default values for the dynamic reconfigurable parameters "
169  "will be loaded.");
170 
171 
172  int channel = 0;
173  m_private_nh.getParam("channel", channel);
175 
176  bool enabled;
177  m_private_nh.getParam("channel_enabled", enabled);
179 
180  int skip;
181  m_private_nh.getParam("skip", skip);
183 
184  float angle_start;
185  m_private_nh.getParam("angle_start", angle_start);
186 
187  float angle_end;
188  m_private_nh.getParam("angle_end", angle_end);
189 
190  // Included check before calculations to prevent rounding errors while calculating
191  if (angle_start == angle_end)
192  {
195  }
196  else
197  {
200  }
201 
202  bool general_system_state;
203  m_private_nh.getParam("general_system_state", general_system_state);
204 
205  bool derived_settings;
206  m_private_nh.getParam("derived_settings", derived_settings);
207 
208  bool measurement_data;
209  m_private_nh.getParam("measurement_data", measurement_data);
210 
211  bool intrusion_data;
212  m_private_nh.getParam("intrusion_data", intrusion_data);
213 
214  bool application_io_data;
215  m_private_nh.getParam("application_io_data", application_io_data);
216 
218  general_system_state, derived_settings, measurement_data, intrusion_data, application_io_data);
219 
220  m_private_nh.getParam("frame_id", m_frame_id);
221 
222  m_private_nh.getParam("use_persistent_config", m_use_pers_conf);
223 
224  return true;
225 }
226 
228 {
229  if (!data.getMeasurementDataPtr()->isEmpty() && !data.getDerivedValuesPtr()->isEmpty())
230  {
231  sensor_msgs::LaserScan scan = createLaserScanMessage(data);
232 
234  }
235 
236 
237  if (!data.getMeasurementDataPtr()->isEmpty() && !data.getDerivedValuesPtr()->isEmpty())
238  {
239  sick_safetyscanners::ExtendedLaserScanMsg extended_scan = createExtendedLaserScanMessage(data);
240 
242 
243  sick_safetyscanners::OutputPathsMsg output_paths = createOutputPathsMessage(data);
244  m_output_path_publisher.publish(output_paths);
245  }
246 
247  sick_safetyscanners::RawMicroScanDataMsg raw_data = createRawDataMessage(data);
248 
249  m_raw_data_publisher.publish(raw_data);
250 }
251 
252 sick_safetyscanners::ExtendedLaserScanMsg
254 {
255  sensor_msgs::LaserScan scan = createLaserScanMessage(data);
256  sick_safetyscanners::ExtendedLaserScanMsg msg;
257  msg.laser_scan = scan;
258 
259  uint16_t num_scan_points = data.getDerivedValuesPtr()->getNumberOfBeams();
260  std::vector<sick::datastructure::ScanPoint> scan_points =
261  data.getMeasurementDataPtr()->getScanPointsVector();
262 
263  msg.reflektor_status.resize(num_scan_points);
264  msg.intrusion.resize(num_scan_points);
265  msg.reflektor_median.resize(num_scan_points);
266  std::vector<bool> medians = getMedianReflectors(scan_points);
267  for (uint16_t i = 0; i < num_scan_points; ++i)
268  {
269  const sick::datastructure::ScanPoint scan_point = scan_points.at(i);
270  msg.reflektor_status[i] = scan_point.getReflectorBit();
271  msg.intrusion[i] = scan_point.getContaminationBit();
272  msg.reflektor_median[i] = medians.at(i);
273  }
274  return msg;
275 }
276 
278  const std::vector<sick::datastructure::ScanPoint> scan_points)
279 {
280  std::vector<bool> res;
281  res.resize(scan_points.size());
282  bool last = false;
283  int start = -1;
284  for (size_t i = 0; i < scan_points.size(); i++)
285  {
286  res.at(i) = false;
287  if (!last && scan_points.at(i).getReflectorBit())
288  {
289  last = true;
290  start = i;
291  }
292  else if (last && (!scan_points.at(i).getReflectorBit() || i == scan_points.size() - 1))
293  {
294  last = false;
295  res.at(start + ((i - start) / 2)) = true;
296  }
297  }
298 
299  return res;
300 }
301 
302 sensor_msgs::LaserScan
304 {
305  sensor_msgs::LaserScan scan;
306  scan.header.frame_id = m_frame_id;
307  scan.header.stamp = ros::Time::now();
308  // Add time offset (to account for network latency etc.)
309  scan.header.stamp += ros::Duration().fromSec(m_time_offset);
310  uint16_t num_scan_points = data.getDerivedValuesPtr()->getNumberOfBeams();
311 
312  scan.angle_min = sick::degToRad(data.getDerivedValuesPtr()->getStartAngle() + m_angle_offset);
313  double angle_max =
315  ->getScanPointsVector()
316  .at(data.getMeasurementDataPtr()->getScanPointsVector().size() - 1)
317  .getAngle() +
319  scan.angle_max = angle_max;
320  scan.angle_increment = sick::degToRad(data.getDerivedValuesPtr()->getAngularBeamResolution());
321  boost::posix_time::microseconds time_increment =
322  boost::posix_time::microseconds(data.getDerivedValuesPtr()->getInterbeamPeriod());
323  scan.time_increment = time_increment.total_microseconds() * 1e-6;
324  boost::posix_time::milliseconds scan_time =
325  boost::posix_time::milliseconds(data.getDerivedValuesPtr()->getScanTime());
326  scan.scan_time = scan_time.total_microseconds() * 1e-6;
327  scan.range_min = m_range_min;
328  scan.range_max = m_range_max;
329  scan.ranges.resize(num_scan_points);
330  scan.intensities.resize(num_scan_points);
331 
332 
333  std::vector<sick::datastructure::ScanPoint> scan_points =
334  data.getMeasurementDataPtr()->getScanPointsVector();
335  for (uint16_t i = 0; i < num_scan_points; ++i)
336  {
337  const sick::datastructure::ScanPoint scan_point = scan_points.at(i);
338  scan.ranges[i] = static_cast<float>(scan_point.getDistance()) *
339  data.getDerivedValuesPtr()->getMultiplicationFactor() * 1e-3; // mm -> m
340  scan.intensities[i] = static_cast<float>(scan_point.getReflectivity());
341  }
342 
343  return scan;
344 }
345 
346 sick_safetyscanners::OutputPathsMsg
348 {
349  sick_safetyscanners::OutputPathsMsg msg;
350 
351  std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
352  sick::datastructure::ApplicationOutputs outputs = app_data->getOutputs();
353 
354  std::vector<bool> eval_out = outputs.getEvalOutVector();
355  std::vector<bool> eval_out_is_safe = outputs.getEvalOutIsSafeVector();
356  std::vector<bool> eval_out_valid = outputs.getEvalOutIsValidVector();
357 
358  std::vector<uint16_t> monitoring_case_numbers = outputs.getMonitoringCaseVector();
359  std::vector<bool> monitoring_case_number_flags = outputs.getMonitoringCaseFlagsVector();
360  if (monitoring_case_number_flags.at(0))
361  {
362  msg.active_monitoring_case = monitoring_case_numbers.at(0);
363  }
364 
365  for (size_t i = 0; i < eval_out.size(); i++)
366  {
367  msg.status.push_back(eval_out.at(i));
368  msg.is_safe.push_back(eval_out_is_safe.at(i));
369  msg.is_valid.push_back(eval_out_valid.at(i));
370  }
371  return msg;
372 }
373 
374 sick_safetyscanners::RawMicroScanDataMsg
376 {
377  sick_safetyscanners::RawMicroScanDataMsg msg;
378 
379  msg.header = createDataHeaderMessage(data);
380  msg.derived_values = createDerivedValuesMessage(data);
381  msg.general_system_state = createGeneralSystemStateMessage(data);
382  msg.measurement_data = createMeasurementDataMessage(data);
383  msg.intrusion_data = createIntrusionDataMessage(data);
384  msg.application_data = createApplicationDataMessage(data);
385 
386  return msg;
387 }
388 
389 sick_safetyscanners::DataHeaderMsg
391 {
392  sick_safetyscanners::DataHeaderMsg msg;
393 
394  if (!data.getDataHeaderPtr()->isEmpty())
395  {
396  std::shared_ptr<sick::datastructure::DataHeader> data_header = data.getDataHeaderPtr();
397 
398  msg.version_version = data_header->getVersionIndicator();
399  msg.version_release = data_header->getVersionRelease();
400  msg.version_major_version = data_header->getVersionMajorVersion();
401  msg.version_minor_version = data_header->getVersionMinorVersion();
402 
403  msg.scan_number = data_header->getScanNumber();
404  msg.sequence_number = data_header->getSequenceNumber();
405 
406  msg.serial_number_of_device = data_header->getSerialNumberOfDevice();
407  msg.serial_number_of_channel_plug = data_header->getSerialNumberOfSystemPlug();
408 
409  msg.channel_number = data_header->getChannelNumber();
410 
411  msg.timestamp_date = data_header->getTimestampDate();
412  msg.timestamp_time = data_header->getTimestampTime();
413  }
414  return msg;
415 }
416 
417 sick_safetyscanners::DerivedValuesMsg
419 {
420  sick_safetyscanners::DerivedValuesMsg msg;
421 
422  if (!data.getDerivedValuesPtr()->isEmpty())
423  {
424  std::shared_ptr<sick::datastructure::DerivedValues> derived_values = data.getDerivedValuesPtr();
425 
426  msg.multiplication_factor = derived_values->getMultiplicationFactor();
427  msg.scan_time = derived_values->getScanTime();
428  msg.interbeam_period = derived_values->getInterbeamPeriod();
429  msg.number_of_beams = derived_values->getNumberOfBeams();
430  msg.start_angle = derived_values->getStartAngle() + m_angle_offset;
431  msg.angular_beam_resolution = derived_values->getAngularBeamResolution();
432  }
433  return msg;
434 }
435 
436 sick_safetyscanners::GeneralSystemStateMsg
438 {
439  sick_safetyscanners::GeneralSystemStateMsg msg;
440 
441  if (!data.getGeneralSystemStatePtr()->isEmpty())
442  {
443  std::shared_ptr<sick::datastructure::GeneralSystemState> general_system_state =
445 
446  msg.run_mode_active = general_system_state->getRunModeActive();
447  msg.standby_mode_active = general_system_state->getStandbyModeActive();
448  msg.contamination_warning = general_system_state->getContaminationWarning();
449  msg.contamination_error = general_system_state->getContaminationError();
450  msg.reference_contour_status = general_system_state->getReferenceContourStatus();
451  msg.manipulation_status = general_system_state->getManipulationStatus();
452 
453  std::vector<bool> safe_cut_off_path = general_system_state->getSafeCutOffPathVector();
454  for (size_t i = 0; i < safe_cut_off_path.size(); i++)
455  {
456  msg.safe_cut_off_path.push_back(safe_cut_off_path.at(i));
457  }
458 
459  std::vector<bool> non_safe_cut_off_path = general_system_state->getNonSafeCutOffPathVector();
460  for (size_t i = 0; i < non_safe_cut_off_path.size(); i++)
461  {
462  msg.non_safe_cut_off_path.push_back(non_safe_cut_off_path.at(i));
463  }
464 
465  std::vector<bool> reset_required_cut_off_path =
466  general_system_state->getResetRequiredCutOffPathVector();
467  for (size_t i = 0; i < reset_required_cut_off_path.size(); i++)
468  {
469  msg.reset_required_cut_off_path.push_back(reset_required_cut_off_path.at(i));
470  }
471 
472  msg.current_monitoring_case_no_table_1 =
473  general_system_state->getCurrentMonitoringCaseNoTable_1();
474  msg.current_monitoring_case_no_table_2 =
475  general_system_state->getCurrentMonitoringCaseNoTable_2();
476  msg.current_monitoring_case_no_table_3 =
477  general_system_state->getCurrentMonitoringCaseNoTable_3();
478  msg.current_monitoring_case_no_table_4 =
479  general_system_state->getCurrentMonitoringCaseNoTable_4();
480 
481  msg.application_error = general_system_state->getApplicationError();
482  msg.device_error = general_system_state->getDeviceError();
483  }
484  return msg;
485 }
486 
487 sick_safetyscanners::MeasurementDataMsg
489 {
490  sick_safetyscanners::MeasurementDataMsg msg;
491 
492  if (!data.getMeasurementDataPtr()->isEmpty())
493  {
494  msg.number_of_beams = data.getMeasurementDataPtr()->getNumberOfBeams();
495  msg.scan_points = createScanPointMessageVector(data);
496  }
497  return msg;
498 }
499 
500 std::vector<sick_safetyscanners::ScanPointMsg>
502 {
503  std::vector<sick_safetyscanners::ScanPointMsg> msg_vector;
504 
505  std::shared_ptr<sick::datastructure::MeasurementData> measurement_data =
506  data.getMeasurementDataPtr();
507  std::vector<sick::datastructure::ScanPoint> scan_points = measurement_data->getScanPointsVector();
508  uint16_t num_points = measurement_data->getNumberOfBeams();
509  for (uint16_t i = 0; i < num_points; i++)
510  {
511  sick::datastructure::ScanPoint scan_point = scan_points.at(i);
512  sick_safetyscanners::ScanPointMsg msg;
513  msg.distance = scan_point.getDistance();
514  msg.reflectivity = scan_point.getReflectivity();
515  msg.angle = scan_point.getAngle() + m_angle_offset;
516  msg.valid = scan_point.getValidBit();
517  msg.infinite = scan_point.getInfiniteBit();
518  msg.glare = scan_point.getGlareBit();
519  msg.reflector = scan_point.getReflectorBit();
520  msg.contamination_warning = scan_point.getContaminationWarningBit();
521  msg.contamination = scan_point.getContaminationBit();
522 
523  msg_vector.push_back(msg);
524  }
525  return msg_vector;
526 }
527 
528 sick_safetyscanners::IntrusionDataMsg
530 {
531  sick_safetyscanners::IntrusionDataMsg msg;
532 
533  if (!data.getIntrusionDataPtr()->isEmpty())
534  {
535  msg.data = createIntrusionDatumMessageVector(data);
536  }
537  return msg;
538 }
539 
540 std::vector<sick_safetyscanners::IntrusionDatumMsg>
542 {
543  std::vector<sick_safetyscanners::IntrusionDatumMsg> msg_vector;
544 
545  std::shared_ptr<sick::datastructure::IntrusionData> intrusion_data = data.getIntrusionDataPtr();
546  std::vector<sick::datastructure::IntrusionDatum> intrusion_datums =
547  intrusion_data->getIntrusionDataVector();
548 
549  for (size_t i = 0; i < intrusion_datums.size(); i++)
550  {
551  sick_safetyscanners::IntrusionDatumMsg msg;
552  sick::datastructure::IntrusionDatum intrusion_datum = intrusion_datums.at(i);
553  msg.size = intrusion_datum.getSize();
554  std::vector<bool> flags = intrusion_datum.getFlagsVector();
555  for (size_t j = 0; j < flags.size(); j++)
556  {
557  msg.flags.push_back(flags.at(j));
558  }
559  msg_vector.push_back(msg);
560  }
561  return msg_vector;
562 }
563 
564 sick_safetyscanners::ApplicationDataMsg
566 {
567  sick_safetyscanners::ApplicationDataMsg msg;
568 
569  if (!data.getApplicationDataPtr()->isEmpty())
570  {
571  msg.inputs = createApplicationInputsMessage(data);
572  msg.outputs = createApplicationOutputsMessage(data);
573  }
574  return msg;
575 }
576 
577 sick_safetyscanners::ApplicationInputsMsg
579 {
580  sick_safetyscanners::ApplicationInputsMsg msg;
581 
582  std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
583  sick::datastructure::ApplicationInputs inputs = app_data->getInputs();
584  std::vector<bool> unsafe_inputs = inputs.getUnsafeInputsInputSourcesVector();
585  std::vector<bool> unsafe_inputs_flags = inputs.getUnsafeInputsFlagsVector();
586  for (size_t i = 0; i < unsafe_inputs.size(); i++)
587  {
588  msg.unsafe_inputs_input_sources.push_back(unsafe_inputs.at(i));
589  msg.unsafe_inputs_flags.push_back(unsafe_inputs_flags.at(i));
590  }
591  std::vector<uint16_t> monitoring_case = inputs.getMonitoringCasevector();
592  std::vector<bool> monitoring_case_flags = inputs.getMonitoringCaseFlagsVector();
593  for (size_t i = 0; i < monitoring_case.size(); i++)
594  {
595  msg.monitoring_case_number_inputs.push_back(monitoring_case.at(i));
596  msg.monitoring_case_number_inputs_flags.push_back(monitoring_case_flags.at(i));
597  }
598  msg.linear_velocity_inputs_velocity_0 = inputs.getVelocity0();
599  msg.linear_velocity_inputs_velocity_0_transmitted_safely = inputs.getVelocity0TransmittedSafely();
600  msg.linear_velocity_inputs_velocity_0_valid = inputs.getVelocity0Valid();
601  msg.linear_velocity_inputs_velocity_1 = inputs.getVelocity1();
602  msg.linear_velocity_inputs_velocity_1_transmitted_safely = inputs.getVelocity1TransmittedSafely();
603  msg.linear_velocity_inputs_velocity_1_valid = inputs.getVelocity1Valid();
604 
605  msg.sleep_mode_input = inputs.getSleepModeInput();
606 
607  return msg;
608 }
609 
610 sick_safetyscanners::ApplicationOutputsMsg
612 {
613  sick_safetyscanners::ApplicationOutputsMsg msg;
614 
615  std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
616  sick::datastructure::ApplicationOutputs outputs = app_data->getOutputs();
617 
618  std::vector<bool> eval_out = outputs.getEvalOutVector();
619  std::vector<bool> eval_out_is_safe = outputs.getEvalOutIsSafeVector();
620  std::vector<bool> eval_out_valid = outputs.getEvalOutIsValidVector();
621  for (size_t i = 0; i < eval_out.size(); i++)
622  {
623  msg.evaluation_path_outputs_eval_out.push_back(eval_out.at(i));
624  msg.evaluation_path_outputs_is_safe.push_back(eval_out_is_safe.at(i));
625  msg.evaluation_path_outputs_is_valid.push_back(eval_out_valid.at(i));
626  }
627 
628  std::vector<uint16_t> monitoring_case = outputs.getMonitoringCaseVector();
629  std::vector<bool> monitoring_case_flags = outputs.getMonitoringCaseFlagsVector();
630  for (size_t i = 0; i < monitoring_case.size(); i++)
631  {
632  msg.monitoring_case_number_outputs.push_back(monitoring_case.at(i));
633  msg.monitoring_case_number_outputs_flags.push_back(monitoring_case_flags.at(i));
634  }
635 
636  msg.sleep_mode_output = outputs.getSleepModeOutput();
637  msg.sleep_mode_output_valid = outputs.getFlagsSleepModeOutputIsValid();
638 
639  msg.error_flag_contamination_warning = outputs.getHostErrorFlagContaminationWarning();
640  msg.error_flag_contamination_error = outputs.getHostErrorFlagContaminationError();
641  msg.error_flag_manipulation_error = outputs.getHostErrorFlagManipulationError();
642  msg.error_flag_glare = outputs.getHostErrorFlagGlare();
643  msg.error_flag_reference_contour_intruded = outputs.getHostErrorFlagReferenceContourIntruded();
644  msg.error_flag_critical_error = outputs.getHostErrorFlagCriticalError();
645  msg.error_flags_are_valid = outputs.getFlagsHostErrorFlagsAreValid();
646 
647  msg.linear_velocity_outputs_velocity_0 = outputs.getVelocity0();
648  msg.linear_velocity_outputs_velocity_0_transmitted_safely =
650  msg.linear_velocity_outputs_velocity_0_valid = outputs.getVelocity0Valid();
651  msg.linear_velocity_outputs_velocity_1 = outputs.getVelocity1();
652  msg.linear_velocity_outputs_velocity_1_transmitted_safely =
654  msg.linear_velocity_outputs_velocity_1_valid = outputs.getVelocity1Valid();
655 
656  std::vector<int16_t> resulting_velocities = outputs.getResultingVelocityVector();
657  std::vector<bool> resulting_velocities_flags = outputs.getResultingVelocityIsValidVector();
658 
659  for (size_t i = 0; i < resulting_velocities.size(); i++)
660  {
661  msg.resulting_velocity.push_back(resulting_velocities.at(i));
662  msg.resulting_velocity_flags.push_back(resulting_velocities_flags.at(i));
663  }
664 
665 
666  return msg;
667 }
668 
669 bool SickSafetyscannersRos::getFieldData(sick_safetyscanners::FieldData::Request& req,
670  sick_safetyscanners::FieldData::Response& res)
671 {
672  std::vector<sick::datastructure::FieldData> fields;
673  m_device->requestFieldData(m_communication_settings, fields);
674 
675  for (size_t i = 0; i < fields.size(); i++)
676  {
677  sick::datastructure::FieldData field = fields.at(i);
678  sick_safetyscanners::FieldMsg field_msg;
679 
680  field_msg.start_angle = degToRad(field.getStartAngle() + m_angle_offset);
681  field_msg.angular_resolution = degToRad(field.getAngularBeamResolution());
682  field_msg.protective_field = field.getIsProtectiveField();
683 
684  std::vector<uint16_t> ranges = field.getBeamDistances();
685  for (size_t j = 0; j < ranges.size(); j++)
686  {
687  field_msg.ranges.push_back(static_cast<float>(ranges.at(j)) * 1e-3);
688  }
689 
690  res.fields.push_back(field_msg);
691  }
692 
693  std::string device_name;
694  m_device->requestDeviceName(m_communication_settings, device_name);
695  res.device_name = device_name;
696 
697 
698  std::vector<sick::datastructure::MonitoringCaseData> monitoring_cases;
699  m_device->requestMonitoringCases(m_communication_settings, monitoring_cases);
700 
701  for (size_t i = 0; i < monitoring_cases.size(); i++)
702  {
703  sick::datastructure::MonitoringCaseData monitoring_case_data = monitoring_cases.at(i);
704  sick_safetyscanners::MonitoringCaseMsg monitoring_case_msg;
705 
706  monitoring_case_msg.monitoring_case_number = monitoring_case_data.getMonitoringCaseNumber();
707  std::vector<uint16_t> mon_fields = monitoring_case_data.getFieldIndices();
708  std::vector<bool> mon_fields_valid = monitoring_case_data.getFieldsValid();
709  for (size_t j = 0; j < mon_fields.size(); j++)
710  {
711  monitoring_case_msg.fields.push_back(mon_fields.at(j));
712  monitoring_case_msg.fields_valid.push_back(mon_fields_valid.at(j));
713  }
714  res.monitoring_cases.push_back(monitoring_case_msg);
715  }
716 
717  return true;
718 }
719 
720 
721 } // namespace sick
bool getVelocity1TransmittedSafely() const
Gets if the second linear velocity output is transmitted safely.
int16_t getVelocity1() const
Gets the second linear velocity output.
sick_safetyscanners::ApplicationOutputsMsg createApplicationOutputsMessage(const sick::datastructure::Data &data)
float getStartAngle() const
Get the start angle of the configuration.
Definition: ConfigData.cpp:42
sick_safetyscanners::MeasurementDataMsg createMeasurementDataMessage(const sick::datastructure::Data &data)
std::vector< uint16_t > getMonitoringCasevector() const
Gets the monitoring case numbers.
sick_safetyscanners::DataHeaderMsg createDataHeaderMessage(const sick::datastructure::Data &data)
void setEInterfaceType(const uint8_t &e_interface_type)
Sets the eInterface type.
void setFeatures(const uint16_t &features)
Set the enabled features.
bool getHostErrorFlagReferenceContourIntruded() const
Gets if a reference contour is intruded.
float getStartAngle() const
Get the start angle of the scan.
Definition: FieldData.cpp:92
bool getHostErrorFlagContaminationError() const
Gets if a contamination error is present.
bool getFlagsSleepModeOutputIsValid() const
Gets if the sleep mode is valid.
ROSCPP_DECL void start()
void publish(const boost::shared_ptr< M > &message) const
bool getInfiniteBit() const
Returns if the scanpoint is infinite.
Definition: ScanPoint.cpp:83
void setSensorTcpPort(const uint16_t &sensor_tcp_port)
Sets the sensor tcp port.
bool getVelocity0TransmittedSafely() const
Gets if first linear velocity input is transmitted safely.
int32_t getSize() const
Returns size of flag vector.
int16_t getVelocity1() const
Gets the second linear velocity input.
std::vector< bool > getResultingVelocityIsValidVector() const
Gets if the resulting velocities are valid.
std::shared_ptr< ApplicationData > getApplicationDataPtr() const
Gets the application data.
Definition: Data.cpp:94
bool getIsProtectiveField() const
Returns if a field is a protective field.
Definition: FieldData.cpp:72
bool getHostErrorFlagGlare() const
Gets if glare is present.
std::vector< bool > getEvalOutIsSafeVector() const
Gets if a cut-off path from the output paths is safe.
ros::NodeHandle m_nh
ROS node handle.
float getMaxRange() const
Gets the max range for the scanner.
Definition: TypeCode.cpp:52
void setEnabled(bool enabled)
Sets if the channel is enabled.
sick_safetyscanners::GeneralSystemStateMsg createGeneralSystemStateMessage(const sick::datastructure::Data &data)
uint16_t skipToPublishFrequency(int skip)
Converts a skip value into a "publish frequency" value.
The applications inputs from a udp data packet.
std::vector< uint16_t > getMonitoringCaseVector() const
Gets the currently active monitoring case numbers.
bool getVelocity1TransmittedSafely() const
Gets if second linear velocity input is transmitted safely.
Class containing the data of a single scan point.
Definition: ScanPoint.h:46
std::vector< sick_safetyscanners::IntrusionDatumMsg > createIntrusionDatumMessageVector(const sick::datastructure::Data &data)
void setEndAngle(const uint32_t &end_angle)
Sets the end angle of the scan.
Class containing a single IntrusionDatum.
std::vector< uint16_t > getBeamDistances() const
Returns vector with beam distances.
Definition: FieldData.cpp:82
bool getVelocity1Valid() const
Gets if second linear velocity input is valid.
Field data for warning and protective fields.
Definition: FieldData.h:48
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer m_field_service_server
sick_safetyscanners::RawMicroScanDataMsg createRawDataMessage(const sick::datastructure::Data &data)
bool getContaminationBit() const
Returns if the scanpoint is contaminated.
Definition: ScanPoint.cpp:98
void setPublishingFrequency(const uint16_t &publishing_frequency)
Sets the publishing frequency.
void reconfigure_callback(const sick_safetyscanners::SickSafetyscannersConfigurationConfig &config, const uint32_t &level)
Function which is triggered when a dynamic reconfiguration is performed.
int16_t getVelocity0() const
Gets the first linear velocity output.
#define ROS_WARN(...)
uint16_t getDistance() const
Getter for the distance of the scanpoint.
Definition: ScanPoint.cpp:68
std::vector< bool > getFlagsVector() const
Getter for the flags vector.
std::vector< bool > getUnsafeInputsFlagsVector() const
Gets the flags for the unsafe input sources.
sick_safetyscanners::ApplicationDataMsg createApplicationDataMessage(const sick::datastructure::Data &data)
int16_t getVelocity0() const
Gets the first linear velocity input.
std::shared_ptr< IntrusionData > getIntrusionDataPtr() const
Gets the intrusion data.
Definition: Data.cpp:84
The data class containing all data blocks of a measurement.
Definition: Data.h:55
dynamic_reconfigure::Server< sick_safetyscanners::SickSafetyscannersConfigurationConfig > m_dynamic_reconfiguration_server
bool getGlareBit() const
Returns if the scanpoint has glare.
Definition: ScanPoint.cpp:88
bool getValidBit() const
Returns if the scanpoint is valid.
Definition: ScanPoint.cpp:78
void setSensorIp(const boost::asio::ip::address_v4 &sensor_ip)
Sets the sensor IP-address.
std::vector< bool > getEvalOutVector() const
Gets the state of the non safe cut-off paths.
int8_t getSleepModeInput() const
Gets the state of the sleep mode.
sick_safetyscanners::ExtendedLaserScanMsg createExtendedLaserScanMessage(const sick::datastructure::Data &data)
bool getHostErrorFlagContaminationWarning() const
Gets if a contamination warning is present.
sick_safetyscanners::DerivedValuesMsg createDerivedValuesMessage(const sick::datastructure::Data &data)
bool getReflectorBit() const
Returns if the scanpoint detects a reflector.
Definition: ScanPoint.cpp:93
bool getFieldData(sick_safetyscanners::FieldData::Request &req, sick_safetyscanners::FieldData::Response &res)
bool getFlagsHostErrorFlagsAreValid() const
Gets if the error flags are valid.
bool getVelocity0Valid() const
Gets if first linear velocity input is valid.
Duration & fromSec(double t)
void receivedUDPPacket(const datastructure::Data &data)
Function which is called when a new complete UDP Packet is received.
#define ROS_INFO(...)
float degToRad(float deg)
Converts degrees to radians.
std::vector< bool > getFieldsValid() const
Returns if the fields are configured and valid.
ros::Publisher m_laser_scan_publisher
ROS topic publisher.
sick_safetyscanners::IntrusionDataMsg createIntrusionDataMessage(const sick::datastructure::Data &data)
std::vector< bool > getMonitoringCaseFlagsVector() const
Gets if the corresponding monitoring case number is valid.
ros::NodeHandle m_private_nh
ROS private node handle.
std::vector< bool > getMedianReflectors(const std::vector< sick::datastructure::ScanPoint > scan_points)
std::shared_ptr< MeasurementData > getMeasurementDataPtr() const
Gets the measurement data.
Definition: Data.cpp:74
void setStartAngle(const uint32_t &start_angle)
Sets the start angle of the scan.
sick_safetyscanners::ApplicationInputsMsg createApplicationInputsMessage(const sick::datastructure::Data &data)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sick_safetyscanners::OutputPathsMsg createOutputPathsMessage(const sick::datastructure::Data &data)
std::shared_ptr< sick::SickSafetyscanners > m_device
uint8_t getInterfaceType() const
Gets the interface type for the scanner.
Definition: TypeCode.cpp:42
sick::datastructure::CommSettings m_communication_settings
The application outputs from a udp data packet.
Config data for current and persistent sensor config.
Definition: ConfigData.h:48
void setHostUdpPort(const uint16_t &host_udp_port)
Sets the host udp port.
sensor_msgs::LaserScan createLaserScanMessage(const sick::datastructure::Data &data)
Stores the data for the different monitoring cases.
void setChannel(const uint8_t &channel)
Sets the channel of the data.
float radToDeg(float rad)
Converts radians to degrees.
bool getHostErrorFlagManipulationError() const
Gets if a manipulation error is present.
ROSCPP_DECL void requestShutdown()
virtual ~SickSafetyscannersRos()
~SickSafetyscannersRos Destructor if the SickSafetyscanners ROS
bool getVelocity0TransmittedSafely() const
Gets if the first linear velocity output is transmitted safely.
bool getParam(const std::string &key, std::string &s) const
bool getContaminationWarningBit() const
Returns if there is a contamination warning.
Definition: ScanPoint.cpp:103
static Time now()
Class containing the type code of a laser scanner.
Definition: TypeCode.h:62
std::vector< bool > getMonitoringCaseFlagsVector() const
Gets the monitoring case flags.
std::shared_ptr< GeneralSystemState > getGeneralSystemStatePtr() const
Gets the general system state.
Definition: Data.cpp:53
std::shared_ptr< DataHeader > getDataHeaderPtr() const
Gets the data header.
Definition: Data.cpp:42
bool readParameters()
Reads and verifies the ROS parameters.
bool getHostErrorFlagCriticalError() const
Gets if a critical error is present.
std::vector< bool > getUnsafeInputsInputSourcesVector() const
Gets the unsafe input sources.
float getEndAngle() const
Get the end angle of the configuration.
Definition: ConfigData.cpp:57
std::vector< bool > getEvalOutIsValidVector() const
If the output path is valid.
ros::Publisher m_extended_laser_scan_publisher
std::vector< uint16_t > getFieldIndices() const
Returns the field indices.
int8_t getSleepModeOutput() const
Gets the state of the sleep mode.
float getAngle() const
Getter for the angle in sensor coordinates.
Definition: ScanPoint.cpp:63
#define ROS_ERROR(...)
bool getVelocity0Valid() const
Gets if the first linear velocity output is valid.
std::vector< sick_safetyscanners::ScanPointMsg > createScanPointMessageVector(const sick::datastructure::Data &data)
void setHostIp(const boost::asio::ip::address_v4 &host_ip)
Sets the IP-address of the host from an IP-address.
uint8_t getReflectivity() const
Getter for the reflectivity value.
Definition: ScanPoint.cpp:73
uint16_t getMonitoringCaseNumber() const
Returns the number of the monitoring case.
std::shared_ptr< DerivedValues > getDerivedValuesPtr() const
Gets the derived values.
Definition: Data.cpp:64
float getAngularBeamResolution() const
Returns the angular resolution between the beams.
Definition: FieldData.cpp:122
bool getVelocity1Valid() const
Gets if the second linear velocity output is valid.
std::vector< int16_t > getResultingVelocityVector() const
Gets the resulting velocity for each monitoring case table.
SickSafetyscannersRos()
Constructor of the SickSafetyscannersRos.


sick_safetyscanners
Author(s): Lennart Puck
autogenerated on Thu May 9 2019 02:41:08