diff --git a/external/concealer/include/concealer/service_with_validation.hpp b/external/concealer/include/concealer/service_with_validation.hpp index 9d1b0c23d9b..da002bf25be 100644 --- a/external/concealer/include/concealer/service_with_validation.hpp +++ b/external/concealer/include/concealer/service_with_validation.hpp @@ -42,17 +42,7 @@ class ServiceWithValidation { } - class TimeoutError : public common::scenario_simulator_exception::Error - { - public: - template - explicit TimeoutError(Ts &&... xs) - : common::scenario_simulator_exception::Error(std::forward(xs)...) - { - } - }; - - auto operator()(const typename T::Request::SharedPtr & request, std::size_t attempts_count = 1) + auto operator()(const typename T::Request::SharedPtr & request, std::size_t attempts_count) -> void { validateAvailability(); @@ -122,7 +112,7 @@ class ServiceWithValidation } } } - throw TimeoutError( + throw common::scenario_simulator_exception::Error( "Requested the service ", std::quoted(service_name), " ", attempts_count, " times, but was not successful."); } diff --git a/external/concealer/src/field_operator_application.cpp b/external/concealer/src/field_operator_application.cpp index c197d4182d1..3ee855dd3bd 100644 --- a/external/concealer/src/field_operator_application.cpp +++ b/external/concealer/src/field_operator_application.cpp @@ -318,10 +318,9 @@ auto FieldOperatorApplication::engage() -> void auto request = std::make_shared(); request->engage = true; try { - return requestEngage(request); - } catch (const decltype(requestEngage)::TimeoutError &) { - // ignore timeout error because this service is validated by Autoware state transition. - return; + return requestEngage(request, 1); + } catch (const common::Error &) { + return; // Ignore error because this service is validated by Autoware state transition. } }); }); @@ -369,10 +368,9 @@ auto FieldOperatorApplication::initialize(const geometry_msgs::msg::Pose & initi std::make_shared(); request->pose.push_back(initial_pose_msg); try { - return requestInitialPose(request); - } catch (const decltype(requestInitialPose)::TimeoutError &) { - // ignore timeout error because this service is validated by Autoware state transition. - return; + return requestInitialPose(request, 1); + } catch (const common::Error &) { + return; // Ignore error because this service is validated by Autoware state transition. } }); }); @@ -417,7 +415,7 @@ auto FieldOperatorApplication::plan(const std::vectorwaypoints.push_back(each.pose); } - requestSetRoutePoints(request); + requestSetRoutePoints(request, 1); waitForAutowareStateToBeWaitingForEngage(); }); @@ -512,7 +510,7 @@ auto FieldOperatorApplication::sendCooperateCommand( request->stamp = latest_cooperate_status_array.stamp; request->commands.push_back(cooperate_command); - task_queue.delay([this, request]() { requestCooperateCommands(request); }); + task_queue.delay([this, request]() { requestCooperateCommands(request, 1); }); used_cooperate_statuses.push_back(*cooperate_status); }