Skip to content

Commit a9cdf6e

Browse files
Fixed error handlings
Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
1 parent 98fba6a commit a9cdf6e

File tree

2 files changed

+2
-6
lines changed

2 files changed

+2
-6
lines changed

localization/ndt_scan_matcher/test/stub_initialpose_client.hpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,7 @@ class StubInitialposeClient : public rclcpp::Node
3838
// wait for the service to be available
3939
while (!align_service_client_->wait_for_service(std::chrono::seconds(1))) {
4040
if (!rclcpp::ok()) {
41-
RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service.");
42-
EXIT_FAILURE;
41+
throw std::runtime_error("Interrupted while waiting for the service.");
4342
}
4443
RCLCPP_INFO(this->get_logger(), "Waiting for service...");
4544
}
@@ -51,7 +50,6 @@ class StubInitialposeClient : public rclcpp::Node
5150
if (
5251
rclcpp::spin_until_future_complete(this->get_node_base_interface(), result) !=
5352
rclcpp::FutureReturnCode::SUCCESS) {
54-
RCLCPP_ERROR(this->get_logger(), "Service call failed");
5553
throw std::runtime_error("Service call failed.");
5654
}
5755
return result.get()->pose_with_covariance;

localization/ndt_scan_matcher/test/stub_trigger_node_client.hpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,7 @@ class StubTriggerNodeClient : public rclcpp::Node
3636
// wait for the service to be available
3737
while (!align_service_client_->wait_for_service(std::chrono::seconds(1))) {
3838
if (!rclcpp::ok()) {
39-
RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service.");
40-
EXIT_FAILURE;
39+
throw std::runtime_error("Interrupted while waiting for the service.");
4140
}
4241
RCLCPP_INFO(this->get_logger(), "Waiting for service...");
4342
}
@@ -49,7 +48,6 @@ class StubTriggerNodeClient : public rclcpp::Node
4948
if (
5049
rclcpp::spin_until_future_complete(this->get_node_base_interface(), result) !=
5150
rclcpp::FutureReturnCode::SUCCESS) {
52-
RCLCPP_ERROR(this->get_logger(), "Service call failed");
5351
throw std::runtime_error("Service call failed.");
5452
}
5553
return result.get()->success;

0 commit comments

Comments
 (0)