SMACC2
Loading...
Searching...
No Matches
cb_call_service.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
23
24namespace smacc2
25{
26namespace client_behaviors
27{
28using namespace std::chrono_literals;
29template <typename ServiceType>
31{
32public:
33 CbServiceCall(const char * serviceName) : serviceName_(serviceName)
34 {
35 request_ = std::make_shared<typename ServiceType::Request>();
36 pollRate_ = 100ms;
37 }
38
40 const char * serviceName, std::shared_ptr<typename ServiceType::Request> request,
41 std::chrono::milliseconds pollRate = 100ms)
42 : serviceName_(serviceName), request_(request), result_(nullptr), pollRate_(pollRate)
43 {
44 }
45
46 void onEntry() override
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 }
83
84 typename rclcpp::Client<ServiceType>::SharedFuture resultFuture_;
85 typename std::shared_ptr<typename ServiceType::Response> result_;
86 std::chrono::milliseconds pollRate_;
87
88protected:
89 //rclcpp::NodeHandle nh_;
90 std::shared_ptr<rclcpp::Client<ServiceType>> client_;
91 std::string serviceName_;
92 std::shared_ptr<typename ServiceType::Request> request_;
93
94 virtual void onServiceResponse(std::shared_ptr<typename ServiceType::Response> /*result*/)
95 {
96 RCLCPP_DEBUG_STREAM(getLogger(), "[" << this->getName() << "] response received ");
97 }
98};
99
100} // namespace client_behaviors
101} // namespace smacc2
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
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)
rclcpp::Client< ServiceType >::SharedFuture resultFuture_
virtual void onServiceResponse(std::shared_ptr< typename ServiceType::Response >)