From ff30adc6028d48548eadcd6350257fe3ae106fe3 Mon Sep 17 00:00:00 2001 From: yamazakiTasuku Date: Sat, 18 Mar 2023 18:42:19 +0900 Subject: [PATCH] scenario_selector_delete_param Signed-off-by: yamazakiTasuku --- .../scenario_selector_node/scenario_selector_node.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index a9e82f46161e6..8f20b6b655d3b 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -351,11 +351,11 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_), current_scenario_(tier4_planning_msgs::msg::Scenario::EMPTY), - update_rate_(this->declare_parameter("update_rate", 10.0)), - th_max_message_delay_sec_(this->declare_parameter("th_max_message_delay_sec", 1.0)), - th_arrived_distance_m_(this->declare_parameter("th_arrived_distance_m", 1.0)), - th_stopped_time_sec_(this->declare_parameter("th_stopped_time_sec", 1.0)), - th_stopped_velocity_mps_(this->declare_parameter("th_stopped_velocity_mps", 0.01)), + update_rate_(this->declare_parameter("update_rate")), + th_max_message_delay_sec_(this->declare_parameter("th_max_message_delay_sec")), + th_arrived_distance_m_(this->declare_parameter("th_arrived_distance_m")), + th_stopped_time_sec_(this->declare_parameter("th_stopped_time_sec")), + th_stopped_velocity_mps_(this->declare_parameter("th_stopped_velocity_mps")), is_parking_completed_(false) { // Input