37template <
typename MessageType>
60 void (
T::*
callback)(
const MessageType &),
T *
object)
67 void (
T::*
callback)(
const MessageType &),
T *
object)
70 onFirstMessageReceived_,
callback,
object);
73 template <
typename TOrthogonal,
typename TSourceObject>
77 this->postMessageEvent = [
this](
auto msg) {
84 this->postInitialMessageEvent = [
this](
auto msg) {
102 RCLCPP_ERROR(
getLogger(),
"topic client with no topic name set. Skipping subscribing");
107 getLogger(),
"[" << this->
getName() <<
"] Subscribing to topic: " << *topicName);
109 rclcpp::SensorDataQoS qos;
112 std::function<void(
typename MessageType::SharedPtr)> fn = [
this](
auto msg) {
122 typename rclcpp::Subscription<MessageType>::SharedPtr
sub_;
rclcpp::Node::SharedPtr getNode()
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
rclcpp::Subscription< MessageType >::SharedPtr sub_
SmaccSubscriberClient(std::string topicname)
virtual ~SmaccSubscriberClient()
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)
std::function< void(const MessageType &)> postMessageEvent
boost::signals2::connection onFirstMessageReceived(void(T::*callback)(const MessageType &), T *object)
std::function< void(const MessageType &)> postInitialMessageEvent
void onOrthogonalAllocation()
std::optional< int > queueSize
void messageCallback(const MessageType &msg)
smacc2::SmaccSignal< void(const MessageType &)> onMessageReceived_
void onInitialize() override
smacc2::SmaccSignal< void(const MessageType &)> onFirstMessageReceived_
std::optional< std::string > topicName
void callback(const image_tools::ROSCvMatContainer &img)