SMACC2
Public Member Functions | Protected Attributes | List of all members
cl_nav2z::CbPauseSlam Class Reference

#include <cb_pause_slam.hpp>

Inheritance diagram for cl_nav2z::CbPauseSlam:
Inheritance graph
Collaboration diagram for cl_nav2z::CbPauseSlam:
Collaboration graph

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 ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage)
 

Protected Attributes

CpSlamToolboxslam_
 
- 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 ()
 
ISmaccStategetCurrentState ()
 
virtual void dispose ()
 
virtual rclcpp::Node::SharedPtr getNode ()
 
virtual rclcpp::Logger getLogger ()
 

Detailed Description

Definition at line 28 of file cb_pause_slam.hpp.

Constructor & Destructor Documentation

◆ CbPauseSlam()

cl_nav2z::CbPauseSlam::CbPauseSlam ( std::string  serviceName = "/slam_toolbox/pause_new_measurements")

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbPauseSlam::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 29 of file cb_pause_slam.cpp.

30{
31 this->requiresComponent(this->slam_);
32
33 auto currentState = slam_->getState();
34
36 {
37 RCLCPP_INFO(
38 getLogger(), "[CbPauseSlam] calling pause service to toggle from resumed to paused");
39 this->request_ = std::make_shared<slam_toolbox::srv::Pause::Request>();
41 this->slam_->toogleState();
42 }
43 else
44 {
45 this->request_ = nullptr;
46 RCLCPP_INFO(
47 getLogger(), "[CbPauseSlam] calling skipped. The current slam state is already paused.");
48 }
49}
CpSlamToolbox * slam_
SlamToolboxState getState()
void requiresComponent(SmaccComponentType *&storage)
std::shared_ptr< typename ServiceType::Request > request_

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().

Here is the call graph for this function:

Member Data Documentation

◆ slam_

CpSlamToolbox* cl_nav2z::CbPauseSlam::slam_
protected

Definition at line 35 of file cb_pause_slam.hpp.

Referenced by onEntry().


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