00001
00002
00003
00004
00024
00025
00026
00033
00034
00035
00036 #include "sick_safetyscanners/SickSafetyscannersRos.h"
00037
00038
00039 namespace sick {
00040
00041 SickSafetyscannersRos::SickSafetyscannersRos()
00042 : m_nh()
00043 , m_private_nh("~")
00044 , m_initialised(false)
00045 , m_time_offset(0.0)
00046 , m_range_min(0.0)
00047 , m_range_max(0.0)
00048 , m_angle_offset(-90.0)
00049 , m_use_pers_conf(false)
00050 {
00051 dynamic_reconfigure::Server<
00052 sick_safetyscanners::SickSafetyscannersConfigurationConfig>::CallbackType reconf_callback =
00053 boost::bind(&SickSafetyscannersRos::reconfigure_callback, this, _1, _2);
00054 m_dynamic_reconfiguration_server.setCallback(reconf_callback);
00055 if (!readParameters())
00056 {
00057 ROS_ERROR("Could not read parameters.");
00058 ros::requestShutdown();
00059 }
00060
00061 m_communication_settings.setSensorTcpPort(2122);
00062 m_laser_scan_publisher = m_nh.advertise<sensor_msgs::LaserScan>("scan", 100);
00063 m_extended_laser_scan_publisher =
00064 m_nh.advertise<sick_safetyscanners::ExtendedLaserScanMsg>("extended_laser_scan", 100);
00065 m_raw_data_publisher = m_nh.advertise<sick_safetyscanners::RawMicroScanDataMsg>("raw_data", 100);
00066 m_output_path_publisher =
00067 m_nh.advertise<sick_safetyscanners::OutputPathsMsg>("output_paths", 100);
00068 m_field_service_server =
00069 m_nh.advertiseService("field_data", &SickSafetyscannersRos::getFieldData, this);
00070
00071 m_device = std::make_shared<sick::SickSafetyscanners>(
00072 boost::bind(&SickSafetyscannersRos::receivedUDPPacket, this, _1), &m_communication_settings);
00073 m_device->run();
00074 readTypeCodeSettings();
00075
00076 if (m_use_pers_conf)
00077 {
00078 readPersistentConfig();
00079 }
00080
00081 m_device->changeSensorSettings(m_communication_settings);
00082 m_initialised = true;
00083 ROS_INFO("Successfully launched node.");
00084 }
00085
00086 void SickSafetyscannersRos::readTypeCodeSettings()
00087 {
00088 ROS_INFO("Reading Type code settings");
00089 sick::datastructure::TypeCode type_code;
00090 m_device->requestTypeCode(m_communication_settings, type_code);
00091 m_communication_settings.setEInterfaceType(type_code.getInterfaceType());
00092 m_range_min = 0.1;
00093 m_range_max = type_code.getMaxRange();
00094 }
00095
00096 void SickSafetyscannersRos::readPersistentConfig()
00097 {
00098 ROS_INFO("Reading Persistent Configuration");
00099 sick::datastructure::ConfigData config_data;
00100 m_device->requestPersistentConfig(m_communication_settings, config_data);
00101 m_communication_settings.setStartAngle(config_data.getStartAngle());
00102 m_communication_settings.setEndAngle(config_data.getEndAngle());
00103 }
00104
00105 void SickSafetyscannersRos::reconfigure_callback(
00106 const sick_safetyscanners::SickSafetyscannersConfigurationConfig& config, const uint32_t& level)
00107 {
00108 if (isInitialised())
00109 {
00110 m_communication_settings.setEnabled(config.channel_enabled);
00111 m_communication_settings.setPublishingFrequency(skipToPublishFrequency(config.skip));
00112 if (config.angle_start == config.angle_end)
00113 {
00114 m_communication_settings.setStartAngle(sick::radToDeg(0));
00115 m_communication_settings.setEndAngle(sick::radToDeg(0));
00116 }
00117 else
00118 {
00119 m_communication_settings.setStartAngle(sick::radToDeg(config.angle_start) - m_angle_offset);
00120 m_communication_settings.setEndAngle(sick::radToDeg(config.angle_end) - m_angle_offset);
00121 }
00122 m_communication_settings.setFeatures(config.general_system_state,
00123 config.derived_settings,
00124 config.measurement_data,
00125 config.intrusion_data,
00126 config.application_io_data);
00127 m_device->changeSensorSettings(m_communication_settings);
00128
00129 m_frame_id = config.frame_id;
00130
00131 m_time_offset = config.time_offset;
00132 }
00133 }
00134
00135 bool SickSafetyscannersRos::isInitialised()
00136 {
00137 return m_initialised;
00138 }
00139
00140
00141 SickSafetyscannersRos::~SickSafetyscannersRos() {}
00142
00143 bool SickSafetyscannersRos::readParameters()
00144 {
00145 std::string sensor_ip_adress = "192.168.1.10";
00146 if (!m_private_nh.getParam("sensor_ip", sensor_ip_adress))
00147 {
00148
00149 ROS_WARN("Using default sensor IP: %s", sensor_ip_adress.c_str());
00150 }
00151 m_communication_settings.setSensorIp(sensor_ip_adress);
00152
00153
00154 std::string host_ip_adress = "192.168.1.9";
00155 if (!m_private_nh.getParam("host_ip", host_ip_adress))
00156 {
00157 ROS_WARN("Using default host IP: %s", host_ip_adress.c_str());
00158 }
00159 m_communication_settings.setHostIp(host_ip_adress);
00160
00161 int host_udp_port = 0;
00162 if (!m_private_nh.getParam("host_udp_port", host_udp_port))
00163 {
00164 ROS_WARN("Using default host UDP Port: %i", host_udp_port);
00165 }
00166 m_communication_settings.setHostUdpPort(host_udp_port);
00167
00168 ROS_WARN("If not further specified the default values for the dynamic reconfigurable parameters "
00169 "will be loaded.");
00170
00171
00172 int channel = 0;
00173 m_private_nh.getParam("channel", channel);
00174 m_communication_settings.setChannel(channel);
00175
00176 bool enabled;
00177 m_private_nh.getParam("channel_enabled", enabled);
00178 m_communication_settings.setEnabled(enabled);
00179
00180 int skip;
00181 m_private_nh.getParam("skip", skip);
00182 m_communication_settings.setPublishingFrequency(skipToPublishFrequency(skip));
00183
00184 float angle_start;
00185 m_private_nh.getParam("angle_start", angle_start);
00186
00187 float angle_end;
00188 m_private_nh.getParam("angle_end", angle_end);
00189
00190
00191 if (angle_start == angle_end)
00192 {
00193 m_communication_settings.setStartAngle(sick::radToDeg(0));
00194 m_communication_settings.setEndAngle(sick::radToDeg(0));
00195 }
00196 else
00197 {
00198 m_communication_settings.setStartAngle(sick::radToDeg(angle_start) - m_angle_offset);
00199 m_communication_settings.setEndAngle(sick::radToDeg(angle_end) - m_angle_offset);
00200 }
00201
00202 bool general_system_state;
00203 m_private_nh.getParam("general_system_state", general_system_state);
00204
00205 bool derived_settings;
00206 m_private_nh.getParam("derived_settings", derived_settings);
00207
00208 bool measurement_data;
00209 m_private_nh.getParam("measurement_data", measurement_data);
00210
00211 bool intrusion_data;
00212 m_private_nh.getParam("intrusion_data", intrusion_data);
00213
00214 bool application_io_data;
00215 m_private_nh.getParam("application_io_data", application_io_data);
00216
00217 m_communication_settings.setFeatures(
00218 general_system_state, derived_settings, measurement_data, intrusion_data, application_io_data);
00219
00220 m_private_nh.getParam("frame_id", m_frame_id);
00221
00222 m_private_nh.getParam("use_persistent_config", m_use_pers_conf);
00223
00224 return true;
00225 }
00226
00227 void SickSafetyscannersRos::receivedUDPPacket(const sick::datastructure::Data& data)
00228 {
00229 if (!data.getMeasurementDataPtr()->isEmpty() && !data.getDerivedValuesPtr()->isEmpty())
00230 {
00231 sensor_msgs::LaserScan scan = createLaserScanMessage(data);
00232
00233 m_laser_scan_publisher.publish(scan);
00234 }
00235
00236
00237 if (!data.getMeasurementDataPtr()->isEmpty() && !data.getDerivedValuesPtr()->isEmpty())
00238 {
00239 sick_safetyscanners::ExtendedLaserScanMsg extended_scan = createExtendedLaserScanMessage(data);
00240
00241 m_extended_laser_scan_publisher.publish(extended_scan);
00242
00243 sick_safetyscanners::OutputPathsMsg output_paths = createOutputPathsMessage(data);
00244 m_output_path_publisher.publish(output_paths);
00245 }
00246
00247 sick_safetyscanners::RawMicroScanDataMsg raw_data = createRawDataMessage(data);
00248
00249 m_raw_data_publisher.publish(raw_data);
00250 }
00251
00252 sick_safetyscanners::ExtendedLaserScanMsg
00253 SickSafetyscannersRos::createExtendedLaserScanMessage(const sick::datastructure::Data& data)
00254 {
00255 sensor_msgs::LaserScan scan = createLaserScanMessage(data);
00256 sick_safetyscanners::ExtendedLaserScanMsg msg;
00257 msg.laser_scan = scan;
00258
00259 uint16_t num_scan_points = data.getDerivedValuesPtr()->getNumberOfBeams();
00260 std::vector<sick::datastructure::ScanPoint> scan_points =
00261 data.getMeasurementDataPtr()->getScanPointsVector();
00262
00263 msg.reflektor_status.resize(num_scan_points);
00264 msg.intrusion.resize(num_scan_points);
00265 msg.reflektor_median.resize(num_scan_points);
00266 std::vector<bool> medians = getMedianReflectors(scan_points);
00267 for (uint16_t i = 0; i < num_scan_points; ++i)
00268 {
00269 const sick::datastructure::ScanPoint scan_point = scan_points.at(i);
00270 msg.reflektor_status[i] = scan_point.getReflectorBit();
00271 msg.intrusion[i] = scan_point.getContaminationBit();
00272 msg.reflektor_median[i] = medians.at(i);
00273 }
00274 return msg;
00275 }
00276
00277 std::vector<bool> SickSafetyscannersRos::getMedianReflectors(
00278 const std::vector<sick::datastructure::ScanPoint> scan_points)
00279 {
00280 std::vector<bool> res;
00281 res.resize(scan_points.size());
00282 bool last = false;
00283 int start = -1;
00284 for (size_t i = 0; i < scan_points.size(); i++)
00285 {
00286 res.at(i) = false;
00287 if (!last && scan_points.at(i).getReflectorBit())
00288 {
00289 last = true;
00290 start = i;
00291 }
00292 else if (last && (!scan_points.at(i).getReflectorBit() || i == scan_points.size() - 1))
00293 {
00294 last = false;
00295 res.at(start + ((i - start) / 2)) = true;
00296 }
00297 }
00298
00299 return res;
00300 }
00301
00302 sensor_msgs::LaserScan
00303 SickSafetyscannersRos::createLaserScanMessage(const sick::datastructure::Data& data)
00304 {
00305 sensor_msgs::LaserScan scan;
00306 scan.header.frame_id = m_frame_id;
00307 scan.header.stamp = ros::Time::now();
00308
00309 scan.header.stamp += ros::Duration().fromSec(m_time_offset);
00310 uint16_t num_scan_points = data.getDerivedValuesPtr()->getNumberOfBeams();
00311
00312 scan.angle_min = sick::degToRad(data.getDerivedValuesPtr()->getStartAngle() + m_angle_offset);
00313 double angle_max =
00314 sick::degToRad(data.getMeasurementDataPtr()
00315 ->getScanPointsVector()
00316 .at(data.getMeasurementDataPtr()->getScanPointsVector().size() - 1)
00317 .getAngle() +
00318 m_angle_offset);
00319 scan.angle_max = angle_max;
00320 scan.angle_increment = sick::degToRad(data.getDerivedValuesPtr()->getAngularBeamResolution());
00321 boost::posix_time::microseconds time_increment =
00322 boost::posix_time::microseconds(data.getDerivedValuesPtr()->getInterbeamPeriod());
00323 scan.time_increment = time_increment.total_microseconds() * 1e-6;
00324 boost::posix_time::milliseconds scan_time =
00325 boost::posix_time::milliseconds(data.getDerivedValuesPtr()->getScanTime());
00326 scan.scan_time = scan_time.total_microseconds() * 1e-6;
00327 scan.range_min = m_range_min;
00328 scan.range_max = m_range_max;
00329 scan.ranges.resize(num_scan_points);
00330 scan.intensities.resize(num_scan_points);
00331
00332
00333 std::vector<sick::datastructure::ScanPoint> scan_points =
00334 data.getMeasurementDataPtr()->getScanPointsVector();
00335 for (uint16_t i = 0; i < num_scan_points; ++i)
00336 {
00337 const sick::datastructure::ScanPoint scan_point = scan_points.at(i);
00338 scan.ranges[i] = static_cast<float>(scan_point.getDistance()) *
00339 data.getDerivedValuesPtr()->getMultiplicationFactor() * 1e-3;
00340 scan.intensities[i] = static_cast<float>(scan_point.getReflectivity());
00341 }
00342
00343 return scan;
00344 }
00345
00346 sick_safetyscanners::OutputPathsMsg
00347 SickSafetyscannersRos::createOutputPathsMessage(const sick::datastructure::Data& data)
00348 {
00349 sick_safetyscanners::OutputPathsMsg msg;
00350
00351 std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
00352 sick::datastructure::ApplicationOutputs outputs = app_data->getOutputs();
00353
00354 std::vector<bool> eval_out = outputs.getEvalOutVector();
00355 std::vector<bool> eval_out_is_safe = outputs.getEvalOutIsSafeVector();
00356 std::vector<bool> eval_out_valid = outputs.getEvalOutIsValidVector();
00357
00358 std::vector<uint16_t> monitoring_case_numbers = outputs.getMonitoringCaseVector();
00359 std::vector<bool> monitoring_case_number_flags = outputs.getMonitoringCaseFlagsVector();
00360 if (monitoring_case_number_flags.at(0))
00361 {
00362 msg.active_monitoring_case = monitoring_case_numbers.at(0);
00363 }
00364
00365 for (size_t i = 0; i < eval_out.size(); i++)
00366 {
00367 msg.status.push_back(eval_out.at(i));
00368 msg.is_safe.push_back(eval_out_is_safe.at(i));
00369 msg.is_valid.push_back(eval_out_valid.at(i));
00370 }
00371 return msg;
00372 }
00373
00374 sick_safetyscanners::RawMicroScanDataMsg
00375 SickSafetyscannersRos::createRawDataMessage(const sick::datastructure::Data& data)
00376 {
00377 sick_safetyscanners::RawMicroScanDataMsg msg;
00378
00379 msg.header = createDataHeaderMessage(data);
00380 msg.derived_values = createDerivedValuesMessage(data);
00381 msg.general_system_state = createGeneralSystemStateMessage(data);
00382 msg.measurement_data = createMeasurementDataMessage(data);
00383 msg.intrusion_data = createIntrusionDataMessage(data);
00384 msg.application_data = createApplicationDataMessage(data);
00385
00386 return msg;
00387 }
00388
00389 sick_safetyscanners::DataHeaderMsg
00390 SickSafetyscannersRos::createDataHeaderMessage(const sick::datastructure::Data& data)
00391 {
00392 sick_safetyscanners::DataHeaderMsg msg;
00393
00394 if (!data.getDataHeaderPtr()->isEmpty())
00395 {
00396 std::shared_ptr<sick::datastructure::DataHeader> data_header = data.getDataHeaderPtr();
00397
00398 msg.version_version = data_header->getVersionIndicator();
00399 msg.version_release = data_header->getVersionRelease();
00400 msg.version_major_version = data_header->getVersionMajorVersion();
00401 msg.version_minor_version = data_header->getVersionMinorVersion();
00402
00403 msg.scan_number = data_header->getScanNumber();
00404 msg.sequence_number = data_header->getSequenceNumber();
00405
00406 msg.serial_number_of_device = data_header->getSerialNumberOfDevice();
00407 msg.serial_number_of_channel_plug = data_header->getSerialNumberOfSystemPlug();
00408
00409 msg.channel_number = data_header->getChannelNumber();
00410
00411 msg.timestamp_date = data_header->getTimestampDate();
00412 msg.timestamp_time = data_header->getTimestampTime();
00413 }
00414 return msg;
00415 }
00416
00417 sick_safetyscanners::DerivedValuesMsg
00418 SickSafetyscannersRos::createDerivedValuesMessage(const sick::datastructure::Data& data)
00419 {
00420 sick_safetyscanners::DerivedValuesMsg msg;
00421
00422 if (!data.getDerivedValuesPtr()->isEmpty())
00423 {
00424 std::shared_ptr<sick::datastructure::DerivedValues> derived_values = data.getDerivedValuesPtr();
00425
00426 msg.multiplication_factor = derived_values->getMultiplicationFactor();
00427 msg.scan_time = derived_values->getScanTime();
00428 msg.interbeam_period = derived_values->getInterbeamPeriod();
00429 msg.number_of_beams = derived_values->getNumberOfBeams();
00430 msg.start_angle = derived_values->getStartAngle() + m_angle_offset;
00431 msg.angular_beam_resolution = derived_values->getAngularBeamResolution();
00432 }
00433 return msg;
00434 }
00435
00436 sick_safetyscanners::GeneralSystemStateMsg
00437 SickSafetyscannersRos::createGeneralSystemStateMessage(const sick::datastructure::Data& data)
00438 {
00439 sick_safetyscanners::GeneralSystemStateMsg msg;
00440
00441 if (!data.getGeneralSystemStatePtr()->isEmpty())
00442 {
00443 std::shared_ptr<sick::datastructure::GeneralSystemState> general_system_state =
00444 data.getGeneralSystemStatePtr();
00445
00446 msg.run_mode_active = general_system_state->getRunModeActive();
00447 msg.standby_mode_active = general_system_state->getStandbyModeActive();
00448 msg.contamination_warning = general_system_state->getContaminationWarning();
00449 msg.contamination_error = general_system_state->getContaminationError();
00450 msg.reference_contour_status = general_system_state->getReferenceContourStatus();
00451 msg.manipulation_status = general_system_state->getManipulationStatus();
00452
00453 std::vector<bool> safe_cut_off_path = general_system_state->getSafeCutOffPathVector();
00454 for (size_t i = 0; i < safe_cut_off_path.size(); i++)
00455 {
00456 msg.safe_cut_off_path.push_back(safe_cut_off_path.at(i));
00457 }
00458
00459 std::vector<bool> non_safe_cut_off_path = general_system_state->getNonSafeCutOffPathVector();
00460 for (size_t i = 0; i < non_safe_cut_off_path.size(); i++)
00461 {
00462 msg.non_safe_cut_off_path.push_back(non_safe_cut_off_path.at(i));
00463 }
00464
00465 std::vector<bool> reset_required_cut_off_path =
00466 general_system_state->getResetRequiredCutOffPathVector();
00467 for (size_t i = 0; i < reset_required_cut_off_path.size(); i++)
00468 {
00469 msg.reset_required_cut_off_path.push_back(reset_required_cut_off_path.at(i));
00470 }
00471
00472 msg.current_monitoring_case_no_table_1 =
00473 general_system_state->getCurrentMonitoringCaseNoTable_1();
00474 msg.current_monitoring_case_no_table_2 =
00475 general_system_state->getCurrentMonitoringCaseNoTable_2();
00476 msg.current_monitoring_case_no_table_3 =
00477 general_system_state->getCurrentMonitoringCaseNoTable_3();
00478 msg.current_monitoring_case_no_table_4 =
00479 general_system_state->getCurrentMonitoringCaseNoTable_4();
00480
00481 msg.application_error = general_system_state->getApplicationError();
00482 msg.device_error = general_system_state->getDeviceError();
00483 }
00484 return msg;
00485 }
00486
00487 sick_safetyscanners::MeasurementDataMsg
00488 SickSafetyscannersRos::createMeasurementDataMessage(const sick::datastructure::Data& data)
00489 {
00490 sick_safetyscanners::MeasurementDataMsg msg;
00491
00492 if (!data.getMeasurementDataPtr()->isEmpty())
00493 {
00494 msg.number_of_beams = data.getMeasurementDataPtr()->getNumberOfBeams();
00495 msg.scan_points = createScanPointMessageVector(data);
00496 }
00497 return msg;
00498 }
00499
00500 std::vector<sick_safetyscanners::ScanPointMsg>
00501 SickSafetyscannersRos::createScanPointMessageVector(const sick::datastructure::Data& data)
00502 {
00503 std::vector<sick_safetyscanners::ScanPointMsg> msg_vector;
00504
00505 std::shared_ptr<sick::datastructure::MeasurementData> measurement_data =
00506 data.getMeasurementDataPtr();
00507 std::vector<sick::datastructure::ScanPoint> scan_points = measurement_data->getScanPointsVector();
00508 uint16_t num_points = measurement_data->getNumberOfBeams();
00509 for (uint16_t i = 0; i < num_points; i++)
00510 {
00511 sick::datastructure::ScanPoint scan_point = scan_points.at(i);
00512 sick_safetyscanners::ScanPointMsg msg;
00513 msg.distance = scan_point.getDistance();
00514 msg.reflectivity = scan_point.getReflectivity();
00515 msg.angle = scan_point.getAngle() + m_angle_offset;
00516 msg.valid = scan_point.getValidBit();
00517 msg.infinite = scan_point.getInfiniteBit();
00518 msg.glare = scan_point.getGlareBit();
00519 msg.reflector = scan_point.getReflectorBit();
00520 msg.contamination_warning = scan_point.getContaminationWarningBit();
00521 msg.contamination = scan_point.getContaminationBit();
00522
00523 msg_vector.push_back(msg);
00524 }
00525 return msg_vector;
00526 }
00527
00528 sick_safetyscanners::IntrusionDataMsg
00529 SickSafetyscannersRos::createIntrusionDataMessage(const sick::datastructure::Data& data)
00530 {
00531 sick_safetyscanners::IntrusionDataMsg msg;
00532
00533 if (!data.getIntrusionDataPtr()->isEmpty())
00534 {
00535 msg.data = createIntrusionDatumMessageVector(data);
00536 }
00537 return msg;
00538 }
00539
00540 std::vector<sick_safetyscanners::IntrusionDatumMsg>
00541 SickSafetyscannersRos::createIntrusionDatumMessageVector(const sick::datastructure::Data& data)
00542 {
00543 std::vector<sick_safetyscanners::IntrusionDatumMsg> msg_vector;
00544
00545 std::shared_ptr<sick::datastructure::IntrusionData> intrusion_data = data.getIntrusionDataPtr();
00546 std::vector<sick::datastructure::IntrusionDatum> intrusion_datums =
00547 intrusion_data->getIntrusionDataVector();
00548
00549 for (size_t i = 0; i < intrusion_datums.size(); i++)
00550 {
00551 sick_safetyscanners::IntrusionDatumMsg msg;
00552 sick::datastructure::IntrusionDatum intrusion_datum = intrusion_datums.at(i);
00553 msg.size = intrusion_datum.getSize();
00554 std::vector<bool> flags = intrusion_datum.getFlagsVector();
00555 for (size_t j = 0; j < flags.size(); j++)
00556 {
00557 msg.flags.push_back(flags.at(j));
00558 }
00559 msg_vector.push_back(msg);
00560 }
00561 return msg_vector;
00562 }
00563
00564 sick_safetyscanners::ApplicationDataMsg
00565 SickSafetyscannersRos::createApplicationDataMessage(const sick::datastructure::Data& data)
00566 {
00567 sick_safetyscanners::ApplicationDataMsg msg;
00568
00569 if (!data.getApplicationDataPtr()->isEmpty())
00570 {
00571 msg.inputs = createApplicationInputsMessage(data);
00572 msg.outputs = createApplicationOutputsMessage(data);
00573 }
00574 return msg;
00575 }
00576
00577 sick_safetyscanners::ApplicationInputsMsg
00578 SickSafetyscannersRos::createApplicationInputsMessage(const sick::datastructure::Data& data)
00579 {
00580 sick_safetyscanners::ApplicationInputsMsg msg;
00581
00582 std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
00583 sick::datastructure::ApplicationInputs inputs = app_data->getInputs();
00584 std::vector<bool> unsafe_inputs = inputs.getUnsafeInputsInputSourcesVector();
00585 std::vector<bool> unsafe_inputs_flags = inputs.getUnsafeInputsFlagsVector();
00586 for (size_t i = 0; i < unsafe_inputs.size(); i++)
00587 {
00588 msg.unsafe_inputs_input_sources.push_back(unsafe_inputs.at(i));
00589 msg.unsafe_inputs_flags.push_back(unsafe_inputs_flags.at(i));
00590 }
00591 std::vector<uint16_t> monitoring_case = inputs.getMonitoringCasevector();
00592 std::vector<bool> monitoring_case_flags = inputs.getMonitoringCaseFlagsVector();
00593 for (size_t i = 0; i < monitoring_case.size(); i++)
00594 {
00595 msg.monitoring_case_number_inputs.push_back(monitoring_case.at(i));
00596 msg.monitoring_case_number_inputs_flags.push_back(monitoring_case_flags.at(i));
00597 }
00598 msg.linear_velocity_inputs_velocity_0 = inputs.getVelocity0();
00599 msg.linear_velocity_inputs_velocity_0_transmitted_safely = inputs.getVelocity0TransmittedSafely();
00600 msg.linear_velocity_inputs_velocity_0_valid = inputs.getVelocity0Valid();
00601 msg.linear_velocity_inputs_velocity_1 = inputs.getVelocity1();
00602 msg.linear_velocity_inputs_velocity_1_transmitted_safely = inputs.getVelocity1TransmittedSafely();
00603 msg.linear_velocity_inputs_velocity_1_valid = inputs.getVelocity1Valid();
00604
00605 msg.sleep_mode_input = inputs.getSleepModeInput();
00606
00607 return msg;
00608 }
00609
00610 sick_safetyscanners::ApplicationOutputsMsg
00611 SickSafetyscannersRos::createApplicationOutputsMessage(const sick::datastructure::Data& data)
00612 {
00613 sick_safetyscanners::ApplicationOutputsMsg msg;
00614
00615 std::shared_ptr<sick::datastructure::ApplicationData> app_data = data.getApplicationDataPtr();
00616 sick::datastructure::ApplicationOutputs outputs = app_data->getOutputs();
00617
00618 std::vector<bool> eval_out = outputs.getEvalOutVector();
00619 std::vector<bool> eval_out_is_safe = outputs.getEvalOutIsSafeVector();
00620 std::vector<bool> eval_out_valid = outputs.getEvalOutIsValidVector();
00621 for (size_t i = 0; i < eval_out.size(); i++)
00622 {
00623 msg.evaluation_path_outputs_eval_out.push_back(eval_out.at(i));
00624 msg.evaluation_path_outputs_is_safe.push_back(eval_out_is_safe.at(i));
00625 msg.evaluation_path_outputs_is_valid.push_back(eval_out_valid.at(i));
00626 }
00627
00628 std::vector<uint16_t> monitoring_case = outputs.getMonitoringCaseVector();
00629 std::vector<bool> monitoring_case_flags = outputs.getMonitoringCaseFlagsVector();
00630 for (size_t i = 0; i < monitoring_case.size(); i++)
00631 {
00632 msg.monitoring_case_number_outputs.push_back(monitoring_case.at(i));
00633 msg.monitoring_case_number_outputs_flags.push_back(monitoring_case_flags.at(i));
00634 }
00635
00636 msg.sleep_mode_output = outputs.getSleepModeOutput();
00637 msg.sleep_mode_output_valid = outputs.getFlagsSleepModeOutputIsValid();
00638
00639 msg.error_flag_contamination_warning = outputs.getHostErrorFlagContaminationWarning();
00640 msg.error_flag_contamination_error = outputs.getHostErrorFlagContaminationError();
00641 msg.error_flag_manipulation_error = outputs.getHostErrorFlagManipulationError();
00642 msg.error_flag_glare = outputs.getHostErrorFlagGlare();
00643 msg.error_flag_reference_contour_intruded = outputs.getHostErrorFlagReferenceContourIntruded();
00644 msg.error_flag_critical_error = outputs.getHostErrorFlagCriticalError();
00645 msg.error_flags_are_valid = outputs.getFlagsHostErrorFlagsAreValid();
00646
00647 msg.linear_velocity_outputs_velocity_0 = outputs.getVelocity0();
00648 msg.linear_velocity_outputs_velocity_0_transmitted_safely =
00649 outputs.getVelocity0TransmittedSafely();
00650 msg.linear_velocity_outputs_velocity_0_valid = outputs.getVelocity0Valid();
00651 msg.linear_velocity_outputs_velocity_1 = outputs.getVelocity1();
00652 msg.linear_velocity_outputs_velocity_1_transmitted_safely =
00653 outputs.getVelocity1TransmittedSafely();
00654 msg.linear_velocity_outputs_velocity_1_valid = outputs.getVelocity1Valid();
00655
00656 std::vector<int16_t> resulting_velocities = outputs.getResultingVelocityVector();
00657 std::vector<bool> resulting_velocities_flags = outputs.getResultingVelocityIsValidVector();
00658
00659 for (size_t i = 0; i < resulting_velocities.size(); i++)
00660 {
00661 msg.resulting_velocity.push_back(resulting_velocities.at(i));
00662 msg.resulting_velocity_flags.push_back(resulting_velocities_flags.at(i));
00663 }
00664
00665
00666 return msg;
00667 }
00668
00669 bool SickSafetyscannersRos::getFieldData(sick_safetyscanners::FieldData::Request& req,
00670 sick_safetyscanners::FieldData::Response& res)
00671 {
00672 std::vector<sick::datastructure::FieldData> fields;
00673 m_device->requestFieldData(m_communication_settings, fields);
00674
00675 for (size_t i = 0; i < fields.size(); i++)
00676 {
00677 sick::datastructure::FieldData field = fields.at(i);
00678 sick_safetyscanners::FieldMsg field_msg;
00679
00680 field_msg.start_angle = degToRad(field.getStartAngle() + m_angle_offset);
00681 field_msg.angular_resolution = degToRad(field.getAngularBeamResolution());
00682 field_msg.protective_field = field.getIsProtectiveField();
00683
00684 std::vector<uint16_t> ranges = field.getBeamDistances();
00685 for (size_t j = 0; j < ranges.size(); j++)
00686 {
00687 field_msg.ranges.push_back(static_cast<float>(ranges.at(j)) * 1e-3);
00688 }
00689
00690 res.fields.push_back(field_msg);
00691 }
00692
00693 std::string device_name;
00694 m_device->requestDeviceName(m_communication_settings, device_name);
00695 res.device_name = device_name;
00696
00697
00698 std::vector<sick::datastructure::MonitoringCaseData> monitoring_cases;
00699 m_device->requestMonitoringCases(m_communication_settings, monitoring_cases);
00700
00701 for (size_t i = 0; i < monitoring_cases.size(); i++)
00702 {
00703 sick::datastructure::MonitoringCaseData monitoring_case_data = monitoring_cases.at(i);
00704 sick_safetyscanners::MonitoringCaseMsg monitoring_case_msg;
00705
00706 monitoring_case_msg.monitoring_case_number = monitoring_case_data.getMonitoringCaseNumber();
00707 std::vector<uint16_t> mon_fields = monitoring_case_data.getFieldIndices();
00708 std::vector<bool> mon_fields_valid = monitoring_case_data.getFieldsValid();
00709 for (size_t j = 0; j < mon_fields.size(); j++)
00710 {
00711 monitoring_case_msg.fields.push_back(mon_fields.at(j));
00712 monitoring_case_msg.fields_valid.push_back(mon_fields_valid.at(j));
00713 }
00714 res.monitoring_cases.push_back(monitoring_case_msg);
00715 }
00716
00717 return true;
00718 }
00719
00720
00721 }