Class Bond

Class Documentation

class Bond

Forms a bond to monitor another process.

The bond::Bond class implements a bond, allowing you to monitor another process and be notified when it dies. In turn, it will be notified when you die.

Public Types

using EventCallback = std::function<void(void)>

Public Functions

BONDCPP_PUBLIC Bond(const std::string &topic, const std::string &id, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params, rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, EventCallback on_broken = EventCallback(), EventCallback on_formed = EventCallback())

Constructor to delegate common functionality.

Parameters:
  • topic – The topic used to exchange the bond status messages.

  • id – The ID of the bond, which should match the ID used on the sister’s end.

  • node_base – base node interface

  • node_logging – logging node interface

  • node_timers – timers node interface

  • on_broken – callback that will be called when the bond is broken.

  • on_formed – callback that will be called when the bond is formed.

BONDCPP_PUBLIC Bond(const std::string &topic, const std::string &id, rclcpp_lifecycle::LifecycleNode::SharedPtr nh, EventCallback on_broken = EventCallback(), EventCallback on_formed = EventCallback())

Constructs a bond, but does not connect.

Parameters:
  • topic – The topic used to exchange the bond status messages.

  • id – The ID of the bond, which should match the ID used on the sister’s end.

  • nh – Lifecycle Node shared ptr.

  • on_broken – callback that will be called when the bond is broken.

  • on_formed – callback that will be called when the bond is formed.

BONDCPP_PUBLIC Bond(const std::string &topic, const std::string &id, rclcpp::Node::SharedPtr nh, EventCallback on_broken = EventCallback(), EventCallback on_formed = EventCallback())

Constructs a bond, but does not connect.

Parameters:
  • topic – The topic used to exchange the bond status messages.

  • id – The ID of the bond, which should match the ID used on the sister’s end.

  • nh – Node shared ptr.

  • on_broken – callback that will be called when the bond is broken.

  • on_formed – callback that will be called when the bond is formed.

BONDCPP_PUBLIC ~Bond()

Destructs the object, breaking the bond if it is still formed.

BONDCPP_PUBLIC void setupConnections ()
inline BONDCPP_PUBLIC double getConnectTimeout () const
BONDCPP_PUBLIC void setConnectTimeout (double dur)
BONDCPP_PUBLIC void connectTimerReset ()
BONDCPP_PUBLIC void connectTimerCancel ()
inline BONDCPP_PUBLIC double getDisconnectTimeout () const
BONDCPP_PUBLIC void setDisconnectTimeout (double dur)
BONDCPP_PUBLIC void disconnectTimerReset ()
BONDCPP_PUBLIC void disconnectTimerCancel ()
inline BONDCPP_PUBLIC double getHeartbeatTimeout () const
BONDCPP_PUBLIC void setHeartbeatTimeout (double dur)
BONDCPP_PUBLIC void heartbeatTimerReset ()
BONDCPP_PUBLIC void heartbeatTimerCancel ()
inline BONDCPP_PUBLIC double getHeartbeatPeriod () const
BONDCPP_PUBLIC void setHeartbeatPeriod (double dur)
BONDCPP_PUBLIC void publishingTimerReset ()
BONDCPP_PUBLIC void publishingTimerCancel ()
inline BONDCPP_PUBLIC double getDeadPublishPeriod () const
BONDCPP_PUBLIC void setDeadPublishPeriod (double dur)
BONDCPP_PUBLIC void deadpublishingTimerReset ()
BONDCPP_PUBLIC void deadpublishingTimerCancel ()
BONDCPP_PUBLIC void start ()

Starts the bond and connects to the sister process.

BONDCPP_PUBLIC void setFormedCallback (EventCallback on_formed)

Sets the formed callback.

BONDCPP_PUBLIC void setBrokenCallback (EventCallback on_broken)

Sets the broken callback.

BONDCPP_PUBLIC bool waitUntilFormed (rclcpp::Duration timeout=rclcpp::Duration(std::chrono::seconds(-1)))

Blocks until the bond is formed for at most ‘duration’. Assumes the node to be spinning in the background.

Parameters:

timeout – Maximum duration to wait. If -1 then this call will not timeout.

Returns:

true iff the bond has been formed.

BONDCPP_PUBLIC bool waitUntilBroken (rclcpp::Duration timeout=rclcpp::Duration(std::chrono::seconds(-1)))

Blocks until the bond is broken for at most ‘duration’. Assumes the node to be spinning in the background.

Parameters:

timeout – Maximum duration to wait. If -1 then this call will not timeout.

Returns:

true iff the bond has been broken, even if it has never been formed.

BONDCPP_PUBLIC bool isBroken ()

Indicates if the bond is broken.

BONDCPP_PUBLIC void breakBond ()

Breaks the bond, notifying the other process.

inline BONDCPP_PUBLIC std::string getTopic () const
inline BONDCPP_PUBLIC std::string getId () const
inline BONDCPP_PUBLIC std::string getInstanceId () const

Friends

friend struct ::BondSM