From d2b9ffc6d64c358ecf567309503b8f4491f66b6f Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 19 Dec 2024 12:41:34 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../launch/control.launch.py | 12 ++++--- .../dummy_diag_publisher_core.hpp | 3 +- .../src/dummy_diag_publisher_core.cpp | 33 +++++++++++-------- 3 files changed, 28 insertions(+), 20 deletions(-) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index b8b8e347ad32b..90190dc655bb4 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -30,13 +30,15 @@ from launch_ros.substitutions import FindPackageShare import yaml + def get_control_cmd_topic(context): - is_redundant = LaunchConfiguration('launch_redundancy_system_components').perform(context) - system_run_mode = LaunchConfiguration('system_run_mode').perform(context) + is_redundant = LaunchConfiguration("launch_redundancy_system_components").perform(context) + system_run_mode = LaunchConfiguration("system_run_mode").perform(context) + + if is_redundant.lower() == "true" and system_run_mode.lower() == "planning_simulation": + return "/main/control/command/control_cmd" + return "/control/command/control_cmd" - if is_redundant.lower() == 'true' and system_run_mode.lower() == 'planning_simulation': - return '/main/control/command/control_cmd' - return '/control/command/control_cmd' def launch_setup(context, *args, **kwargs): with open(LaunchConfiguration("vehicle_param_file").perform(context), "r") as f: diff --git a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp index 97a7a9efdd7f4..64e2e0426046d 100644 --- a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp +++ b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp @@ -63,7 +63,8 @@ class DummyDiagPublisher : public rclcpp::Node rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_; void loadRequiredDiags(); - rcl_interfaces::msg::SetParametersResult onSetParams(const std::vector & parameters); + rcl_interfaces::msg::SetParametersResult onSetParams( + const std::vector & parameters); std::optional convertStrToStatus(const std::string & status_str); std::string convertStatusToStr(const Status & status); diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index a7144ee56227e..805a334bfe36e 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -16,6 +16,7 @@ #define FMT_HEADER_ONLY #include + #include #include @@ -141,8 +142,8 @@ rclcpp::NodeOptions override_options(rclcpp::NodeOptions options) true); } -rcl_interfaces::msg::SetParametersResult - DummyDiagPublisher::onSetParams(const std::vector & parameters) +rcl_interfaces::msg::SetParametersResult DummyDiagPublisher::onSetParams( + const std::vector & parameters) { rcl_interfaces::msg::SetParametersResult result; result.successful = true; @@ -157,25 +158,29 @@ rcl_interfaces::msg::SetParametersResult auto new_status = convertStrToStatus(parameter.as_string()); if (new_status) { diag.status = *new_status; - RCLCPP_INFO(this->get_logger(), "Updated %s status to: %s", - diag.name.c_str(), parameter.as_string().c_str()); + RCLCPP_INFO( + this->get_logger(), "Updated %s status to: %s", diag.name.c_str(), + parameter.as_string().c_str()); } else { result.successful = false; result.reason = "Invalid status value for: " + parameter.as_string(); - RCLCPP_WARN(this->get_logger(), "Invalid status value for %s: %s", - diag.name.c_str(), parameter.as_string().c_str()); + RCLCPP_WARN( + this->get_logger(), "Invalid status value for %s: %s", diag.name.c_str(), + parameter.as_string().c_str()); } } else if (param_name == diag.name + std::string(".is_active")) { param_found = true; try { diag.is_active = parameter.as_bool(); - RCLCPP_INFO(this->get_logger(), "Updated %s is_active to: %s", - diag.name.c_str(), diag.is_active ? "true" : "false"); + RCLCPP_INFO( + this->get_logger(), "Updated %s is_active to: %s", diag.name.c_str(), + diag.is_active ? "true" : "false"); } catch (const rclcpp::ParameterTypeException & e) { result.successful = false; result.reason = "Invalid is_active value for: " + parameter.as_string(); - RCLCPP_WARN(this->get_logger(), "Invalid is_active value for %s: %s", - diag.name.c_str(), parameter.as_string().c_str()); + RCLCPP_WARN( + this->get_logger(), "Invalid is_active value for %s: %s", diag.name.c_str(), + parameter.as_string().c_str()); } } } @@ -183,8 +188,9 @@ rcl_interfaces::msg::SetParametersResult if (!param_found) { result.successful = false; result.reason = "Parameter not registered: " + parameter.get_name(); - RCLCPP_WARN(this->get_logger(), "Attempted to set unregistered parameter: %s", - parameter.get_name().c_str()); + RCLCPP_WARN( + this->get_logger(), "Attempted to set unregistered parameter: %s", + parameter.get_name().c_str()); } } @@ -214,8 +220,7 @@ DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) // Parameter Callback Handle param_callback_handle_ = this->add_on_set_parameters_callback( - std::bind(&DummyDiagPublisher::onSetParams, this, std::placeholders::_1) - ); + std::bind(&DummyDiagPublisher::onSetParams, this, std::placeholders::_1)); } #include