Class Receiver
Defined in File receiver.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class Receiver : public rclcpp::Node
Abstract receiver class to decode CAN (FD) node frames. Needs to be extended for specific CAN node.
Public Types
-
using FrameId = uint32_t
-
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(), bool use_fd = false)
Construct a new Receiver object.
- Parameters:
node_name – Name of the node
options – Node options
use_fd – Enable CAN FD frames
-
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.
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
- Template Parameters:
Msg – Type of ROS message to send
Protected Functions
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
-
const bool use_fd_ = {false}
Use CAN FD frames, defaults to false.
-
bool use_j1939_ = {false}
Use J1939 protocol, defaults to false if J1939 protocol handling is not implemented for sensor.
-
using FrameId = uint32_t