15 #ifndef CONCEALER__SERVICE_HPP_
16 #define CONCEALER__SERVICE_HPP_
18 #include <autoware_adapi_v1_msgs/msg/response_status.hpp>
21 #include <rclcpp/rclcpp.hpp>
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>
36 typename rclcpp::Client<T>::SharedPtr client;
38 rclcpp::WallRate interval;
41 template <
typename Node>
44 const std::chrono::nanoseconds & interval = std::chrono::seconds(1))
46 client(node.template create_client<T>(name, rmw_qos_profile_default)),
51 auto operator()(
const typename T::Request::SharedPtr & request, std::size_t attempts_count)
53 while (!client->service_is_ready()) {
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)>) {
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;
68 static_assert([]() {
return false; });
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;
74 static_assert([]() {
return false; });
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)>) {
81 response->responses.begin(), response->responses.end(),
82 [](
const auto & response) { return response.success; });
84 static_assert([]() {
return false; });
87 static_assert([]() {
return false; });
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())) {
100 "Requested the service ", std::quoted(name),
" ", attempts_count,
101 " times, but was not successful.");
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