SMACC2
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
smacc2::components::CpTopicSubscriber< MessageType > Class Template Reference

#include <cp_topic_subscriber.hpp>

Inheritance diagram for smacc2::components::CpTopicSubscriber< MessageType >:
Inheritance graph
Collaboration diagram for smacc2::components::CpTopicSubscriber< MessageType >:
Collaboration graph

Public Types

typedef MessageType TMessageType
 

Public Member Functions

 CpTopicSubscriber ()
 
 CpTopicSubscriber (std::string topicname)
 
virtual ~CpTopicSubscriber ()
 
template<typename T >
boost::signals2::connection onMessageReceived (void(T::*callback)(const MessageType &), T *object)
 
template<typename T >
boost::signals2::connection onFirstMessageReceived (void(T::*callback)(const MessageType &), T *object)
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
void onInitialize () override
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

std::optional< int > queueSize
 
smacc2::SmaccSignal< void(const MessageType &)> onFirstMessageReceived_
 
smacc2::SmaccSignal< void(const MessageType &)> onMessageReceived_
 
std::function< void(const MessageType &)> postMessageEvent
 
std::function< void(const MessageType &)> postInitialMessageEvent
 

Private Member Functions

void messageCallback (const MessageType &msg)
 

Private Attributes

rclcpp::Subscription< MessageType >::SharedPtr sub_
 
bool firstMessage_
 
bool initialized_
 
std::string topicName_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
virtual void onInitialize ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

template<typename MessageType>
class smacc2::components::CpTopicSubscriber< MessageType >

Definition at line 34 of file cp_topic_subscriber.hpp.

Member Typedef Documentation

◆ TMessageType

template<typename MessageType >
typedef MessageType smacc2::components::CpTopicSubscriber< MessageType >::TMessageType

Definition at line 39 of file cp_topic_subscriber.hpp.

Constructor & Destructor Documentation

◆ CpTopicSubscriber() [1/2]

template<typename MessageType >
smacc2::components::CpTopicSubscriber< MessageType >::CpTopicSubscriber ( )
inline

◆ CpTopicSubscriber() [2/2]

template<typename MessageType >
smacc2::components::CpTopicSubscriber< MessageType >::CpTopicSubscriber ( std::string  topicname)
inline

◆ ~CpTopicSubscriber()

template<typename MessageType >
virtual smacc2::components::CpTopicSubscriber< MessageType >::~CpTopicSubscriber ( )
inlinevirtual

Definition at line 45 of file cp_topic_subscriber.hpp.

45{}

Member Function Documentation

◆ messageCallback()

template<typename MessageType >
void smacc2::components::CpTopicSubscriber< MessageType >::messageCallback ( const MessageType &  msg)
inlineprivate

Definition at line 114 of file cp_topic_subscriber.hpp.

115 {
116 if (firstMessage_)
117 {
120 firstMessage_ = false;
121 }
122
123 postMessageEvent(msg);
125 }
std::function< void(const MessageType &)> postMessageEvent
std::function< void(const MessageType &)> postInitialMessageEvent
smacc2::SmaccSignal< void(const MessageType &)> onFirstMessageReceived_
smacc2::SmaccSignal< void(const MessageType &)> onMessageReceived_

References smacc2::components::CpTopicSubscriber< MessageType >::firstMessage_, smacc2::components::CpTopicSubscriber< MessageType >::onFirstMessageReceived_, smacc2::components::CpTopicSubscriber< MessageType >::onMessageReceived_, smacc2::components::CpTopicSubscriber< MessageType >::postInitialMessageEvent, and smacc2::components::CpTopicSubscriber< MessageType >::postMessageEvent.

Referenced by smacc2::components::CpTopicSubscriber< MessageType >::onInitialize().

Here is the caller graph for this function:

◆ onFirstMessageReceived()

template<typename MessageType >
template<typename T >
boost::signals2::connection smacc2::components::CpTopicSubscriber< MessageType >::onFirstMessageReceived ( void(T::*)(const MessageType &)  callback,
T *  object 
)
inline

Definition at line 61 of file cp_topic_subscriber.hpp.

63 {
65 onFirstMessageReceived_, callback, object);
66 }
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onInitialize()

template<typename MessageType >
void smacc2::components::CpTopicSubscriber< MessageType >::onInitialize ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 86 of file cp_topic_subscriber.hpp.

87 {
88 if (!initialized_)
89 {
90 firstMessage_ = true;
91
92 if (!queueSize) queueSize = 1;
93
94 RCLCPP_INFO_STREAM(
95 getLogger(), "[" << this->getName() << "] Subscribing to topic: " << topicName_);
96
97 rclcpp::SensorDataQoS qos;
98 if (queueSize) qos.keep_last(*queueSize);
99
100 std::function<void(typename MessageType::SharedPtr)> fn = [this](auto msg)
101 { this->messageCallback(*msg); };
102
103 sub_ = this->getNode()->template create_subscription<MessageType>(topicName_, qos, fn);
104 this->initialized_ = true;
105 }
106 }
virtual std::string getName() const
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()
rclcpp::Subscription< MessageType >::SharedPtr sub_
void messageCallback(const MessageType &msg)

References smacc2::components::CpTopicSubscriber< MessageType >::firstMessage_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccComponent::getNode(), smacc2::components::CpTopicSubscriber< MessageType >::initialized_, smacc2::components::CpTopicSubscriber< MessageType >::messageCallback(), smacc2::components::CpTopicSubscriber< MessageType >::queueSize, smacc2::components::CpTopicSubscriber< MessageType >::sub_, and smacc2::components::CpTopicSubscriber< MessageType >::topicName_.

Here is the call graph for this function:

◆ onMessageReceived()

template<typename MessageType >
template<typename T >
boost::signals2::connection smacc2::components::CpTopicSubscriber< MessageType >::onMessageReceived ( void(T::*)(const MessageType &)  callback,
T *  object 
)
inline

Definition at line 54 of file cp_topic_subscriber.hpp.

56 {
57 return this->getStateMachine()->createSignalConnection(onMessageReceived_, callback, object);
58 }

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onOrthogonalAllocation()

template<typename MessageType >
template<typename TOrthogonal , typename TSourceObject >
void smacc2::components::CpTopicSubscriber< MessageType >::onOrthogonalAllocation ( )
inline

Definition at line 69 of file cp_topic_subscriber.hpp.

70 {
71 this->postMessageEvent = [=](auto msg)
72 {
73 auto event = new EvTopicMessage<TSourceObject, TOrthogonal, MessageType>();
74 event->msgData = msg;
75 this->postEvent(event);
76 };
77
78 this->postInitialMessageEvent = [=](auto msg)
79 {
80 auto event = new EvTopicInitialMessage<TSourceObject, TOrthogonal, MessageType>();
81 event->msgData = msg;
82 this->postEvent(event);
83 };
84 }

References smacc2::ISmaccComponent::postEvent().

Here is the call graph for this function:

Member Data Documentation

◆ firstMessage_

template<typename MessageType >
bool smacc2::components::CpTopicSubscriber< MessageType >::firstMessage_
private

◆ initialized_

template<typename MessageType >
bool smacc2::components::CpTopicSubscriber< MessageType >::initialized_
private

◆ onFirstMessageReceived_

template<typename MessageType >
smacc2::SmaccSignal<void(const MessageType &)> smacc2::components::CpTopicSubscriber< MessageType >::onFirstMessageReceived_

◆ onMessageReceived_

template<typename MessageType >
smacc2::SmaccSignal<void(const MessageType &)> smacc2::components::CpTopicSubscriber< MessageType >::onMessageReceived_

◆ postInitialMessageEvent

template<typename MessageType >
std::function<void(const MessageType &)> smacc2::components::CpTopicSubscriber< MessageType >::postInitialMessageEvent

◆ postMessageEvent

template<typename MessageType >
std::function<void(const MessageType &)> smacc2::components::CpTopicSubscriber< MessageType >::postMessageEvent

◆ queueSize

template<typename MessageType >
std::optional<int> smacc2::components::CpTopicSubscriber< MessageType >::queueSize

◆ sub_

template<typename MessageType >
rclcpp::Subscription<MessageType>::SharedPtr smacc2::components::CpTopicSubscriber< MessageType >::sub_
private

◆ topicName_

template<typename MessageType >
std::string smacc2::components::CpTopicSubscriber< MessageType >::topicName_
private

The documentation for this class was generated from the following file: