Class Receiver

Inheritance Relationships

Derived Type

Class Documentation

class Receiver

Receiver interface.

Subclassed by off_highway_premium_radar_sample::Converter

Public Types

using SharedPtr = std::shared_ptr<Receiver>

Public Functions

virtual ~Receiver() = default

Destructor.

inline virtual void on_location_data(const LocationData&)

Called from receiving thread on receiving a full location data measurement.

Parameters:

data – Location data measurement (in host order)

inline virtual void on_sensor_feedback(const SensorFeedback&)

Called from receiving thread on receiving a sensor feedback PDU.

Parameters:

data – Sensor feedback PDU (in host order)

inline virtual void on_sensor_state_information(const SensorStateInformation&)

Called from receiving thread on receiving a sensor information PDU.

Parameters:

data – Sensor information PDU (in host order)

inline virtual void on_sensor_broadcast(const SensorBroadcast&)

Called from receiving thread on receiving a sensor broadcast PDU.

Parameters:

data – Sensor broadcast PDU (in host order)

inline virtual void on_location_attributes(const LocationAttributes&)

Called from receiving thread on receiving a location attributes PDU.

Parameters:

data – Location attributes PDU (in host order)

inline virtual void on_sensor_dtc_information(const SensorDTCInformation&)

Called from receiving thread on receiving a sensor DTC information PDU.

Parameters:

data – Sensor information PDU (in host order)