diff --git a/planning/behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_detection_area_module/src/manager.cpp index 99888d0789559..16d32b8a49964 100644 --- a/planning/behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_detection_area_module/src/manager.cpp @@ -15,6 +15,7 @@ #include "manager.hpp" #include +#include #include @@ -29,22 +30,24 @@ namespace behavior_velocity_planner { using lanelet::autoware::DetectionArea; +using tier4_autoware_utils::getOrDeclareParameter; DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node) : SceneModuleManagerInterfaceWithRTC( node, getModuleName(), - node.declare_parameter(std::string(getModuleName()) + ".enable_rtc")) + getOrDeclareParameter(node, std::string(getModuleName()) + ".enable_rtc")) { const std::string ns(getModuleName()); - planner_param_.stop_margin = node.declare_parameter(ns + ".stop_margin"); - planner_param_.use_dead_line = node.declare_parameter(ns + ".use_dead_line"); - planner_param_.dead_line_margin = node.declare_parameter(ns + ".dead_line_margin"); - planner_param_.use_pass_judge_line = node.declare_parameter(ns + ".use_pass_judge_line"); - planner_param_.state_clear_time = node.declare_parameter(ns + ".state_clear_time"); + planner_param_.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); + planner_param_.use_dead_line = getOrDeclareParameter(node, ns + ".use_dead_line"); + planner_param_.dead_line_margin = getOrDeclareParameter(node, ns + ".dead_line_margin"); + planner_param_.use_pass_judge_line = + getOrDeclareParameter(node, ns + ".use_pass_judge_line"); + planner_param_.state_clear_time = getOrDeclareParameter(node, ns + ".state_clear_time"); planner_param_.hold_stop_margin_distance = - node.declare_parameter(ns + ".hold_stop_margin_distance"); + getOrDeclareParameter(node, ns + ".hold_stop_margin_distance"); planner_param_.distance_to_judge_over_stop_line = - node.declare_parameter(ns + ".distance_to_judge_over_stop_line"); + getOrDeclareParameter(node, ns + ".distance_to_judge_over_stop_line"); } void DetectionAreaModuleManager::launchNewModules(