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 Functions

Bond(const std::string &topic, const std::string &id, rclcpp_lifecycle::LifecycleNode::SharedPtr nh, std::function<void(void)> on_broken = std::function<void(void)>(), std::function<void(void)> on_formed = std::function<void(void)>())

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.

Bond(const std::string &topic, const std::string &id, rclcpp::Node::SharedPtr nh, std::function<void(void)> on_broken = std::function<void(void)>(), std::function<void(void)> on_formed = std::function<void(void)>())

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.

~Bond()

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

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

Starts the bond and connects to the sister process.

void setFormedCallback(std::function<void(void)> on_formed)

Sets the formed callback.

void setBrokenCallback(std::function<void(void)> on_broken)

Sets the broken callback.

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.

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.

bool isBroken()

Indicates if the bond is broken.

void breakBond()

Breaks the bond, notifying the other process.

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

Friends

friend struct ::BondSM