Skip to content

Commit

Permalink
Remove class ServceWithValidation::TimeoutError
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Dec 17, 2024
1 parent 2400c42 commit 2104027
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 22 deletions.
14 changes: 2 additions & 12 deletions external/concealer/include/concealer/service_with_validation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,17 +42,7 @@ class ServiceWithValidation
{
}

class TimeoutError : public common::scenario_simulator_exception::Error
{
public:
template <typename... Ts>
explicit TimeoutError(Ts &&... xs)
: common::scenario_simulator_exception::Error(std::forward<decltype(xs)>(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();
Expand Down Expand Up @@ -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.");
}
Expand Down
18 changes: 8 additions & 10 deletions external/concealer/src/field_operator_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -318,10 +318,9 @@ auto FieldOperatorApplication::engage() -> void
auto request = std::make_shared<Engage::Request>();
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.
}
});
});
Expand Down Expand Up @@ -369,10 +368,9 @@ auto FieldOperatorApplication::initialize(const geometry_msgs::msg::Pose & initi
std::make_shared<autoware_adapi_v1_msgs::srv::InitializeLocalization::Request>();
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.
}
});
});
Expand Down Expand Up @@ -417,7 +415,7 @@ auto FieldOperatorApplication::plan(const std::vector<geometry_msgs::msg::PoseSt
request->waypoints.push_back(each.pose);
}

requestSetRoutePoints(request);
requestSetRoutePoints(request, 1);

waitForAutowareStateToBeWaitingForEngage();
});
Expand Down Expand Up @@ -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);
}
Expand Down

0 comments on commit 2104027

Please sign in to comment.