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

#include <cl_multirole_sensor.h>

Inheritance diagram for cl_multirole_sensor::ClMultiroleSensor< MessageType >:
Inheritance graph
Collaboration diagram for cl_multirole_sensor::ClMultiroleSensor< MessageType >:
Collaboration graph

Public Types

typedef MessageType TMessageType
 
- Public Types inherited from smacc::client_bases::SmaccSubscriberClient< MessageType >
typedef MessageType TMessageType
 

Public Member Functions

 ClMultiroleSensor ()
 
template<typename T >
boost::signals2::connection onMessageTimeout (void(T::*callback)(const ros::TimerEvent &), T *object)
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual void initialize () override
 
- Public Member Functions inherited from smacc::client_bases::SmaccSubscriberClient< MessageType >
 SmaccSubscriberClient ()
 
 SmaccSubscriberClient (std::string topicname)
 
virtual ~SmaccSubscriberClient ()
 
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::ISmaccClient
 ISmaccClient ()
 
virtual ~ISmaccClient ()
 
virtual void initialize ()
 
virtual std::string getName () const
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TComponent >
TComponent * getComponent ()
 
template<typename TComponent >
TComponent * getComponent (std::string name)
 
virtual smacc::introspection::TypeInfo::Ptr getType ()
 
ISmaccStateMachinegetStateMachine ()
 
template<typename TSmaccSignal , typename T >
void connectSignal (TSmaccSignal &signal, void(T::*callback)(), T *object)
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
void getComponents (std::vector< std::shared_ptr< ISmaccComponent > > &components)
 

Public Attributes

SmaccSignal< void(const ros::TimerEvent &)> onMessageTimeout_
 
std::function< void(const ros::TimerEvent &ev)> postTimeoutMessageEvent
 
boost::optional< ros::Duration > timeout_
 
- Public Attributes inherited from smacc::client_bases::SmaccSubscriberClient< MessageType >
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 Member Functions

void resetTimer (const MessageType &msg)
 
- Protected Member Functions inherited from smacc::ISmaccClient
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createNamedComponent (std::string name, TArgs... targs)
 
void setStateMachine (ISmaccStateMachine *stateMachine)
 
void setOrthogonal (ISmaccOrthogonal *orthogonal)
 

Private Member Functions

void timeoutCallback (const ros::TimerEvent &timerdata)
 

Private Attributes

ros::Timer timeoutTimer_
 
bool initialized_
 

Additional Inherited Members

- Protected Attributes inherited from smacc::client_bases::SmaccSubscriberClient< MessageType >
ros::NodeHandle nh_
 
- Protected Attributes inherited from smacc::ISmaccClient
std::map< ComponentKey, std::shared_ptr< smacc::ISmaccComponent > > components_
 

Detailed Description

template<typename MessageType>
class cl_multirole_sensor::ClMultiroleSensor< MessageType >

Definition at line 25 of file cl_multirole_sensor.h.

Member Typedef Documentation

◆ TMessageType

template<typename MessageType >
typedef MessageType cl_multirole_sensor::ClMultiroleSensor< MessageType >::TMessageType

Definition at line 28 of file cl_multirole_sensor.h.

Constructor & Destructor Documentation

◆ ClMultiroleSensor()

template<typename MessageType >
cl_multirole_sensor::ClMultiroleSensor< MessageType >::ClMultiroleSensor ( )
inline

Member Function Documentation

◆ initialize()

template<typename MessageType >
virtual void cl_multirole_sensor::ClMultiroleSensor< MessageType >::initialize ( )
inlineoverridevirtual

Reimplemented from smacc::client_bases::SmaccSubscriberClient< MessageType >.

Definition at line 60 of file cl_multirole_sensor.h.

61 {
62 if (!initialized_)
63 {
65
67
68 if (timeout_)
69 {
70 timeoutTimer_ = this->nh_.createTimer(*timeout_, boost::bind(&ClMultiroleSensor<MessageType>::timeoutCallback, this, _1));
71 timeoutTimer_.start();
72 }
73 else
74 {
75 ROS_WARN("Timeout sensor client not set, skipping timeout watchdog funcionality");
76 }
77
78 initialized_ = true;
79 }
80 }
boost::optional< ros::Duration > timeout_
void timeoutCallback(const ros::TimerEvent &timerdata)
void resetTimer(const MessageType &msg)
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)

References smacc::client_bases::SmaccSubscriberClient< MessageType >::initialize(), cl_multirole_sensor::ClMultiroleSensor< MessageType >::initialized_, smacc::client_bases::SmaccSubscriberClient< MessageType >::nh_, smacc::client_bases::SmaccSubscriberClient< MessageType >::onMessageReceived(), cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeout_, and cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutTimer_.

Here is the call graph for this function:

◆ onMessageTimeout()

template<typename MessageType >
template<typename T >
boost::signals2::connection cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout ( void(T::*)(const ros::TimerEvent &)  callback,
T *  object 
)
inline

Definition at line 39 of file cl_multirole_sensor.h.

40 {
41 return this->getStateMachine()->createSignalConnection(onMessageTimeout_, callback, object);
42 }
SmaccSignal< void(const ros::TimerEvent &)> onMessageTimeout_
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

References smacc::ISmaccStateMachine::createSignalConnection(), and smacc::ISmaccClient::getStateMachine().

Here is the call graph for this function:

◆ onOrthogonalAllocation()

template<typename MessageType >
template<typename TOrthogonal , typename TSourceObject >
void cl_multirole_sensor::ClMultiroleSensor< MessageType >::onOrthogonalAllocation ( )
inline

Definition at line 47 of file cl_multirole_sensor.h.

48 {
49 SmaccSubscriberClient<MessageType>::template onOrthogonalAllocation<TOrthogonal, TSourceObject>();
50
51 this->postTimeoutMessageEvent = [=](auto &timerdata) {
52 onMessageTimeout_(timerdata);
53
54 auto event = new EvTopicMessageTimeout<TSourceObject, TOrthogonal>();
55 event->timerData = timerdata;
56 this->postEvent(event);
57 };
58 }
std::function< void(const ros::TimerEvent &ev)> postTimeoutMessageEvent

References cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout_, and smacc::ISmaccClient::postEvent().

Here is the call graph for this function:

◆ resetTimer()

template<typename MessageType >
void cl_multirole_sensor::ClMultiroleSensor< MessageType >::resetTimer ( const MessageType &  msg)
inlineprotected

Definition at line 85 of file cl_multirole_sensor.h.

86 {
87 //resetting the timer
88 this->timeoutTimer_.stop();
89 this->timeoutTimer_.start();
90 }

References cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutTimer_.

◆ timeoutCallback()

template<typename MessageType >
void cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutCallback ( const ros::TimerEvent &  timerdata)
inlineprivate

Member Data Documentation

◆ initialized_

template<typename MessageType >
bool cl_multirole_sensor::ClMultiroleSensor< MessageType >::initialized_
private

◆ onMessageTimeout_

template<typename MessageType >
SmaccSignal<void(const ros::TimerEvent &)> cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout_

◆ postTimeoutMessageEvent

template<typename MessageType >
std::function<void(const ros::TimerEvent &ev)> cl_multirole_sensor::ClMultiroleSensor< MessageType >::postTimeoutMessageEvent

◆ timeout_

template<typename MessageType >
boost::optional<ros::Duration> cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeout_

◆ timeoutTimer_

template<typename MessageType >
ros::Timer cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutTimer_
private

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