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:
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)
43 {
44 }
45
46 void onEntry() override
47 {
49 getLogger(), "[" << this->getName() << "] creating ros service client: " << serviceName_);
50
51 client_ = getNode()->create_client<ServiceType>(serviceName_);
52
54 getLogger(), "[" << this->getName() << "] making service request to " << serviceName_);
55
56 resultFuture_ = client_->async_send_request(request_).future.share();
57
58 std::future_status status = resultFuture_.wait_for(0s);
59
61 getLogger(), "thread state: " << (int)status << " ok " << rclcpp::ok() << " shutdown "
62 << this->isShutdownRequested() << "");
63
64 while (status != std::future_status::ready && rclcpp::ok() && !this->isShutdownRequested())
65 {
67 getLogger(), *getNode()->get_clock(), 1000,
68 "[" << this->getName() << "] waiting response ");
69 rclcpp::sleep_for(pollRate_);
70 status = resultFuture_.wait_for(0s);
71 }
72
73 if (status == std::future_status::ready)
74 {
75 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] response received ");
76 result_ = resultFuture_.get();
78 this->postSuccessEvent();
79 }
80 else
81 {
82 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] response not received ");
83 this->postFailureEvent();
84 }
85 }
86
87 std::shared_future<std::shared_ptr<typename ServiceType::Response>> resultFuture_;
88
89 typename std::shared_ptr<typename ServiceType::Response> result_;
90 std::chrono::milliseconds pollRate_;
91
92protected:
93 //rclcpp::NodeHandle nh_;
94 std::shared_ptr<rclcpp::Client<ServiceType>> client_;
95 std::string serviceName_;
96 std::shared_ptr<typename ServiceType::Request> request_;
97
98 virtual void onServiceResponse(std::shared_ptr<typename ServiceType::Response> /*result*/)
99 {
100 RCLCPP_INFO_STREAM(getLogger(), "[" << this->getName() << "] response received ");
101 }
102};
103
104} // namespace client_behaviors
105} // namespace smacc2
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)
virtual void onServiceResponse(std::shared_ptr< typename ServiceType::Response >)
std::shared_future< std::shared_ptr< typename ServiceType::Response > > resultFuture_