Class SickSafetyscanners

Nested Relationships

Nested Types

Inheritance Relationships

Derived Types

Class Documentation

class SickSafetyscanners

Sick safety scanners base class that implements the shared functionality between the Node (Ros2) and LifCycle node (LifeCycle)

Subclassed by sick::SickSafetyscannersLifeCycle, sick::SickSafetyscannersRos2

Public Types

using DiagnosedLaserScanPublisher = diagnostic_updater::DiagnosedPublisher<sensor_msgs::msg::LaserScan>

Public Functions

template<typename NodeT>
inline void loadParameters(NodeT &node)

Load the initial parameters

This method is a template function because the node and lifecycle node are not sharing the same implementation but have the same interface.

Template Parameters:

NodeT – Templated node input

Parameters:

node – Node

rcl_interfaces::msg::SetParametersResult parametersCallback(std::vector<rclcpp::Parameter> parameters)
void setupCommunication(std::function<void(const sick::datastructure::Data&)> callback)

Setup the device communication

Parameters:

callback – Callback that fires when a new UDP packet is received

template<typename NodeT>
inline void startCommunication(NodeT *node, rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr publisher)

Start the sensor communication by receiving UDP packets

void stopCommunication()

Stop the sensor communication

void sensorDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &diagnostic_status)
bool getFieldData(const std::shared_ptr<sick_safetyscanners2_interfaces::srv::FieldData::Request> request, std::shared_ptr<sick_safetyscanners2_interfaces::srv::FieldData::Response> response)
void readPersistentConfig()
void readTypeCodeSettings()
void readMetadata()
void readFirmwareVersion()

Public Members

Config m_config
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr m_param_callback
std::shared_ptr<diagnostic_updater::Updater> m_diagnostic_updater
std::shared_ptr<DiagnosedLaserScanPublisher> m_diagnosed_laser_scan_publisher
std::unique_ptr<sick::AsyncSickSafetyScanner> m_device
sick_safetyscanners2_interfaces::msg::RawMicroScanData m_last_raw_msg

Public Static Functions

template<typename NodeT>
static inline void initializeParameters(NodeT &node)

Initialize parameters for this node

This method is a template function because the node and lifecycle node are not sharing the same implementation but have the same interface.

Template Parameters:

NodeT – Templated node input

Parameters:

node – Node

struct Config

Sick safety scanner configuration

Public Functions

inline void setupMsgCreator()

Public Members

boost::asio::ip::address_v4 m_sensor_ip
boost::asio::ip::address_v4 m_interface_ip
std::string m_frame_id
double m_time_offset = 0.0
double m_range_min = 0.0
double m_range_max
double m_frequency_tolerance = 0.1
double m_expected_frequency = 34.0
double m_timestamp_min_acceptable = -1.0
double m_timestamp_max_acceptable = 1.0
double m_min_intensities = 0.0

min intensities for laser points

bool m_use_sick_angles
float m_angle_offset = -90.0
bool m_use_pers_conf = false
sick::types::port_t m_tcp_port = 2122
datastructure::ConfigMetadata m_metadata
datastructure::FirmwareVersion m_firmware_version
sick::datastructure::CommSettings m_communications_settings
std::unique_ptr<sick::MessageCreator> m_msg_creator