18#include <rclcpp/rclcpp.hpp>
30template <
typename TSource,
typename TOrthogonal>
37template <
typename MessageType>
64 template <
typename TOrthogonal,
typename TSourceObject>
68 this->postTimeoutMessageEvent = [
this]()
95 <<
"] Initializing message timeout watchdog with duration: "
96 << timeout_->seconds() <<
"s");
109 "[CpMessageTimeout] Timeout duration not set, skipping timeout watchdog functionality");
134 getLogger(),
"[CpMessageTimeout] Message timeout occurred after %f seconds",
void resetTimer(const MessageType &)
void onInitialize() override
SmaccSignal< void()> onMessageTimeout_
boost::signals2::connection onMessageTimeout(void(T::*callback)(), T *object)
std::optional< rclcpp::Duration > timeout_
virtual ~CpMessageTimeout()
void onComponentInitialization()
std::function< void()> postTimeoutMessageEvent
rclcpp::TimerBase::SharedPtr timeoutTimer_
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)