Skip to content

Commit

Permalink
refactor(detection_area): use getOrDeclareParameter (autowarefoundati…
Browse files Browse the repository at this point in the history
…on#4766)

Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe authored Aug 28, 2023
1 parent e017725 commit ddb49ec
Showing 1 changed file with 11 additions and 8 deletions.
19 changes: 11 additions & 8 deletions planning/behavior_velocity_detection_area_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "manager.hpp"

#include <lanelet2_extension/utility/query.hpp>
#include <tier4_autoware_utils/ros/parameter.hpp>

#include <tf2/utils.h>

Expand All @@ -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<bool>(std::string(getModuleName()) + ".enable_rtc"))
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
planner_param_.stop_margin = node.declare_parameter<double>(ns + ".stop_margin");
planner_param_.use_dead_line = node.declare_parameter<bool>(ns + ".use_dead_line");
planner_param_.dead_line_margin = node.declare_parameter<double>(ns + ".dead_line_margin");
planner_param_.use_pass_judge_line = node.declare_parameter<bool>(ns + ".use_pass_judge_line");
planner_param_.state_clear_time = node.declare_parameter<double>(ns + ".state_clear_time");
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
planner_param_.use_dead_line = getOrDeclareParameter<bool>(node, ns + ".use_dead_line");
planner_param_.dead_line_margin = getOrDeclareParameter<double>(node, ns + ".dead_line_margin");
planner_param_.use_pass_judge_line =
getOrDeclareParameter<bool>(node, ns + ".use_pass_judge_line");
planner_param_.state_clear_time = getOrDeclareParameter<double>(node, ns + ".state_clear_time");
planner_param_.hold_stop_margin_distance =
node.declare_parameter<double>(ns + ".hold_stop_margin_distance");
getOrDeclareParameter<double>(node, ns + ".hold_stop_margin_distance");
planner_param_.distance_to_judge_over_stop_line =
node.declare_parameter<double>(ns + ".distance_to_judge_over_stop_line");
getOrDeclareParameter<double>(node, ns + ".distance_to_judge_over_stop_line");
}

void DetectionAreaModuleManager::launchNewModules(
Expand Down

0 comments on commit ddb49ec

Please sign in to comment.