Class Receiver

Inheritance Relationships

Base Type

  • public off_highway_can::Receiver

Class Documentation

class Receiver : public off_highway_can::Receiver

Uss receiver class to decode CAN frames into object list and echo list to publish.

Object list is published as simple list or as point cloud. Echo list is only published as simple list. Sensor information frame is used as diagnostic input and also published directly.

Line objects in point cloud are sampled along the line.

Public Types

using Message = off_highway_can::Message
using Object = off_highway_uss_msgs::msg::Object
using Objects = off_highway_uss_msgs::msg::Objects
using Echo = off_highway_uss_msgs::msg::Echo
using DirectEcho = off_highway_uss_msgs::msg::DirectEcho
using DirectEchos = off_highway_uss_msgs::msg::DirectEchos
using MaxDetectionRange = off_highway_uss_msgs::msg::MaxDetectionRange
using Information = off_highway_uss_msgs::msg::Information

Public Functions

explicit Receiver(const std::string &node_name = "receiver", const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a new Receiver object.

~Receiver() = default

Destroy the Receiver object.

Protected Functions

virtual Messages fillMessageDefinitions() override

Fill message definitions to decode frames of CAN node. Only stored definitions are processed.

Returns:

Messages of CAN node to decode and process

virtual void process(std_msgs::msg::Header header, const FrameId &id, Message &message) override

Process CAN message (e.g. convert into own data type).

Parameters:
  • header – Header of corresponding ROS message

  • id – Id of respective CAN frame

  • message – Decoded message (values) of frame to use for processing

template<typename T>
void manage(T &l)

Filter list and remove too old elements from list.

bool filter(const Object &object)

Check if object is invalid.

Parameters:

object – Object to check

Returns:

True if object is invalid and should be filtered, false otherwise

void manage_and_publish_objects()

Manage object list and publish it.

void publish_objects()

Publish objects as list.

void publish_pcl()

Publish objects as point cloud.

bool filter(const DirectEcho &direct_echo)

Check if echo is invalid.

Parameters:

direct_echo – Echo to check

Returns:

True if echo is invalid and should be filtered, false otherwise

void manage_and_publish_direct_echos()

Manage echo list and publish it.

void publish_direct_echos()

Publish echos as list.

void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat) const

Update diagnostics status by checking last sensor information.

Uses sensor blindness, sensor faulted and failure status of sensor information message to indicate sensor error.

Parameters:

stat – Status wrapper of diagnostics.

void declare_and_get_parameters()

Declare and get node parameters.

Protected Attributes

Information info_
std::shared_ptr<DiagTask> diag_task_
rclcpp::Publisher<Objects>::SharedPtr pub_objects_
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_objects_pcl_
rclcpp::Publisher<DirectEchos>::SharedPtr pub_direct_echos_
rclcpp::Publisher<MaxDetectionRange>::SharedPtr pub_max_detection_range_
rclcpp::Publisher<Information>::SharedPtr pub_info_
rclcpp::TimerBase::SharedPtr publish_objects_timer_
rclcpp::TimerBase::SharedPtr publish_direct_echos_timer_
uint32_t can_id_offset_

CAN frame id offset for functional frames.

uint32_t object_base_id_

CAN id of first object message (USS_MAP_OBJ_01)

uint32_t direct_echo_base_id_

CAN id of first direct echo message (USS_DEMsg_Sens_01)

uint32_t info_id_
uint32_t max_detection_range_id_
double allowed_age_

Allowed age of objects and echos.

double line_sample_distance_

Sample distance along line of line objects.

double publish_frequency_
std::array<std::optional<Object>, kCountObjects> objects_

Objects stored as optionals in fixed-size array to encode validity while ensuring order.

std::array<std::optional<DirectEcho>, kCountDirectEchos> direct_echos_

Echos stored as optionals in fixed-size array to encode validity while ensuring order.

Protected Static Attributes

static constexpr uint8_t kDirectEchoBaseIdOffset = 0x0
static constexpr uint8_t kInfoIdOffset = 0x0C
static constexpr uint8_t kMaxDetectionRangeIdOffset = 0xD
static constexpr uint8_t kObjectBaseIdOffset = 0x10
static constexpr uint8_t kCountObjects = 20
static constexpr uint8_t kCountObjectFrames = kCountObjects / 2
static constexpr uint8_t kCountDirectEchos = 12
static constexpr double kCentimeterToMeter = 0.01
static constexpr std::array<double, 8> kExistProbabilitySteps = {0.0, 17.0, 23.0, 30.0, 40.0, 60.0, 80.0, 100.0}