Class Receiver

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class Receiver : public rclcpp::Node

Abstract receiver class to decode CAN node frames. Needs to be extended for specific CAN node.

Public Types

using FrameId = can_msgs::msg::Frame::_id_type
using FrameData = can_msgs::msg::Frame::_data_type
using Messages = std::unordered_map<FrameId, Message>
using DiagTask = diagnostic_updater::GenericFunctionDiagnosticTask<diagnostic_updater::DiagnosticStatusWrapper>
using DiagCompositeTask = diagnostic_updater::CompositeDiagnosticTask

Public Functions

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

Construct a new Receiver object.

virtual ~Receiver() = default

Destroy the Receiver object.

void initialize()

Initialize object (2nd step) by filling message definitions.

void start()

Initialize and start watchdog and subscription to receive frame messages.

void stop()

Stop subscription and watchdog.

void callback_can(const can_msgs::msg::Frame::ConstSharedPtr &frame)

Callback on received frames.

Checks if frame id is relevant for this instance. If yes, tries to decode message and checks for valid CRC and message counter. If valid, processes message.

Parameters:

frame – ROS CAN frame

Messages get_messages() const

Returns message definitions of configured CAN messages.

Protected Functions

void add_diag_task(const std::shared_ptr<diagnostic_updater::DiagnosticTask> &task)

Add diagnostic task to composite task for including it in the diagnostic updater.

Parameters:

task – Task to add

void force_diag_update()

Enforce diagnose update.

virtual Messages fillMessageDefinitions() = 0

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) = 0

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

virtual bool is_j1939_source_address_matching(uint8_t source_address)

Check if source address of received message matches configured J1939 source address.

Parameters:

source_address – Source address of received message

Protected Attributes

std::string node_frame_id_

Node TF frame id, needed in derived implementations for publishing with correct frame in header

bool use_j1939_ = {false}

Use J1939 protocol, defaults to false if J1939 protocol handling is not implemented for sensor.