Class SubscriptionManagerTF

Inheritance Relationships

Base Type

Class Documentation

class SubscriptionManagerTF : public SubscriptionManager

Manages and stores data of subscriptions to a specific TF topic.

The SubscriptionManager class is responsible for managing and storing data of subscriptions to a specific TF topic. It provides methods to manage the transforms, avoiding any missed transform

Public Functions

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

Constructs a SubscriptionManagerTF 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).

  • static_tf – Flag indicating whether the subscriber is a static transform .

virtual ~SubscriptionManagerTF()
virtual void check_subscription() override

Check if the subscription has been successful, or try to set it up.

virtual bool is_stale() const override

Check if the subscriber data is stale, but returns always false for static_tf.

void set_include_pattern(const std::vector<std::string> &pattern)

Store the vector of tf name include pattern, and convert them to std::regex.

Note: a transform is matched if either the frame_id or the child_frame_id match the regex.

void set_exclude_pattern(const std::vector<std::string> &pattern)

Store the vector of tf name exclude pattern, and convert them to std::regex.

Note: a transform is matched if either the frame_id or the child_frame_id match the regex.

Protected Functions

virtual void create_subscription(const std::string &topic, const std::string &msg_type, const rclcpp::QoS &qos) override

Create the subscriber.

This function creates the actual subscriber after setup-subscription has handled the qos and other params. Can be overloaded by specialized subscribers

void tf2_callback(const std::shared_ptr<const tf2_msgs::msg::TFMessage> &tfmsg)

Callback function for handling tf2 messages.

This function is called when a tf2 message is received by the subscription manager. It stores the recovered transforms in the tfs_ messages

Parameters:

tfmsg – A shared pointer to the tf2 message.

Protected Attributes

rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr tf2_subscriber_

The ROS2 TF2 subscriber object.

rclcpp::Serialization<tf2_msgs::msg::TFMessage> tf2_serialization_

The ROS2 TF2 serialization object.

std::map<std::pair<std::string, std::string>, size_t> tf_id_

Map linking (frame_id,child_frame_id) to the position in tf_s.

tf2_msgs::msg::TFMessage tfs_

TF message grouping all the transforms received so far.

bool static_tf_

Flag indicating if this a static tf topic.

std::vector<std::regex> include_pattern

List of accepted tf name pattern (frame_id or child), ignored if empty.

std::vector<std::regex> exclude_pattern

List of excluded tf name pattern (frame_id or child), ignored if empty.