SMACC2
|
#include <cl_multirole_sensor.hpp>
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 () |
ISmaccStateMachine * | getStateMachine () |
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) |
const std::vector< std::shared_ptr< ISmaccComponent > > & | iterateComponents () const |
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_ |
Definition at line 37 of file cl_multirole_sensor.hpp.
typedef MessageType cl_multirole_sensor::ClMultiroleSensor< MessageType >::TMessageType |
Definition at line 40 of file cl_multirole_sensor.hpp.
|
inline |
Definition at line 43 of file cl_multirole_sensor.hpp.
References cl_multirole_sensor::ClMultiroleSensor< MessageType >::initialized_.
|
inlineoverridevirtual |
Reimplemented from smacc2::client_bases::SmaccSubscriberClient< MessageType >.
Definition at line 71 of file cl_multirole_sensor.hpp.
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_.
|
inline |
Definition at line 49 of file cl_multirole_sensor.hpp.
References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccClient::getStateMachine().
|
inline |
Definition at line 57 of file cl_multirole_sensor.hpp.
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().
|
inlineprotected |
Definition at line 102 of file cl_multirole_sensor.hpp.
References cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutTimer_.
|
inlineprivate |
Definition at line 114 of file cl_multirole_sensor.hpp.
References cl_multirole_sensor::ClMultiroleSensor< MessageType >::postTimeoutMessageEvent.
|
private |
Definition at line 112 of file cl_multirole_sensor.hpp.
Referenced by cl_multirole_sensor::ClMultiroleSensor< MessageType >::ClMultiroleSensor(), and cl_multirole_sensor::ClMultiroleSensor< MessageType >::onInitialize().
SmaccSignal<void()> cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout_ |
Definition at line 41 of file cl_multirole_sensor.hpp.
Referenced by cl_multirole_sensor::ClMultiroleSensor< MessageType >::onOrthogonalAllocation().
std::function<void()> cl_multirole_sensor::ClMultiroleSensor< MessageType >::postTimeoutMessageEvent |
Definition at line 54 of file cl_multirole_sensor.hpp.
Referenced by cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeoutCallback().
std::optional<rclcpp::Duration> cl_multirole_sensor::ClMultiroleSensor< MessageType >::timeout_ |
Definition at line 99 of file cl_multirole_sensor.hpp.
Referenced by cl_multirole_sensor::ClMultiroleSensor< MessageType >::onInitialize().
|
private |
Definition at line 111 of file cl_multirole_sensor.hpp.
Referenced by cl_multirole_sensor::ClMultiroleSensor< MessageType >::onInitialize(), and cl_multirole_sensor::ClMultiroleSensor< MessageType >::resetTimer().