|
SMACC2
|
#include <cp_slam_toolbox.hpp>


Public Types | |
| enum class | SlamToolboxState { Resumed , Paused } |
Public Member Functions | |
| CpSlamToolbox () | |
| virtual | ~CpSlamToolbox () |
| SlamToolboxState | getState () |
| void | toogleState () |
Public Member Functions inherited from smacc2::ISmaccComponent | |
| ISmaccComponent () | |
| virtual | ~ISmaccComponent () |
| virtual std::string | getName () const |
Private Attributes | |
| SlamToolboxState | state_ |
Additional Inherited Members | |
Protected Member Functions inherited from smacc2::ISmaccComponent | |
| virtual void | onInitialize () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TComponent > | |
| void | requiresComponent (TComponent *&requiredComponentStorage) |
| 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 () |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Definition at line 31 of file cp_slam_toolbox.hpp.
|
strong |
| Enumerator | |
|---|---|
| Resumed | |
| Paused | |
Definition at line 37 of file cp_slam_toolbox.hpp.
| cl_nav2z::CpSlamToolbox::CpSlamToolbox | ( | ) |
Definition at line 25 of file cp_slam_toolbox.cpp.
|
virtual |
Definition at line 26 of file cp_slam_toolbox.cpp.
|
inline |
Definition at line 43 of file cp_slam_toolbox.hpp.
References state_.
Referenced by cl_nav2z::CbPauseSlam::onEntry(), and cl_nav2z::CbResumeSlam::onEntry().

| void cl_nav2z::CpSlamToolbox::toogleState | ( | ) |
Definition at line 28 of file cp_slam_toolbox.cpp.
References Paused, Resumed, and state_.
Referenced by cl_nav2z::CbPauseSlam::onEntry(), and cl_nav2z::CbResumeSlam::onEntry().

|
private |
Definition at line 48 of file cp_slam_toolbox.hpp.
Referenced by getState(), and toogleState().