Class NetworkBridge
Defined in File network_bridge.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class NetworkBridge : public rclcpp::Node
A class that provides bridging of ROS2 topics over a network interface.
The
NetworkBridge
class is derived from therclcpp::Node
class and provides functionality for sending and receiving telemetry data over network. It handles the setup of a network interface, parsing and creating headers, compressing and decompressing data, and error handling. The class also manages the ROS 2 subscriptions, timers, and publishers associated with the communication.Public Functions
-
explicit NetworkBridge(const std::string &node_name)
Constructs a NetworkBridge object.
This constructor initializes a NetworkBridge object with the specified node name.
- Parameters:
node_name – The name of the ROS 2 node.
-
~NetworkBridge() override
-
virtual void initialize()
Loads parameters, loads network interface, and opens the network interface.
It should be called before any other functions are called on the object.
-
virtual void shutdown()
Destroy the objects created by the bridge.
It should be called once spinning is over, and before the shared pointer is reset, to make sure the garbage collector can run
Protected Functions
-
virtual void load_parameters()
Loads default parameters and creates subsciption managers for each topic.
-
virtual void load_network_interface()
Loads the network interface as a dynamic plugin and initializes it.
-
virtual void receive_data(std::span<const uint8_t> data)
Callback function for handling received data.
- Parameters:
data – The data to be received, represented as a span.
Sends data to the network interface.
- Parameters:
manager – A shared pointer to the SubscriptionManager object.
-
void check_network_health()
-
virtual std::vector<uint8_t> create_header(const std::string &topic, const std::string &msg_type)
Creates a header for the message.
- Parameters:
topic – The topic of the message.
msg_type – The type of the message.
header – The header to be created.
-
virtual void parse_header(const std::vector<uint8_t> &header, std::string &topic, std::string &msg_type, double &time)
Parses the header of the message.
- Parameters:
header – The header to be parsed.
topic – The topic of the message.
msg_type – The type of the message.
time – The time the message was sent.
-
virtual void compress(std::vector<uint8_t> const &data, std::vector<uint8_t> &compressed_data, int zstd_compression_level = 3)
Compresses the given data using Zstandard compression algorithm.
- Parameters:
data – The input data to be compressed.
compressed_data – [out] The vector to store the compressed data.
zstd_compression_level – The compression level to be used (default: 3).
-
virtual void decompress(std::span<const uint8_t> compressed_data, std::vector<uint8_t> &data)
Decompresses the given compressed data.
This function takes a span of compressed data and decompresses it, storing the result in the provided data vector
- Parameters:
compressed_data – The compressed data to be decompressed.
data – [out] The vector to store the decompressed data.
Protected Attributes
-
pluginlib::ClassLoader<network_bridge::NetworkInterface> loader_
A class template that provides a plugin loader for network interfaces.
- Template Parameters:
InterfaceT – The interface type that the loaded plugins must implement.
-
std::string network_interface_name_
The name of the network interface plugin.
-
std::shared_ptr<network_bridge::NetworkInterface> network_interface_
A shared pointer to an instance of the
network_bridge::NetworkInterface
class.
-
std::vector<std::shared_ptr<SubscriptionManager>> sub_mgrs_
A vector of the SubscriptionManager’s for each topic.
These are stored to keep them from going out of scope, but are not used directly.
-
std::vector<rclcpp::TimerBase::SharedPtr> timers_
A vector of timers for sending each received topic over network.
These are stored to keep them from going out of scope.
See also
rclcpp::TimerBase
-
rclcpp::TimerBase::SharedPtr network_check_timer_
A time to check the network status, especially useful for tcp interface.
These are stored to keep them from going out of scope, but are not used directly.
See also
rclcpp::TimerBase
-
std::map<std::string, rclcpp::GenericPublisher::SharedPtr> publishers_
A map that stores the publisher object against the topic name.
-
std::string publish_namespace_
the namespace for the publishers.
-
explicit NetworkBridge(const std::string &node_name)