17#include <boost/signals2.hpp>
24template <
typename TSource,
typename TOrthogonal>
42 ClRosTimer(rclcpp::Duration duration,
bool oneshot =
false);
54 template <
typename TOrthogonal,
typename TSourceObject>
57 this->
postTimerEvent_ = [=]() { this->postEvent<EvTimer<TSourceObject, TOrthogonal>>(); };
rclcpp::Duration duration_
virtual void initialize()
void onOrthogonalAllocation()
boost::signals2::connection onTimerTick(void(T::*callback)(), T *object)
smacc2::SmaccSignal< void()> onTimerTick_
rclcpp::TimerBase::SharedPtr timer_
std::function< void()> postTimerEvent_
ClRosTimer(rclcpp::Duration duration, bool oneshot=false)
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
void callback(const image_tools::ROSCvMatContainer &img)