scenario_simulator_v2 C++ API
service.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
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 CONCEALER__SERVICE_HPP_
16 #define CONCEALER__SERVICE_HPP_
17 
18 #include <autoware_adapi_v1_msgs/msg/response_status.hpp>
19 #include <chrono>
21 #include <rclcpp/rclcpp.hpp>
23 #include <string>
24 #include <tier4_external_api_msgs/msg/response_status.hpp>
25 #include <tier4_rtc_msgs/msg/cooperate_response.hpp>
26 #include <tier4_rtc_msgs/srv/auto_mode_with_module.hpp>
27 #include <type_traits>
28 
29 namespace concealer
30 {
31 template <typename T>
32 class Service
33 {
34  const std::string name;
35 
36  typename rclcpp::Client<T>::SharedPtr client;
37 
38  rclcpp::WallRate interval;
39 
40 public:
41  template <typename Node>
42  explicit Service(
43  const std::string & name, Node & node,
44  const std::chrono::nanoseconds & interval = std::chrono::seconds(1))
45  : name(name),
46  client(node.template create_client<T>(name, rmw_qos_profile_default)),
47  interval(interval)
48  {
49  }
50 
51  auto operator()(const typename T::Request::SharedPtr & request, std::size_t attempts_count)
52  {
53  while (!client->service_is_ready()) {
54  interval.sleep();
55  }
56 
57  auto receive = [this](const auto & response) {
58  if constexpr (DetectMember_status<typename T::Response>::value) {
59  if constexpr (std::is_same_v<
60  tier4_external_api_msgs::msg::ResponseStatus,
61  decltype(T::Response::status)>) {
62  return response->status.code == tier4_external_api_msgs::msg::ResponseStatus::SUCCESS;
63  } else if constexpr (std::is_same_v<
64  autoware_adapi_v1_msgs::msg::ResponseStatus,
65  decltype(T::Response::status)>) {
66  return response->status.success;
67  } else {
68  static_assert([]() { return false; });
69  }
70  } else if constexpr (DetectMember_success<typename T::Response>::value) {
71  if constexpr (std::is_same_v<bool, decltype(T::Response::success)>) {
72  return response->success;
73  } else {
74  static_assert([]() { return false; });
75  }
76  } else if constexpr (DetectMember_responses<typename T::Response>::value) {
77  if constexpr (std::is_same_v<
78  std::vector<tier4_rtc_msgs::msg::CooperateResponse>,
79  decltype(T::Response::responses)>) {
80  return std::all_of(
81  response->responses.begin(), response->responses.end(),
82  [](const auto & response) { return response.success; });
83  } else {
84  static_assert([]() { return false; });
85  }
86  } else {
87  static_assert([]() { return false; });
88  }
89  };
90 
91  for (std::size_t attempt = 0; attempt < attempts_count; ++attempt, interval.sleep()) {
92  if (auto future = client->async_send_request(request);
93  future.wait_for(interval.period()) == std::future_status::ready and
94  receive(future.get())) {
95  return;
96  }
97  }
98 
100  "Requested the service ", std::quoted(name), " ", attempts_count,
101  " times, but was not successful.");
102  }
103 };
104 } // namespace concealer
105 
106 #endif //CONCEALER__SERVICE_HPP_
Definition: service.hpp:33
auto operator()(const typename T::Request::SharedPtr &request, std::size_t attempts_count)
Definition: service.hpp:51
Service(const std::string &name, Node &node, const std::chrono::nanoseconds &interval=std::chrono::seconds(1))
Definition: service.hpp:42
Definition: autoware_universe.hpp:40
constexpr int SUCCESS
Definition: constants.hpp:22
std::string string
Definition: junit5.hpp:26
Autoware encountered some problem that led to a simulation failure.
Definition: exception.hpp:41