Template Class LiveSync< SyncT, SubscriberT, MsgPack< MsgTypes… > >

Class Documentation

template<typename SyncT, template<typename, typename> typename SubscriberT, typename ...MsgTypes>
class LiveSync<SyncT, SubscriberT, MsgPack<MsgTypes...>>

Class to subscribe to ROS2 topics using a given sync.

Public Types

typedef SyncT::Callback Callback

The type of callback to expect from this sync. A typical callback function signature would be

void foo(const std::vector<std::shared_ptr<const MsgType>> &vec1,
         const std::vector<std::shared_ptr<const MsgType>> &vec2)

Public Functions

inline LiveSync(rclcpp::Node *node, const std::vector<std::vector<string>> &topics, const Callback &callback, const rclcpp::QoS &qos)

Constructor for LiveSync, an object that will subscribe to topics and give synchronized callbacks, using the provided sync policy.

Parameters:
  • node – the node to use

  • topics – vector of vector of topics to subscribe, one vec per type

  • callback – called when sync is obtained across all msgs

  • qos – quality of service to use for subscriptions

inline std::shared_ptr<SyncT> getSync()
Returns:

sync object that was created.

inline rclcpp::Node *getNode()
Returns:

rclcpp node to be found.