SMACC2
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.hpp>

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 smacc2::client_bases::SmaccSubscriberClient< MessageType >
typedef MessageType TMessageType
 

Public Member Functions

 ClMultiroleSensor ()
 
template<typename T >
boost::signals2::connection onMessageTimeout (void(T::*callback)(), T *object)
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
void onInitialize () override
 
- Public Member Functions inherited from smacc2::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 ()
 
- Public Member Functions inherited from smacc2::ISmaccClient
 ISmaccClient ()
 
virtual ~ISmaccClient ()
 
virtual void onInitialize ()
 
virtual std::string getName () const
 
template<typename TComponent >
TComponent * getComponent ()
 
template<typename TComponent >
TComponent * getComponent (std::string name)
 
template<typename TComponent >
TComponent * getComponent (int index)
 
virtual smacc2::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)
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 

Public Attributes

SmaccSignal< void()> onMessageTimeout_
 
std::function< void()> postTimeoutMessageEvent
 
std::optional< rclcpp::Duration > timeout_
 
- Public Attributes inherited from smacc2::client_bases::SmaccSubscriberClient< MessageType >
std::optional< std::string > topicName
 
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
 

Protected Member Functions

void resetTimer (const MessageType &)
 
void onInitialize () override
 
- Protected Member Functions inherited from smacc2::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)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 

Private Member Functions

void timeoutCallback ()
 

Private Attributes

rclcpp::TimerBase::SharedPtr timeoutTimer_
 
bool initialized_
 

Additional Inherited Members

- Protected Attributes inherited from smacc2::ISmaccClient
std::map< ComponentKey, std::shared_ptr< smacc2::ISmaccComponent > > components_
 

Detailed Description

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

Definition at line 37 of file cl_multirole_sensor.hpp.

Member Typedef Documentation

◆ TMessageType

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

Definition at line 40 of file cl_multirole_sensor.hpp.

Constructor & Destructor Documentation

◆ ClMultiroleSensor()

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

Member Function Documentation

◆ onInitialize()

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

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

Definition at line 71 of file cl_multirole_sensor.hpp.

72 {
73 if (!initialized_)
74 {
76
78
79 if (timeout_)
80 {
81 auto ros_clock = rclcpp::Clock::make_shared();
82 timeoutTimer_ = rclcpp::create_timer(
83 this->getNode(), this->getNode()->get_clock(), *timeout_,
85
86 timeoutTimer_->reset();
87 }
88 else
89 {
90 RCLCPP_WARN(
91 this->getLogger(),
92 "Timeout sensor client not set, skipping timeout watchdog funcionality");
93 }
94
95 initialized_ = true;
96 }
97 }
rclcpp::TimerBase::SharedPtr timeoutTimer_
std::optional< rclcpp::Duration > timeout_
rclcpp::Node::SharedPtr getNode()
Definition: client.cpp:60
rclcpp::Logger getLogger()
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)

References smacc2::ISmaccClient::getLogger(), smacc2::ISmaccClient::getNode(), cl_multirole_sensor::ClMultiroleSensor< MessageType >::initialized_, smacc2::client_bases::SmaccSubscriberClient< MessageType >::onInitialize(), smacc2::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::*)()  callback,
T *  object 
)
inline

Definition at line 49 of file cl_multirole_sensor.hpp.

50 {
51 return this->getStateMachine()->createSignalConnection(onMessageTimeout_, callback, object);
52 }
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::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 57 of file cl_multirole_sensor.hpp.

58 {
59 SmaccSubscriberClient<MessageType>::template onOrthogonalAllocation<
60 TOrthogonal, TSourceObject>();
61
62 this->postTimeoutMessageEvent = [this]()
63 {
64 this->onMessageTimeout_();
65
66 auto event = new EvTopicMessageTimeout<TSourceObject, TOrthogonal>();
67 this->postEvent(event);
68 };
69 }

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

Referenced by cl_multirole_sensor::ClMultiroleSensor< MessageType >::onOrthogonalAllocation().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ resetTimer()

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

Definition at line 102 of file cl_multirole_sensor.hpp.

103 {
104 //resetting the timer
105 timeoutTimer_->reset();
106 //timeoutTimer_->stop();
107 //timeoutTimer_->start();
108 }

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

◆ timeoutCallback()

template<typename MessageType >
void cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutCallback ( )
inlineprivate

Member Data Documentation

◆ initialized_

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

◆ onMessageTimeout_

template<typename MessageType >
SmaccSignal<void()> cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout_

◆ postTimeoutMessageEvent

template<typename MessageType >
std::function<void()> cl_multirole_sensor::ClMultiroleSensor< MessageType >::postTimeoutMessageEvent

◆ timeout_

template<typename MessageType >
std::optional<rclcpp::Duration> cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeout_

◆ timeoutTimer_

template<typename MessageType >
rclcpp::TimerBase::SharedPtr cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutTimer_
private

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