Class MessageCreator

Class Documentation

class MessageCreator

Public Functions

MessageCreator(std::string frame_id, double time_offset, double range_min, double range_max, float angle_offset, double min_intensities)

Constructor of the Message helper class.

Parameters:
  • frame_id – The frame_id used for the laser scan

  • time_offset – Time offset to add to the timestamp due to timing issues

  • range_min – The minimum range for the sensor

  • range_max – The maximum range for the sensor

  • angle_offset – The offset added to the angle

  • min_intensities – Threshold to filter too low intensities

sensor_msgs::msg::LaserScan createLaserScanMsg(const sick::datastructure::Data &data, rclcpp::Time now)

Creates a Laserscan message from the parsed data.

Parameters:
  • data – The parsed data from the sensor

  • now – The current timestamp to give the message

Returns:

The constructed LaserScan Message

sick_safetyscanners2_interfaces::msg::OutputPaths createOutputPathsMsg(const sick::datastructure::Data &data)

Creates the Output Pats Message from the parsed data.

Parameters:

data – The parsed data from the sensor

Returns:

The constructed OutputPaths Message

sick_safetyscanners2_interfaces::msg::ExtendedLaserScan createExtendedLaserScanMsg(const sick::datastructure::Data &data, rclcpp::Time now)

Constructs an extended LaserScan including reflector values from the parsed data.

Parameters:
  • data – The parsed data from the sensor

  • now – The current timestamp to give the message

Returns:

The constructed extended LaserScan Message

sick_safetyscanners2_interfaces::msg::RawMicroScanData createRawDataMsg(const sick::datastructure::Data &data)

Constructs a message containing all raw values from the sensor.

Parameters:

data – The parsed data from the sensor

Returns:

The raw values of the sensor in a ROS2 Message.