Class SerializedPublisher

Inheritance Relationships

Base Type

  • public fuse_core::AsyncPublisher

Class Documentation

class SerializedPublisher : public fuse_core::AsyncPublisher

Publisher plugin that publishes the transaction and graph as serialized messages.

Public Functions

SerializedPublisher()

Constructor.

virtual ~SerializedPublisher() = default

Destructor.

void initialize(fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces, const std::string &name) override

Shadowing extension to the AsyncPublisher::initialize call.

virtual void onInit() override

Perform any required post-construction initialization, such as advertising publishers or reading from the parameter server.

void notifyCallback(fuse_core::Transaction::ConstSharedPtr transaction, fuse_core::Graph::ConstSharedPtr graph) override

Notify the publisher about variables that have been added or removed.

Parameters:
  • transaction[in] A Transaction object, describing the set of variables that have been added and/or removed

  • graph[in] A read-only pointer to the graph object, allowing queries to be performed whenever needed

Protected Types

using GraphPublisherCallback = std::function<void(fuse_core::Graph::ConstSharedPtr, const rclcpp::Time&)>
using GraphPublisherThrottledCallback = fuse_core::ThrottledCallback<GraphPublisherCallback>

Protected Functions

void graphPublisherCallback(fuse_core::Graph::ConstSharedPtr graph, const rclcpp::Time &stamp) const

Publish the serialized graph.

Parameters:
  • graph[in] A read-only pointer to the graph object, allowing queries to be performed whenever needed

  • stamp[in] A rclcpp::Time stamp used for the serialized graph message published

Protected Attributes

fuse_core::node_interfaces::NodeInterfaces<fuse_core::node_interfaces::Base, fuse_core::node_interfaces::Clock, fuse_core::node_interfaces::Logging, fuse_core::node_interfaces::Parameters, fuse_core::node_interfaces::Topics, fuse_core::node_interfaces::Waitables> interfaces_

Shadows AsyncPublisher interfaces_.

std::string frame_id_

The name of the frame for the serialized graph and transaction messages published

rclcpp::Publisher<fuse_msgs::msg::SerializedGraph>::SharedPtr graph_publisher_
rclcpp::Publisher<fuse_msgs::msg::SerializedTransaction>::SharedPtr transaction_publisher_
GraphPublisherThrottledCallback graph_publisher_throttled_callback_

The graph publisher throttled callback