|
| 1 | +// Copyright 2021 Tier IV, 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 | +#ifndef AUTOWARE_API_UTILS__RCLCPP__CLIENT_HPP_ |
| 16 | +#define AUTOWARE_API_UTILS__RCLCPP__CLIENT_HPP_ |
| 17 | + |
| 18 | +#include "autoware_api_utils/types/response.hpp" |
| 19 | +#include "rclcpp/client.hpp" |
| 20 | + |
| 21 | +#include <chrono> |
| 22 | +#include <utility> |
| 23 | + |
| 24 | +namespace autoware_api_utils |
| 25 | +{ |
| 26 | +template <typename ServiceT> |
| 27 | +class Client |
| 28 | +{ |
| 29 | +public: |
| 30 | + RCLCPP_SMART_PTR_DEFINITIONS(Client) |
| 31 | + |
| 32 | + using ResponseStatus = autoware_external_api_msgs::msg::ResponseStatus; |
| 33 | + using AutowareServiceResult = std::pair<ResponseStatus, typename ServiceT::Response::SharedPtr>; |
| 34 | + |
| 35 | + Client(typename rclcpp::Client<ServiceT>::SharedPtr client, rclcpp::Logger logger) |
| 36 | + : client_(client), logger_(logger) |
| 37 | + { |
| 38 | + } |
| 39 | + |
| 40 | + AutowareServiceResult call( |
| 41 | + const typename ServiceT::Request::SharedPtr & request, |
| 42 | + const std::chrono::nanoseconds & timeout = std::chrono::seconds(2)) |
| 43 | + { |
| 44 | + RCLCPP_INFO( |
| 45 | + logger_, "client request: \n%s", rosidl_generator_traits::to_yaml(*request).c_str()); |
| 46 | + |
| 47 | + if (!client_->service_is_ready()) { |
| 48 | + RCLCPP_INFO(logger_, "client available"); |
| 49 | + return {response_error("Internal service is not available."), nullptr}; |
| 50 | + } |
| 51 | + |
| 52 | + auto future = client_->async_send_request(request); |
| 53 | + if (future.wait_for(timeout) != std::future_status::ready) { |
| 54 | + RCLCPP_INFO(logger_, "client timeout"); |
| 55 | + return {response_error("Internal service has timed out."), nullptr}; |
| 56 | + } |
| 57 | + |
| 58 | + RCLCPP_INFO( |
| 59 | + logger_, "client response: \n%s", rosidl_generator_traits::to_yaml(future.get()).c_str()); |
| 60 | + return {response_success(), future.get()}; |
| 61 | + } |
| 62 | + |
| 63 | +private: |
| 64 | + RCLCPP_DISABLE_COPY(Client) |
| 65 | + |
| 66 | + typename rclcpp::Client<ServiceT>::SharedPtr client_; |
| 67 | + rclcpp::Logger logger_; |
| 68 | +}; |
| 69 | + |
| 70 | +} // namespace autoware_api_utils |
| 71 | + |
| 72 | +#endif // AUTOWARE_API_UTILS__RCLCPP__CLIENT_HPP_ |
0 commit comments