SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
smacc2::client_behaviors::CbServiceCall< ServiceType > Class Template Reference

#include <cb_call_service.hpp>

Inheritance diagram for smacc2::client_behaviors::CbServiceCall< ServiceType >:
Inheritance graph
Collaboration diagram for smacc2::client_behaviors::CbServiceCall< ServiceType >:
Collaboration graph

Public Member Functions

 CbServiceCall (const char *serviceName)
 
 CbServiceCall (const char *serviceName, std::shared_ptr< typename ServiceType::Request > request, std::chrono::milliseconds pollRate=100ms)
 
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)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod 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, bool throwExceptionIfNotExist=false)
 
virtual void onEntry ()
 
virtual void onExit ()
 
virtual void executeOnEntry ()
 
virtual void executeOnExit ()
 

Public Attributes

rclcpp::Client< ServiceType >::SharedFuture resultFuture_
 
std::shared_ptr< typename ServiceType::Response > result_
 
std::chrono::milliseconds pollRate_
 

Protected Member Functions

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 ()
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual void dispose ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Protected Attributes

std::shared_ptr< rclcpp::Client< ServiceType > > client_
 
std::string serviceName_
 
std::shared_ptr< typename ServiceType::Request > request_
 

Detailed Description

template<typename ServiceType>
class smacc2::client_behaviors::CbServiceCall< ServiceType >

Definition at line 30 of file cb_call_service.hpp.

Constructor & Destructor Documentation

◆ CbServiceCall() [1/2]

template<typename ServiceType >
smacc2::client_behaviors::CbServiceCall< ServiceType >::CbServiceCall ( const char *  serviceName)
inline

Definition at line 33 of file cb_call_service.hpp.

33 : serviceName_(serviceName)
34 {
35 request_ = std::make_shared<typename ServiceType::Request>();
36 pollRate_ = 100ms;
37 }
std::shared_ptr< typename ServiceType::Request > request_

References smacc2::client_behaviors::CbServiceCall< ServiceType >::pollRate_, and smacc2::client_behaviors::CbServiceCall< ServiceType >::request_.

◆ CbServiceCall() [2/2]

template<typename ServiceType >
smacc2::client_behaviors::CbServiceCall< ServiceType >::CbServiceCall ( const char *  serviceName,
std::shared_ptr< typename ServiceType::Request >  request,
std::chrono::milliseconds  pollRate = 100ms 
)
inline

Definition at line 39 of file cb_call_service.hpp.

42 : serviceName_(serviceName), request_(request), result_(nullptr), pollRate_(pollRate)
43 {
44 }
std::shared_ptr< typename ServiceType::Response > result_

Member Function Documentation

◆ onEntry()

template<typename ServiceType >
void smacc2::client_behaviors::CbServiceCall< ServiceType >::onEntry ( )
inlineoverridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 46 of file cb_call_service.hpp.

47 {
48 RCLCPP_DEBUG_STREAM(
49 getLogger(), "[" << this->getName() << "] creating ros service client: " << serviceName_);
50
51 client_ = getNode()->create_client<ServiceType>(serviceName_);
52
53 RCLCPP_DEBUG_STREAM(
54 getLogger(), "[" << this->getName() << "] making service request to " << serviceName_);
55
56 resultFuture_ = client_->async_send_request(request_);
57
58 std::future_status status = resultFuture_.wait_for(0s);
59
60 RCLCPP_DEBUG_STREAM(
61 getLogger(), "thread state: " << (int)status << " ok " << rclcpp::ok() << " shutdown "
62 << this->isShutdownRequested() << "");
63 while (status != std::future_status::ready && rclcpp::ok() && !this->isShutdownRequested())
64 {
65 RCLCPP_DEBUG_STREAM(getLogger(), "[" << this->getName() << "] waiting response ");
66 rclcpp::sleep_for(pollRate_);
67 status = resultFuture_.wait_for(0s);
68 }
69
70 if (status == std::future_status::ready)
71 {
72 RCLCPP_DEBUG_STREAM(getLogger(), "[" << this->getName() << "] response received ");
73 result_ = resultFuture_.get();
75 this->postSuccessEvent();
76 }
77 else
78 {
79 RCLCPP_DEBUG_STREAM(getLogger(), "[" << this->getName() << "] response not received ");
80 this->postFailureEvent();
81 }
82 }
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
std::shared_ptr< rclcpp::Client< ServiceType > > client_
rclcpp::Client< ServiceType >::SharedFuture resultFuture_
virtual void onServiceResponse(std::shared_ptr< typename ServiceType::Response >)

References smacc2::client_behaviors::CbServiceCall< ServiceType >::client_, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), smacc2::SmaccAsyncClientBehavior::isShutdownRequested(), smacc2::client_behaviors::CbServiceCall< ServiceType >::onServiceResponse(), smacc2::client_behaviors::CbServiceCall< ServiceType >::pollRate_, smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), smacc2::client_behaviors::CbServiceCall< ServiceType >::request_, smacc2::client_behaviors::CbServiceCall< ServiceType >::result_, smacc2::client_behaviors::CbServiceCall< ServiceType >::resultFuture_, and smacc2::client_behaviors::CbServiceCall< ServiceType >::serviceName_.

Referenced by cl_nav2z::CbResumeSlam::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onServiceResponse()

template<typename ServiceType >
virtual void smacc2::client_behaviors::CbServiceCall< ServiceType >::onServiceResponse ( std::shared_ptr< typename ServiceType::Response >  )
inlineprotectedvirtual

Definition at line 94 of file cb_call_service.hpp.

95 {
96 RCLCPP_DEBUG_STREAM(getLogger(), "[" << this->getName() << "] response received ");
97 }

References smacc2::ISmaccClientBehavior::getLogger(), and smacc2::ISmaccClientBehavior::getName().

Referenced by smacc2::client_behaviors::CbServiceCall< ServiceType >::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ client_

template<typename ServiceType >
std::shared_ptr<rclcpp::Client<ServiceType> > smacc2::client_behaviors::CbServiceCall< ServiceType >::client_
protected

◆ pollRate_

template<typename ServiceType >
std::chrono::milliseconds smacc2::client_behaviors::CbServiceCall< ServiceType >::pollRate_

◆ request_

template<typename ServiceType >
std::shared_ptr<typename ServiceType::Request> smacc2::client_behaviors::CbServiceCall< ServiceType >::request_
protected

◆ result_

template<typename ServiceType >
std::shared_ptr<typename ServiceType::Response> smacc2::client_behaviors::CbServiceCall< ServiceType >::result_

◆ resultFuture_

template<typename ServiceType >
rclcpp::Client<ServiceType>::SharedFuture smacc2::client_behaviors::CbServiceCall< ServiceType >::resultFuture_

◆ serviceName_

template<typename ServiceType >
std::string smacc2::client_behaviors::CbServiceCall< ServiceType >::serviceName_
protected

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