Class Converter

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class Converter : public off_highway_premium_radar_sample::Receiver

Converter interface to receive and send sensor data.

Subclassed by off_highway_premium_radar_sample::DefaultConverter

Public Types

using SharedPtr = std::shared_ptr<Converter>

Public Functions

virtual ~Converter() = default

Destructor.

inline virtual void configure(rclcpp::Node::WeakPtr parent, Sender::SharedPtr sender)

Configure converter with parent node and sender interface.

virtual void on_configure() = 0

Callback that is called in configure.

Protected Functions

inline rclcpp::Time decide_on_stamp(uint32_t sensor_sec, uint32_t sensor_nanosec)

Decide to use sensor or ROS time stamp and get it.

Sensor time may not be compatible since ROS uses int32 as type for the seconds in its time message while the sensor uses uint32. This method falls back to ROS time in an incompatible case.

Parameters:
  • sensor_sec – Sensor seconds

  • sensor_nanosec – Sensor nanoseconds

Returns:

Timestamp to use

Protected Attributes

rclcpp::Node::WeakPtr parent_

Parent node.

Sender::SharedPtr sender_

Sender interface to send data to sensor.

rclcpp::Clock::SharedPtr clock_

Clock to use.

rclcpp::Logger logger_ = {rclcpp::get_logger("Converter")}

Logger to use.

std::string frame_id_ = {"base_link"}

Frame ID for messages.

bool use_sensor_time_ = {false}

Stamp messages with time from sensor if possible for message or with ROS time.