From 6f46242cca93003fd8395f5fcb37aafeea676ab8 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Wed, 10 Apr 2024 10:51:23 +0900 Subject: [PATCH] cleanup code Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --- .../fault_injection/fault_injection_node.hpp | 5 ---- .../fault_injection_node.cpp | 27 ------------------- 2 files changed, 32 deletions(-) diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp index 0af84a5448019..999d18b38c7b0 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp +++ b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp @@ -39,11 +39,6 @@ class FaultInjectionNode : public rclcpp::Node void on_simulation_events(const SimulationEvents::ConstSharedPtr msg); rclcpp::Subscription::SharedPtr sub_simulation_events_; - // Parameter Server - rcl_interfaces::msg::SetParametersResult on_set_param( - const std::vector & params); - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - void update_event_diag( diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name); diff --git a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp index 289b0602bb1f3..7b8f87400beab 100644 --- a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp +++ b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp @@ -49,10 +49,6 @@ FaultInjectionNode::FaultInjectionNode(rclcpp::NodeOptions node_options) using std::placeholders::_1; - // Parameter Server - set_param_res_ = - this->add_on_set_parameters_callback(std::bind(&FaultInjectionNode::on_set_param, this, _1)); - // Subscriber sub_simulation_events_ = this->create_subscription( "~/input/simulation_events", rclcpp::QoS{rclcpp::KeepLast(10)}, @@ -86,29 +82,6 @@ void FaultInjectionNode::update_event_diag( wrap.hardware_id = diag.hardware_id; } -rcl_interfaces::msg::SetParametersResult FaultInjectionNode::on_set_param( - const std::vector & params) -{ - rcl_interfaces::msg::SetParametersResult result; - - RCLCPP_DEBUG(this->get_logger(), "call on_set_param"); - - try { - double value = NAN; - if (tier4_autoware_utils::updateParam(params, "diagnostic_updater.period", value)) { - updater_.set_period(value); - } - } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { - result.successful = false; - result.reason = e.what(); - return result; - } - - result.successful = true; - result.reason = "success"; - return result; -} - std::vector FaultInjectionNode::read_event_diag_list() { // Expected parameter name is "event_diag_list.param_name".