44 , m_initialised(false)
48 , m_angle_offset(-90.0)
49 , m_use_pers_conf(false)
51 dynamic_reconfigure::Server<
52 sick_safetyscanners::SickSafetyscannersConfigurationConfig>::CallbackType reconf_callback =
64 m_nh.
advertise<sick_safetyscanners::ExtendedLaserScanMsg>(
"extended_laser_scan", 100);
67 m_nh.
advertise<sick_safetyscanners::OutputPathsMsg>(
"output_paths", 100);
71 m_device = std::make_shared<sick::SickSafetyscanners>(
83 ROS_INFO(
"Successfully launched node.");
88 ROS_INFO(
"Reading Type code settings");
98 ROS_INFO(
"Reading Persistent Configuration");
106 const sick_safetyscanners::SickSafetyscannersConfigurationConfig& config,
const uint32_t& level)
112 if (config.angle_start == config.angle_end)
123 config.derived_settings,
124 config.measurement_data,
125 config.intrusion_data,
126 config.application_io_data);
145 std::string sensor_ip_adress =
"192.168.1.10";
149 ROS_WARN(
"Using default sensor IP: %s", sensor_ip_adress.c_str());
154 std::string host_ip_adress =
"192.168.1.9";
157 ROS_WARN(
"Using default host IP: %s", host_ip_adress.c_str());
161 int host_udp_port = 0;
164 ROS_WARN(
"Using default host UDP Port: %i", host_udp_port);
168 ROS_WARN(
"If not further specified the default values for the dynamic reconfigurable parameters " 191 if (angle_start == angle_end)
202 bool general_system_state;
205 bool derived_settings;
208 bool measurement_data;
214 bool application_io_data;
218 general_system_state, derived_settings, measurement_data, intrusion_data, application_io_data);
252 sick_safetyscanners::ExtendedLaserScanMsg
256 sick_safetyscanners::ExtendedLaserScanMsg msg;
257 msg.laser_scan = scan;
260 std::vector<sick::datastructure::ScanPoint> scan_points =
263 msg.reflektor_status.resize(num_scan_points);
264 msg.intrusion.resize(num_scan_points);
265 msg.reflektor_median.resize(num_scan_points);
267 for (uint16_t i = 0; i < num_scan_points; ++i)
272 msg.reflektor_median[i] = medians.at(i);
278 const std::vector<sick::datastructure::ScanPoint> scan_points)
280 std::vector<bool> res;
281 res.resize(scan_points.size());
284 for (
size_t i = 0; i < scan_points.size(); i++)
287 if (!last && scan_points.at(i).getReflectorBit())
292 else if (last && (!scan_points.at(i).getReflectorBit() || i == scan_points.size() - 1))
295 res.at(start + ((i - start) / 2)) =
true;
302 sensor_msgs::LaserScan
305 sensor_msgs::LaserScan scan;
315 ->getScanPointsVector()
319 scan.angle_max = angle_max;
321 boost::posix_time::microseconds time_increment =
323 scan.time_increment = time_increment.total_microseconds() * 1e-6;
324 boost::posix_time::milliseconds scan_time =
326 scan.scan_time = scan_time.total_microseconds() * 1e-6;
329 scan.ranges.resize(num_scan_points);
330 scan.intensities.resize(num_scan_points);
333 std::vector<sick::datastructure::ScanPoint> scan_points =
335 for (uint16_t i = 0; i < num_scan_points; ++i)
338 scan.ranges[i] =
static_cast<float>(scan_point.
getDistance()) *
340 scan.intensities[i] =
static_cast<float>(scan_point.
getReflectivity());
346 sick_safetyscanners::OutputPathsMsg
349 sick_safetyscanners::OutputPathsMsg msg;
360 if (monitoring_case_number_flags.at(0))
362 msg.active_monitoring_case = monitoring_case_numbers.at(0);
365 for (
size_t i = 0; i < eval_out.size(); i++)
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));
374 sick_safetyscanners::RawMicroScanDataMsg
377 sick_safetyscanners::RawMicroScanDataMsg msg;
389 sick_safetyscanners::DataHeaderMsg
392 sick_safetyscanners::DataHeaderMsg msg;
396 std::shared_ptr<sick::datastructure::DataHeader> data_header = data.
getDataHeaderPtr();
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();
403 msg.scan_number = data_header->getScanNumber();
404 msg.sequence_number = data_header->getSequenceNumber();
406 msg.serial_number_of_device = data_header->getSerialNumberOfDevice();
407 msg.serial_number_of_channel_plug = data_header->getSerialNumberOfSystemPlug();
409 msg.channel_number = data_header->getChannelNumber();
411 msg.timestamp_date = data_header->getTimestampDate();
412 msg.timestamp_time = data_header->getTimestampTime();
417 sick_safetyscanners::DerivedValuesMsg
420 sick_safetyscanners::DerivedValuesMsg msg;
424 std::shared_ptr<sick::datastructure::DerivedValues> derived_values = data.
getDerivedValuesPtr();
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();
436 sick_safetyscanners::GeneralSystemStateMsg
439 sick_safetyscanners::GeneralSystemStateMsg msg;
443 std::shared_ptr<sick::datastructure::GeneralSystemState> general_system_state =
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();
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++)
456 msg.safe_cut_off_path.push_back(safe_cut_off_path.at(i));
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++)
462 msg.non_safe_cut_off_path.push_back(non_safe_cut_off_path.at(i));
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++)
469 msg.reset_required_cut_off_path.push_back(reset_required_cut_off_path.at(i));
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();
481 msg.application_error = general_system_state->getApplicationError();
482 msg.device_error = general_system_state->getDeviceError();
487 sick_safetyscanners::MeasurementDataMsg
490 sick_safetyscanners::MeasurementDataMsg msg;
500 std::vector<sick_safetyscanners::ScanPointMsg>
503 std::vector<sick_safetyscanners::ScanPointMsg> msg_vector;
505 std::shared_ptr<sick::datastructure::MeasurementData> measurement_data =
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++)
512 sick_safetyscanners::ScanPointMsg msg;
523 msg_vector.push_back(msg);
528 sick_safetyscanners::IntrusionDataMsg
531 sick_safetyscanners::IntrusionDataMsg msg;
540 std::vector<sick_safetyscanners::IntrusionDatumMsg>
543 std::vector<sick_safetyscanners::IntrusionDatumMsg> msg_vector;
545 std::shared_ptr<sick::datastructure::IntrusionData> intrusion_data = data.
getIntrusionDataPtr();
546 std::vector<sick::datastructure::IntrusionDatum> intrusion_datums =
547 intrusion_data->getIntrusionDataVector();
549 for (
size_t i = 0; i < intrusion_datums.size(); i++)
551 sick_safetyscanners::IntrusionDatumMsg msg;
553 msg.size = intrusion_datum.
getSize();
555 for (
size_t j = 0; j < flags.size(); j++)
557 msg.flags.push_back(flags.at(j));
559 msg_vector.push_back(msg);
564 sick_safetyscanners::ApplicationDataMsg
567 sick_safetyscanners::ApplicationDataMsg msg;
577 sick_safetyscanners::ApplicationInputsMsg
580 sick_safetyscanners::ApplicationInputsMsg msg;
586 for (
size_t i = 0; i < unsafe_inputs.size(); i++)
588 msg.unsafe_inputs_input_sources.push_back(unsafe_inputs.at(i));
589 msg.unsafe_inputs_flags.push_back(unsafe_inputs_flags.at(i));
593 for (
size_t i = 0; i < monitoring_case.size(); i++)
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));
598 msg.linear_velocity_inputs_velocity_0 = inputs.
getVelocity0();
601 msg.linear_velocity_inputs_velocity_1 = inputs.
getVelocity1();
610 sick_safetyscanners::ApplicationOutputsMsg
613 sick_safetyscanners::ApplicationOutputsMsg msg;
621 for (
size_t i = 0; i < eval_out.size(); i++)
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));
630 for (
size_t i = 0; i < monitoring_case.size(); i++)
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));
647 msg.linear_velocity_outputs_velocity_0 = outputs.
getVelocity0();
648 msg.linear_velocity_outputs_velocity_0_transmitted_safely =
651 msg.linear_velocity_outputs_velocity_1 = outputs.
getVelocity1();
652 msg.linear_velocity_outputs_velocity_1_transmitted_safely =
659 for (
size_t i = 0; i < resulting_velocities.size(); i++)
661 msg.resulting_velocity.push_back(resulting_velocities.at(i));
662 msg.resulting_velocity_flags.push_back(resulting_velocities_flags.at(i));
670 sick_safetyscanners::FieldData::Response& res)
672 std::vector<sick::datastructure::FieldData> fields;
675 for (
size_t i = 0; i < fields.size(); i++)
678 sick_safetyscanners::FieldMsg field_msg;
685 for (
size_t j = 0; j < ranges.size(); j++)
687 field_msg.ranges.push_back(static_cast<float>(ranges.at(j)) * 1e-3);
690 res.fields.push_back(field_msg);
693 std::string device_name;
695 res.device_name = device_name;
698 std::vector<sick::datastructure::MonitoringCaseData> monitoring_cases;
701 for (
size_t i = 0; i < monitoring_cases.size(); i++)
704 sick_safetyscanners::MonitoringCaseMsg monitoring_case_msg;
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++)
711 monitoring_case_msg.fields.push_back(mon_fields.at(j));
712 monitoring_case_msg.fields_valid.push_back(mon_fields_valid.at(j));
714 res.monitoring_cases.push_back(monitoring_case_msg);
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.
sick_safetyscanners::MeasurementDataMsg createMeasurementDataMessage(const sick::datastructure::Data &data)
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.
bool getHostErrorFlagContaminationError() const
Gets if a contamination error is present.
bool getFlagsSleepModeOutputIsValid() const
Gets if the sleep mode is valid.
void publish(const boost::shared_ptr< M > &message) const
bool getInfiniteBit() const
Returns if the scanpoint is infinite.
void setSensorTcpPort(const uint16_t &sensor_tcp_port)
Sets the sensor tcp port.
int32_t getSize() const
Returns size of flag vector.
std::vector< bool > getResultingVelocityIsValidVector() const
Gets if the resulting velocities are valid.
std::shared_ptr< ApplicationData > getApplicationDataPtr() const
Gets the application data.
bool getIsProtectiveField() const
Returns if a field is a protective field.
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.
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.
std::vector< uint16_t > getMonitoringCaseVector() const
Gets the currently active monitoring case numbers.
Class containing the data of a single scan point.
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.
Field data for warning and protective fields.
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.
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.
uint16_t getDistance() const
Getter for the distance of the scanpoint.
std::vector< bool > getFlagsVector() const
Getter for the flags vector.
sick_safetyscanners::ApplicationDataMsg createApplicationDataMessage(const sick::datastructure::Data &data)
std::shared_ptr< IntrusionData > getIntrusionDataPtr() const
Gets the intrusion data.
The data class containing all data blocks of a measurement.
dynamic_reconfigure::Server< sick_safetyscanners::SickSafetyscannersConfigurationConfig > m_dynamic_reconfiguration_server
bool getGlareBit() const
Returns if the scanpoint has glare.
bool getValidBit() const
Returns if the scanpoint is valid.
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.
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.
bool getFieldData(sick_safetyscanners::FieldData::Request &req, sick_safetyscanners::FieldData::Response &res)
bool getFlagsHostErrorFlagsAreValid() const
Gets if the error flags are valid.
ros::Publisher m_output_path_publisher
Duration & fromSec(double t)
void receivedUDPPacket(const datastructure::Data &data)
Function which is called when a new complete UDP Packet is received.
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.
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.
sick::datastructure::CommSettings m_communication_settings
The application outputs from a udp data packet.
Config data for current and persistent sensor config.
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.
ros::Publisher m_raw_data_publisher
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.
void readTypeCodeSettings()
Class containing the type code of a laser scanner.
std::shared_ptr< GeneralSystemState > getGeneralSystemStatePtr() const
Gets the general system state.
std::shared_ptr< DataHeader > getDataHeaderPtr() const
Gets the data header.
bool readParameters()
Reads and verifies the ROS parameters.
bool getHostErrorFlagCriticalError() const
Gets if a critical error is present.
float getEndAngle() const
Get the end angle of the configuration.
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.
void readPersistentConfig()
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.
uint16_t getMonitoringCaseNumber() const
Returns the number of the monitoring case.
std::shared_ptr< DerivedValues > getDerivedValuesPtr() const
Gets the derived values.
float getAngularBeamResolution() const
Returns the angular resolution between the beams.
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.