Class SubscriptionManager

Class Documentation

class SubscriptionManager

Manages and stores data of subscriptions to a specific topic.

The SubscriptionManager class is responsible for managing and storing data of subscriptions to a specific topic. It provides methods to retrieve the stored data and set up subscriptions for the topic.

Public Functions

SubscriptionManager(const rclcpp::Node::SharedPtr &node, const std::string &topic, const std::string &subscribe_namespace, int zstd_compression_level = 3, bool publish_stale_data = false)

Constructs a SubscriptionManager object.

This constructor initializes a SubscriptionManager object with the given parameters.

Parameters:
  • node – A pointer to the rclcpp::Node object.

  • topic – The topic to subscribe to.

  • zstd_compression_level – The compression level for Zstandard compression (default: 3).

  • namespace – The namespace for the subscription.

  • publish_stale_data – Flag indicating whether to publish stale data (default: false).

const std::vector<uint8_t> &get_data()

Retrieves the data stored in the subscription manager.

This method returns a constant reference to the vector containing the stored data. If no data has been received or if the data is stale and the flag publish_stale_data_ is false, an empty vector is returned.

Returns:

A constant reference to the vector containing the data.

Public Members

std::string msg_type_

The type of message stored in the subscription manager.

std::string topic_

The topic name for the subscription.

std::string subscribe_namespace_

The namespace for the subscription.

int zstd_compression_level_

The compression level used for Zstandard compression (1->22).

Protected Functions

void setup_subscription()

Sets up a subscription for a given topic.

This function sets up a subscription for the specified topic. It takes a string parameter representing the topic to subscribe to. This function is called automatically in the constructor and get_data() method. It fails if the topic does not exist or if there are no publishers on this topic.

void callback(const std::shared_ptr<const rclcpp::SerializedMessage> &serialized_msg)

Callback function for handling serialized messages.

This function is called when a serialized message is received by the subscription manager. It stores the data from serialized_msg into the data_ vector.

Parameters:

serialized_msg – A shared pointer to the serialized message.

Protected Attributes

const rclcpp::Node::SharedPtr node_

Pointer to the ROS 2 node.

bool received_msg_

Flag indicating whether a message has ever been received.

bool is_stale_

Flag indicating whether the data is stale (already accessed via get_data()).

bool publish_stale_data_

Flag indicating whether to publish stale data.

rclcpp::GenericSubscription::SharedPtr subscriber

The ROS2 generalized subscriber object.

std::vector<uint8_t> data_

The data buffer for the subscription manager.