33template <
typename MessageType>
55 void (T::*callback)(
const MessageType &), T *
object)
62 void (T::*callback)(
const MessageType &), T *
object)
65 onFirstMessageReceived_, callback,
object);
68 template <
typename TOrthogonal,
typename TSourceObject>
71 this->postMessageEvent = [=](
auto msg)
78 this->postInitialMessageEvent = [=](
auto msg)
97 rclcpp::SensorDataQoS qos;
100 std::function<void(
typename MessageType::SharedPtr)> fn = [
this](
auto msg)
109 typename rclcpp::Subscription<MessageType>::SharedPtr
sub_;
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
CpTopicSubscriber(std::string topicname)
std::optional< int > queueSize
rclcpp::Subscription< MessageType >::SharedPtr sub_
std::function< void(const MessageType &)> postMessageEvent
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)
std::function< void(const MessageType &)> postInitialMessageEvent
virtual ~CpTopicSubscriber()
void messageCallback(const MessageType &msg)
void onInitialize() override
boost::signals2::connection onFirstMessageReceived(void(T::*callback)(const MessageType &), T *object)
smacc2::SmaccSignal< void(const MessageType &)> onFirstMessageReceived_
void onOrthogonalAllocation()
smacc2::SmaccSignal< void(const MessageType &)> onMessageReceived_