|
SMACC2
|
#include <cp_ros2_timer.hpp>


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) |
| template<typename TComponent > | |
| void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist) |
| template<typename TComponent > | |
| void | requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TComponent > | |
| void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| 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 |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Definition at line 30 of file cp_ros2_timer.hpp.
|
inline |
Definition at line 33 of file cp_ros2_timer.hpp.
|
inlinevirtual |
Definition at line 38 of file cp_ros2_timer.hpp.
References timer_.
|
inline |
Definition at line 82 of file cp_ros2_timer.hpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and timer_.

|
inlineoverridevirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 46 of file cp_ros2_timer.hpp.
References duration_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccComponent::getNode(), initialized_, oneshot_, timer_, and timerCallback().

|
inline |
Definition at line 92 of file cp_ros2_timer.hpp.
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().


|
inline |
Definition at line 64 of file cp_ros2_timer.hpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and timer_.

|
inline |
Definition at line 73 of file cp_ros2_timer.hpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and timer_.

|
inlineprivate |
Definition at line 98 of file cp_ros2_timer.hpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), oneshot_, onTimerTick_, and timer_.
Referenced by onInitialize().


|
private |
Definition at line 115 of file cp_ros2_timer.hpp.
Referenced by onInitialize().
|
private |
Definition at line 117 of file cp_ros2_timer.hpp.
Referenced by onInitialize().
|
private |
Definition at line 116 of file cp_ros2_timer.hpp.
Referenced by onInitialize(), and timerCallback().
| smacc2::SmaccSignal<void()> smacc2::client_core_components::CpRos2Timer::onTimerTick_ |
Definition at line 62 of file cp_ros2_timer.hpp.
Referenced by timerCallback().
|
private |
Definition at line 114 of file cp_ros2_timer.hpp.
Referenced by cancelTimer(), onInitialize(), startTimer(), stopTimer(), timerCallback(), and ~CpRos2Timer().