Skip to content

Commit 1ce4a39

Browse files
style(pre-commit): autofix
1 parent e5ce69b commit 1ce4a39

File tree

2 files changed

+17
-13
lines changed

2 files changed

+17
-13
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+4-8
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,6 @@
3838
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
3939
#include <nav_msgs/msg/odometry.hpp>
4040

41-
4241
struct HazardLampPolicy
4342
{
4443
bool emergency;
@@ -66,12 +65,8 @@ class MrmHandler : public rclcpp::Node
6665
MrmHandler();
6766

6867
private:
69-
//type
70-
enum RequestType
71-
{
72-
CALL,
73-
CANCEL
74-
};
68+
// type
69+
enum RequestType { CALL, CANCEL };
7570

7671
// Subscribers
7772
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
@@ -134,7 +129,8 @@ class MrmHandler : public rclcpp::Node
134129
rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_emergency_stop_;
135130

136131
bool requestMrmBehavior(
137-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior, RequestType request_type) const;
132+
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
133+
RequestType request_type) const;
138134
void logMrmCallingResult(
139135
const tier4_system_msgs::srv::OperateMrm::Response & result, const std::string & behavior,
140136
bool is_call) const;

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+13-5
Original file line numberDiff line numberDiff line change
@@ -272,7 +272,8 @@ void MrmHandler::handlePostFailureRequest()
272272
}
273273

274274
bool MrmHandler::requestMrmBehavior(
275-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior, RequestType request_type) const
275+
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
276+
RequestType request_type) const
276277
{
277278
using autoware_adapi_v1_msgs::msg::MrmState;
278279

@@ -285,7 +286,8 @@ bool MrmHandler::requestMrmBehavior(
285286
RCLCPP_ERROR(this->get_logger(), "invalid request type: %d", request_type);
286287
return false;
287288
}
288-
const auto duration = std::chrono::duration<double, std::ratio<1>>(request->operate ? param_.timeout_call_mrm_behavior : param_.timeout_cancel_mrm_behavior);
289+
const auto duration = std::chrono::duration<double, std::ratio<1>>(
290+
request->operate ? param_.timeout_call_mrm_behavior : param_.timeout_cancel_mrm_behavior);
289291
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
290292

291293
const auto behavior2string = [](const int behavior) {
@@ -329,14 +331,20 @@ bool MrmHandler::requestMrmBehavior(
329331
if (future.wait_for(duration) == std::future_status::ready) {
330332
const auto result = future.get();
331333
if (result->response.success == true) {
332-
RCLCPP_WARN(this->get_logger(), request->operate ? "%s is operated." : "%s is canceled.", behavior2string(mrm_behavior));
334+
RCLCPP_WARN(
335+
this->get_logger(), request->operate ? "%s is operated." : "%s is canceled.",
336+
behavior2string(mrm_behavior));
333337
return true;
334338
} else {
335-
RCLCPP_ERROR(this->get_logger(), request->operate ? "%s failed to operate." : "%s failed to cancel.", behavior2string(mrm_behavior));
339+
RCLCPP_ERROR(
340+
this->get_logger(), request->operate ? "%s failed to operate." : "%s failed to cancel.",
341+
behavior2string(mrm_behavior));
336342
return false;
337343
}
338344
} else {
339-
RCLCPP_ERROR(this->get_logger(), request->operate ? "%s call timed out." : "%s cancel timed out.", behavior2string(mrm_behavior));
345+
RCLCPP_ERROR(
346+
this->get_logger(), request->operate ? "%s call timed out." : "%s cancel timed out.",
347+
behavior2string(mrm_behavior));
340348
return false;
341349
}
342350
}

0 commit comments

Comments
 (0)