26namespace client_behaviors
28using namespace std::chrono_literals;
29template <
typename ServiceType>
35 request_ = std::make_shared<typename ServiceType::Request>();
40 const char * serviceName, std::shared_ptr<typename ServiceType::Request> request,
41 std::chrono::milliseconds pollRate = 100ms)
61 getLogger(),
"thread state: " << (
int)status <<
" ok " << rclcpp::ok() <<
" shutdown "
65 RCLCPP_DEBUG_STREAM(
getLogger(),
"[" << this->
getName() <<
"] waiting response ");
70 if (status == std::future_status::ready)
72 RCLCPP_DEBUG_STREAM(
getLogger(),
"[" << this->
getName() <<
"] response received ");
79 RCLCPP_DEBUG_STREAM(
getLogger(),
"[" << this->
getName() <<
"] response not received ");
85 typename std::shared_ptr<typename ServiceType::Response>
result_;
90 std::shared_ptr<rclcpp::Client<ServiceType>>
client_;
92 std::shared_ptr<typename ServiceType::Request>
request_;
96 RCLCPP_DEBUG_STREAM(
getLogger(),
"[" << this->
getName() <<
"] response received ");
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
bool isShutdownRequested()
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_
rclcpp::Client< ServiceType >::SharedFuture resultFuture_
virtual void onServiceResponse(std::shared_ptr< typename ServiceType::Response >)