|
SMACC2
|
#include <cb_pause_slam.hpp>


Public Member Functions | |
| CbPauseSlam (std::string serviceName="/slam_toolbox/pause_new_measurements") | |
| void | onEntry () override |
Public Member Functions inherited from smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause > | |
| CbServiceCall (const char *serviceName) | |
| CbServiceCall (const char *serviceName, std::shared_ptr< typename ServiceType::Request >) | |
| void | onEntry () override |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| virtual | ~SmaccAsyncClientBehavior () |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onSuccess (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFinished (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFailure (TCallback callback, T *object) |
Public Member Functions inherited from smacc2::ISmaccClientBehavior | |
| ISmaccClientBehavior () | |
| virtual | ~ISmaccClientBehavior () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage) |
Protected Attributes | |
| CpSlamToolbox * | slam_ |
Protected Attributes inherited from smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause > | |
| std::shared_ptr< rclcpp::Client< slam_toolbox::srv::Pause > > | client_ |
| std::string | serviceName_ |
| std::shared_ptr< typename ServiceType::Request > | request_ |
Additional Inherited Members | |
Public Attributes inherited from smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause > | |
| std::shared_ptr< typename ServiceType::Response > | result_ |
Protected Member Functions inherited from smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause > | |
| void | onServiceResponse (typename rclcpp::Client< slam_toolbox::srv::Pause >::SharedFuture result) |
Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| void | postSuccessEvent () |
| void | postFailureEvent () |
| virtual void | dispose () override |
| bool | isShutdownRequested () |
Protected Member Functions inherited from smacc2::ISmaccClientBehavior | |
| virtual void | runtimeConfigure () |
| virtual void | onEntry () |
| virtual void | onExit () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| ISmaccState * | getCurrentState () |
| virtual void | dispose () |
| virtual rclcpp::Node::SharedPtr | getNode () |
| virtual rclcpp::Logger | getLogger () |
Definition at line 28 of file cb_pause_slam.hpp.
| cl_nav2z::CbPauseSlam::CbPauseSlam | ( | std::string | serviceName = "/slam_toolbox/pause_new_measurements" | ) |
Definition at line 24 of file cb_pause_slam.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 29 of file cb_pause_slam.cpp.
References smacc2::ISmaccClientBehavior::currentState, smacc2::ISmaccClientBehavior::getLogger(), cl_nav2z::CpSlamToolbox::getState(), smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause >::onEntry(), smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause >::request_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_nav2z::CpSlamToolbox::Resumed, slam_, and cl_nav2z::CpSlamToolbox::toogleState().

|
protected |
Definition at line 35 of file cb_pause_slam.hpp.
Referenced by onEntry().