Template Class StampedVariableSynchronizer

Class Documentation

template<typename ...Ts>
class StampedVariableSynchronizer

A utility class that finds the most recent timestamp shared by a set of stamped variables.

This is designed to be used by derived fuse_core::Publisher classes. The class remembers the last common timestamp from the previous call, and attempts to find a more recent common timestamp using the provided transaction information. If no common timestamp is found after searching the transaction, a full search of the graph will be conducted. If no common timestamp is found after searching the full graph, a zero timestamp will be returned.

The set of variable types are provided in the template parameters. e.g.

auto synchronizer = StampedVariableSynchronizer<Orientation2DStamped, Position2DStamped>(device_id);

This class only functions with variables derived from the fuse_variables::Stamped base class.

Public Functions

explicit StampedVariableSynchronizer(const fuse_core::UUID &device_id = fuse_core::uuid::NIL)

Construct a synchronizer object.

Parameters:

device_id[in] The device id to use for all variable types

rclcpp::Time findLatestCommonStamp(const fuse_core::Transaction &transaction, const fuse_core::Graph &graph)

Find the latest timestamp for which variables of all the specified template types exist in the graph.

Parameters:
  • transaction[in] A fuse_core::Transaction object containing the changes to the graph since the last call

  • graph[in] The complete graph

Returns:

The latest timestamp shared by all requested variable types