SMACC2
Loading...
Searching...
No Matches
smacc2::client_core_components::CpRos2Timer Class Reference

#include <cp_ros2_timer.hpp>

Inheritance diagram for smacc2::client_core_components::CpRos2Timer:
Inheritance graph
Collaboration diagram for smacc2::client_core_components::CpRos2Timer:
Collaboration graph

Public Member Functions

 CpRos2Timer (rclcpp::Duration duration, bool oneshot=false)
 
virtual ~CpRos2Timer ()
 
void onInitialize () override
 
void startTimer ()
 
void stopTimer ()
 
void cancelTimer ()
 
template<typename T >
boost::signals2::connection onTimerTick (void(T::*callback)(), T *object)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

smacc2::SmaccSignal< void()> onTimerTick_
 

Private Member Functions

void timerCallback ()
 

Private Attributes

rclcpp::TimerBase::SharedPtr timer_
 
rclcpp::Duration duration_
 
bool oneshot_
 
bool initialized_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename TOrthogonal , typename TClient >
void onComponentInitialization ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
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

Definition at line 30 of file cp_ros2_timer.hpp.

Constructor & Destructor Documentation

◆ CpRos2Timer()

smacc2::client_core_components::CpRos2Timer::CpRos2Timer ( rclcpp::Duration duration,
bool oneshot = false )
inline

◆ ~CpRos2Timer()

virtual smacc2::client_core_components::CpRos2Timer::~CpRos2Timer ( )
inlinevirtual

Definition at line 38 of file cp_ros2_timer.hpp.

39 {
40 if (timer_)
41 {
42 timer_->cancel();
43 }
44 }

References timer_.

Member Function Documentation

◆ cancelTimer()

void smacc2::client_core_components::CpRos2Timer::cancelTimer ( )
inline

Definition at line 82 of file cp_ros2_timer.hpp.

83 {
84 if (timer_)
85 {
86 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Cancelling timer");
87 timer_->cancel();
88 }
89 }
virtual std::string getName() const
rclcpp::Logger getLogger() const

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and timer_.

Here is the call graph for this function:

◆ onInitialize()

void smacc2::client_core_components::CpRos2Timer::onInitialize ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 46 of file cp_ros2_timer.hpp.

47 {
48 if (!initialized_)
49 {
50 RCLCPP_INFO_STREAM(
51 getLogger(), "[" << this->getName() << "] Initializing ROS2 Timer with duration: "
52 << duration_.seconds() << "s, oneshot: " << (oneshot_ ? "true" : "false"));
53
54 auto clock = this->getNode()->get_clock();
55 timer_ = rclcpp::create_timer(
56 this->getNode(), clock, duration_, std::bind(&CpRos2Timer::timerCallback, this));
57
58 this->initialized_ = true;
59 }
60 }
rclcpp::Node::SharedPtr getNode()

References duration_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccComponent::getNode(), initialized_, oneshot_, timer_, and timerCallback().

Here is the call graph for this function:

◆ onTimerTick()

template<typename T >
boost::signals2::connection smacc2::client_core_components::CpRos2Timer::onTimerTick ( void(T::* callback )(),
T * object )
inline

Definition at line 92 of file cp_ros2_timer.hpp.

93 {
94 return this->getStateMachine()->createSignalConnection(onTimerTick_, callback, object);
95 }
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
smacc2::SmaccSignal< void()> onTimerTick_

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

Referenced by cl_ros2_timer::CbTimerCountdownLoop::onEntry(), cl_ros2_timer::CbTimerCountdownOnce::onEntry(), and cl_ros2_timer::components::CpTimerListener1::onInitialize().

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

◆ startTimer()

void smacc2::client_core_components::CpRos2Timer::startTimer ( )
inline

Definition at line 64 of file cp_ros2_timer.hpp.

65 {
66 if (timer_ && timer_->is_canceled())
67 {
68 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Starting timer");
69 timer_->reset();
70 }
71 }

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and timer_.

Here is the call graph for this function:

◆ stopTimer()

void smacc2::client_core_components::CpRos2Timer::stopTimer ( )
inline

Definition at line 73 of file cp_ros2_timer.hpp.

74 {
75 if (timer_)
76 {
77 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] Stopping timer");
78 timer_->cancel();
79 }
80 }

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and timer_.

Here is the call graph for this function:

◆ timerCallback()

void smacc2::client_core_components::CpRos2Timer::timerCallback ( )
inlineprivate

Definition at line 98 of file cp_ros2_timer.hpp.

99 {
100 RCLCPP_DEBUG_STREAM(getLogger(), "[" << this->getName() << "] Timer tick");
101
102 if (!onTimerTick_.empty())
103 {
104 onTimerTick_();
105 }
106
107 if (oneshot_)
108 {
109 RCLCPP_INFO_STREAM(
110 getLogger(), "[" << this->getName() << "] Oneshot timer completed, cancelling");
111 timer_->cancel();
112 }
113 }

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), oneshot_, onTimerTick_, and timer_.

Referenced by onInitialize().

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

Member Data Documentation

◆ duration_

rclcpp::Duration smacc2::client_core_components::CpRos2Timer::duration_
private

Definition at line 115 of file cp_ros2_timer.hpp.

Referenced by onInitialize().

◆ initialized_

bool smacc2::client_core_components::CpRos2Timer::initialized_
private

Definition at line 117 of file cp_ros2_timer.hpp.

Referenced by onInitialize().

◆ oneshot_

bool smacc2::client_core_components::CpRos2Timer::oneshot_
private

Definition at line 116 of file cp_ros2_timer.hpp.

Referenced by onInitialize(), and timerCallback().

◆ onTimerTick_

smacc2::SmaccSignal<void()> smacc2::client_core_components::CpRos2Timer::onTimerTick_

Definition at line 62 of file cp_ros2_timer.hpp.

Referenced by timerCallback().

◆ timer_

rclcpp::TimerBase::SharedPtr smacc2::client_core_components::CpRos2Timer::timer_
private

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