18#include <rclcpp/rclcpp.hpp>
27template <
typename TSource,
typename TOrthogonal>
36template <
typename MessageType>
56 template <
typename TOrthogonal,
typename TSourceObject>
60 TOrthogonal, TSourceObject>();
62 this->postTimeoutMessageEvent = [
this]() {
80 auto ros_clock = rclcpp::Clock::make_shared();
91 "Timeout sensor client not set, skipping timeout watchdog funcionality");
void resetTimer(const MessageType &)
SmaccSignal< void()> onMessageTimeout_
void onOrthogonalAllocation()
rclcpp::TimerBase::SharedPtr timeoutTimer_
boost::signals2::connection onMessageTimeout(void(T::*callback)(), T *object)
void onInitialize() override
std::function< void()> postTimeoutMessageEvent
std::optional< rclcpp::Duration > timeout_
rclcpp::Node::SharedPtr getNode()
ISmaccStateMachine * getStateMachine()
rclcpp::Logger getLogger()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)
void onInitialize() override
void callback(const image_tools::ROSCvMatContainer &img)