26namespace client_behaviors
28using namespace std::chrono_literals;
29template <
typename ServiceType>
35 request_ = std::make_shared<typename ServiceType::Request>();
61 getLogger(),
"thread state: " << (
int)
status <<
" ok " << rclcpp::ok() <<
" shutdown "
68 "[" << this->
getName() <<
"] waiting response ");
73 if (
status == std::future_status::ready)
82 RCLCPP_INFO_STREAM(
getLogger(),
"[" << this->
getName() <<
"] response not received ");
87 std::shared_future<std::shared_ptr<typename ServiceType::Response>>
resultFuture_;
89 typename std::shared_ptr<typename ServiceType::Response>
result_;
94 std::shared_ptr<rclcpp::Client<ServiceType>>
client_;
96 std::shared_ptr<typename ServiceType::Request>
request_;
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
bool isShutdownRequested()
onEntry is executed in a new thread. However the current state cannot be left until the onEntry threa...
std::shared_ptr< typename ServiceType::Response > result_
std::shared_ptr< typename ServiceType::Request > request_
std::shared_ptr< rclcpp::Client< ServiceType > > client_
CbServiceCall(const char *serviceName, std::shared_ptr< typename ServiceType::Request > request, std::chrono::milliseconds pollRate=100ms)
CbServiceCall(const char *serviceName)
std::chrono::milliseconds pollRate_
virtual void onServiceResponse(std::shared_ptr< typename ServiceType::Response >)
std::shared_future< std::shared_ptr< typename ServiceType::Response > > resultFuture_