SMACC2
|
#include <cb_pause_slam.hpp>
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_future< std::shared_ptr< typename ServiceType::Response > > | resultFuture_ |
std::shared_ptr< typename ServiceType::Response > | result_ |
std::chrono::milliseconds | pollRate_ |
Protected Member Functions inherited from smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause > | |
virtual void | onServiceResponse (std::shared_ptr< typename ServiceType::Response >) |
Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
void | postSuccessEvent () |
void | postFailureEvent () |
virtual void | dispose () override |
bool | isShutdownRequested () |
onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread. | |
Protected Member Functions inherited from smacc2::ISmaccClientBehavior | |
virtual void | runtimeConfigure () |
template<typename EventType > | |
void | postEvent (const EventType &ev) |
template<typename EventType > | |
void | postEvent () |
ISmaccState * | getCurrentState () |
virtual rclcpp::Node::SharedPtr | getNode () const |
virtual rclcpp::Logger | getLogger () const |
Definition at line 28 of file cb_pause_slam.hpp.
cl_nitrosz::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_nitrosz::CpSlamToolbox::getState(), smacc2::client_behaviors::CbServiceCall< ServiceType >::onEntry(), smacc2::client_behaviors::CbServiceCall< slam_toolbox::srv::Pause >::request_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_nitrosz::CpSlamToolbox::Resumed, slam_, and cl_nitrosz::CpSlamToolbox::toogleState().
|
protected |
Definition at line 35 of file cb_pause_slam.hpp.
Referenced by onEntry().