Class Publisher

Inheritance Relationships

Derived Type

Class Documentation

class Publisher

The interface class for publisher plugins in the fuse ecosystem.

A publisher plugin is responsible for querying the latest variable value from the optimized Graph, converting the variable values into ROS messages, and publishing the messages on their desired topics. Publisher plugins will be loaded by the optimizer at run/configure time. The optimizer will notify the plugins after the graph has been optimized. This class defines the supported interface between the optimizer and publisher. If you are deriving a new publisher class, consider using fuse_core::AsyncPublisher as the base class instead. It offers additional features making it act similar to a standard node or nodelet.

Subclassed by fuse_core::AsyncPublisher

Public Functions

Publisher() = default

Constructor.

All ROS plugins must provide a default constructor for use with the plugin loader.

virtual ~Publisher() = default

Destructor.

virtual void initialize(node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces, const std::string &name) = 0

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

This will be called on each plugin after construction, and after the ros node has been initialized. Plugins are encouraged to subnamespace any of their parameters to prevent conflicts and allow the same plugin to be used multiple times with different settings and topics.

This requires all possible interfaces, but plugins may choose to use only some of them.

Parameters:

name[in] A unique name to give this plugin instance

virtual const std::string &name() const = 0

Get the unique name of this publisher.

virtual void notify(Transaction::ConstSharedPtr transaction, Graph::ConstSharedPtr graph) = 0

Notify the publisher that an optimization cycle is complete, and about changes to the Graph.

Most publishers will only publish new data whenever the Graph values have been updated. The Publisher::notify() method will be called by the optimizer (and in the optimizer’s thread) after every optimization cycle is complete. Additionally, the set of added and removed variables and constraints since the last optimization cycle will be provided to the publisher. In many cases this should prevent the plugins from searching through the entire graph, looking for the variables of interest.

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

inline virtual void start()

Function to be executed whenever the optimizer is ready to receive transactions.

This method will be called by the optimizer, in the optimizer’s thread, once the optimizer has been initialized and is ready to receive transactions. It may also be called as part of a stop-start cycle when the optimizer has been requested to reset itself. This allows the publisher to reset any internal state before the optimizer begins processing after a reset. No calls to notify() will happen before the optimizer calls start().

inline virtual void stop()

Function to be executed whenever the optimizer is no longer ready to receive transactions.

This method will be called by the optimizer, in the optimizer’s thread, before the optimizer shutdowns. It may also be called as part of a stop-start cycle when the optimizer has been requested to reset itself. This allows the publisher to reset any internal state before the optimizer begins processing after a reset. No calls to notify() will happen until start() has been called again.