29namespace client_core_components
33template <
typename MessageType>
60 void (T::*callback)(
const MessageType &), T *
object)
68 void (T::*callback)(
const MessageType &), T *
object)
71 onFirstMessageReceived_, callback,
object);
74 template <
typename TOrthogonal,
typename TSourceObject>
77 this->postMessageEvent = [=](
auto msg)
84 this->postInitialMessageEvent = [=](
auto msg)
103 rclcpp::SensorDataQoS qos;
106 std::function<void(
typename MessageType::SharedPtr)> fn = [
this](
auto msg)
115 typename rclcpp::Subscription<MessageType>::SharedPtr
sub_;
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()
smacc2::SmaccSignalConnection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
smacc2::SmaccSignal< void(const MessageType &)> onFirstMessageReceived_
void onInitialize() override
void messageCallback(const MessageType &msg)
smacc2::SmaccSignal< void(const MessageType &)> onMessageReceived_
std::optional< int > queueSize
std::function< void(const MessageType &)> postInitialMessageEvent
smacc2::SmaccSignalConnection onFirstMessageReceived(void(T::*callback)(const MessageType &), T *object)
CpTopicSubscriber(std::string topicname)
rclcpp::Subscription< MessageType >::SharedPtr sub_
std::function< void(const MessageType &)> postMessageEvent
void onStateOrthogonalAllocation()
smacc2::SmaccSignalConnection onMessageReceived(void(T::*callback)(const MessageType &), T *object)
virtual ~CpTopicSubscriber()
boost::signals2::connection SmaccSignalConnection