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

#include <cp_topic_subscriber.h>

Inheritance diagram for smacc::components::CpTopicSubscriber< MessageType >:
Inheritance graph
Collaboration diagram for smacc::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 ()
 
virtual void initialize ()
 
- Public Member Functions inherited from smacc::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

boost::optional< std::string > topicName
 
boost::optional< int > queueSize
 
smacc::SmaccSignal< void(const MessageType &)> onFirstMessageReceived_
 
smacc::SmaccSignal< void(const MessageType &)> onMessageReceived_
 
std::function< void(const MessageType &)> postMessageEvent
 
std::function< void(const MessageType &)> postInitialMessageEvent
 

Protected Attributes

ros::NodeHandle nh_
 
- Protected Attributes inherited from smacc::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Private Member Functions

void messageCallback (const MessageType &msg)
 

Private Attributes

ros::Subscriber sub_
 
bool firstMessage_
 
bool initialized_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc::ISmaccComponent
virtual void initialize (ISmaccClient *owner)
 
void setStateMachine (ISmaccStateMachine *stateMachine)
 
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)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
virtual void onInitialize ()
 
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)
 

Detailed Description

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

Definition at line 15 of file cp_topic_subscriber.h.

Member Typedef Documentation

◆ TMessageType

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

Definition at line 21 of file cp_topic_subscriber.h.

Constructor & Destructor Documentation

◆ CpTopicSubscriber() [1/2]

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

◆ CpTopicSubscriber() [2/2]

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

Definition at line 28 of file cp_topic_subscriber.h.

29 {
30 topicName = topicname;
31 }
boost::optional< std::string > topicName

References smacc::components::CpTopicSubscriber< MessageType >::topicName.

◆ ~CpTopicSubscriber()

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

Definition at line 33 of file cp_topic_subscriber.h.

34 {
35 sub_.shutdown();
36 }

References smacc::components::CpTopicSubscriber< MessageType >::sub_.

Member Function Documentation

◆ initialize()

template<typename MessageType >
virtual void smacc::components::CpTopicSubscriber< MessageType >::initialize ( )
inlinevirtual

Definition at line 72 of file cp_topic_subscriber.h.

73 {
74 if (!initialized_)
75 {
76 firstMessage_ = true;
77
78 if (!queueSize)
79 queueSize = 1;
80
81 if (!topicName)
82 {
83 ROS_ERROR("topic client with no topic name set. Skipping subscribing");
84 }
85 else
86 {
87 ROS_INFO_STREAM("[" << this->getName() << "] Subscribing to topic: " << topicName);
88
90 this->initialized_ = true;
91 }
92 }
93 }
virtual std::string getName() const
void messageCallback(const MessageType &msg)

References smacc::components::CpTopicSubscriber< MessageType >::firstMessage_, smacc::ISmaccComponent::getName(), smacc::components::CpTopicSubscriber< MessageType >::initialized_, smacc::components::CpTopicSubscriber< MessageType >::nh_, smacc::components::CpTopicSubscriber< MessageType >::queueSize, smacc::components::CpTopicSubscriber< MessageType >::sub_, and smacc::components::CpTopicSubscriber< MessageType >::topicName.

Here is the call graph for this function:

◆ messageCallback()

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

◆ onFirstMessageReceived()

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

Definition at line 51 of file cp_topic_subscriber.h.

52 {
53 return this->getStateMachine()->createSignalConnection(onFirstMessageReceived_, callback, object);
54 }

References smacc::components::CpTopicSubscriber< MessageType >::onFirstMessageReceived_.

◆ onMessageReceived()

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

Definition at line 45 of file cp_topic_subscriber.h.

46 {
47 return this->getStateMachine()->createSignalConnection(onMessageReceived_, callback, object);
48 }

References smacc::components::CpTopicSubscriber< MessageType >::onMessageReceived_.

◆ onOrthogonalAllocation()

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

Definition at line 57 of file cp_topic_subscriber.h.

58 {
59 this->postMessageEvent = [=](auto msg) {
60 auto event = new EvTopicMessage<TSourceObject, TOrthogonal>();
61 event->msgData = msg;
62 this->postEvent(event);
63 };
64
65 this->postInitialMessageEvent = [=](auto msg) {
66 auto event = new EvTopicInitialMessage<TSourceObject, TOrthogonal>();
67 event->msgData = msg;
68 this->postEvent(event);
69 };
70 }

References smacc::ISmaccComponent::postEvent().

Here is the call graph for this function:

Member Data Documentation

◆ firstMessage_

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

◆ initialized_

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

◆ nh_

template<typename MessageType >
ros::NodeHandle smacc::components::CpTopicSubscriber< MessageType >::nh_
protected

◆ onFirstMessageReceived_

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

◆ onMessageReceived_

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

◆ postInitialMessageEvent

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

◆ postMessageEvent

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

◆ queueSize

template<typename MessageType >
boost::optional<int> smacc::components::CpTopicSubscriber< MessageType >::queueSize

◆ sub_

template<typename MessageType >
ros::Subscriber smacc::components::CpTopicSubscriber< MessageType >::sub_
private

◆ topicName

template<typename MessageType >
boost::optional<std::string> smacc::components::CpTopicSubscriber< MessageType >::topicName

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