Skip to content

Commit 61630e6

Browse files
authored
refactor(intersection): use getOrDeclareParameter (#4767)
Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>
1 parent ddb49ec commit 61630e6

File tree

1 file changed

+54
-48
lines changed
  • planning/behavior_velocity_intersection_module/src

1 file changed

+54
-48
lines changed

planning/behavior_velocity_intersection_module/src/manager.cpp

+54-48
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
1818
#include <behavior_velocity_planner_common/utilization/util.hpp>
1919
#include <lanelet2_extension/utility/utilities.hpp>
20+
#include <tier4_autoware_utils/ros/parameter.hpp>
2021

2122
#include <lanelet2_core/primitives/BasicRegulatoryElements.h>
2223

@@ -29,94 +30,99 @@
2930

3031
namespace behavior_velocity_planner
3132
{
33+
using tier4_autoware_utils::getOrDeclareParameter;
34+
3235
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
3336
: SceneModuleManagerInterfaceWithRTC(
3437
node, getModuleName(),
35-
node.declare_parameter<bool>(std::string(getModuleName()) + ".enable_rtc.intersection")),
38+
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
3639
occlusion_rtc_interface_(
3740
&node, "intersection_occlusion",
38-
node.declare_parameter<bool>(
39-
std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
41+
getOrDeclareParameter<bool>(
42+
node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
4043
{
4144
const std::string ns(getModuleName());
4245
auto & ip = intersection_param_;
4346
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
4447
ip.common.attention_area_margin =
45-
node.declare_parameter<double>(ns + ".common.attention_area_margin");
48+
getOrDeclareParameter<double>(node, ns + ".common.attention_area_margin");
4649
ip.common.attention_area_length =
47-
node.declare_parameter<double>(ns + ".common.attention_area_length");
50+
getOrDeclareParameter<double>(node, ns + ".common.attention_area_length");
4851
ip.common.attention_area_angle_thr =
49-
node.declare_parameter<double>(ns + ".common.attention_area_angle_threshold");
50-
ip.common.stop_line_margin = node.declare_parameter<double>(ns + ".common.stop_line_margin");
52+
getOrDeclareParameter<double>(node, ns + ".common.attention_area_angle_threshold");
53+
ip.common.stop_line_margin = getOrDeclareParameter<double>(node, ns + ".common.stop_line_margin");
5154
ip.common.intersection_velocity =
52-
node.declare_parameter<double>(ns + ".common.intersection_velocity");
55+
getOrDeclareParameter<double>(node, ns + ".common.intersection_velocity");
5356
ip.common.intersection_max_acc =
54-
node.declare_parameter<double>(ns + ".common.intersection_max_accel");
57+
getOrDeclareParameter<double>(node, ns + ".common.intersection_max_accel");
5558
ip.common.stop_overshoot_margin =
56-
node.declare_parameter<double>(ns + ".common.stop_overshoot_margin");
59+
getOrDeclareParameter<double>(node, ns + ".common.stop_overshoot_margin");
5760
ip.common.use_intersection_area =
58-
node.declare_parameter<bool>(ns + ".common.use_intersection_area");
61+
getOrDeclareParameter<bool>(node, ns + ".common.use_intersection_area");
5962
ip.common.path_interpolation_ds =
60-
node.declare_parameter<double>(ns + ".common.path_interpolation_ds");
63+
getOrDeclareParameter<double>(node, ns + ".common.path_interpolation_ds");
6164
ip.common.consider_wrong_direction_vehicle =
62-
node.declare_parameter<bool>(ns + ".common.consider_wrong_direction_vehicle");
65+
getOrDeclareParameter<bool>(node, ns + ".common.consider_wrong_direction_vehicle");
6366

6467
ip.stuck_vehicle.use_stuck_stopline =
65-
node.declare_parameter<bool>(ns + ".stuck_vehicle.use_stuck_stopline");
68+
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.use_stuck_stopline");
6669
ip.stuck_vehicle.stuck_vehicle_detect_dist =
67-
node.declare_parameter<double>(ns + ".stuck_vehicle.stuck_vehicle_detect_dist");
70+
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_detect_dist");
6871
ip.stuck_vehicle.stuck_vehicle_ignore_dist =
69-
node.declare_parameter<double>(ns + ".stuck_vehicle.stuck_vehicle_ignore_dist") +
72+
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_ignore_dist") +
7073
vehicle_info.max_longitudinal_offset_m;
7174
ip.stuck_vehicle.stuck_vehicle_vel_thr =
72-
node.declare_parameter<double>(ns + ".stuck_vehicle.stuck_vehicle_vel_thr");
75+
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.stuck_vehicle_vel_thr");
7376
/*
7477
ip.stuck_vehicle.assumed_front_car_decel =
75-
node.declare_parameter<double>(ns + ".stuck_vehicle.assumed_front_car_decel");
78+
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.assumed_front_car_decel");
7679
ip.stuck_vehicle.enable_front_car_decel_prediction =
77-
node.declare_parameter<bool>(ns + ".stuck_vehicle.enable_front_car_decel_prediction");
80+
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.enable_front_car_decel_prediction");
7881
*/
7982
ip.stuck_vehicle.timeout_private_area =
80-
node.declare_parameter<double>(ns + ".stuck_vehicle.timeout_private_area");
83+
getOrDeclareParameter<double>(node, ns + ".stuck_vehicle.timeout_private_area");
8184

8285
ip.collision_detection.min_predicted_path_confidence =
83-
node.declare_parameter<double>(ns + ".collision_detection.min_predicted_path_confidence");
86+
getOrDeclareParameter<double>(node, ns + ".collision_detection.min_predicted_path_confidence");
8487
ip.collision_detection.minimum_ego_predicted_velocity =
85-
node.declare_parameter<double>(ns + ".collision_detection.minimum_ego_predicted_velocity");
88+
getOrDeclareParameter<double>(node, ns + ".collision_detection.minimum_ego_predicted_velocity");
8689
ip.collision_detection.state_transit_margin_time =
87-
node.declare_parameter<double>(ns + ".collision_detection.state_transit_margin_time");
88-
ip.collision_detection.normal.collision_start_margin_time =
89-
node.declare_parameter<double>(ns + ".collision_detection.normal.collision_start_margin_time");
90-
ip.collision_detection.normal.collision_end_margin_time =
91-
node.declare_parameter<double>(ns + ".collision_detection.normal.collision_end_margin_time");
92-
ip.collision_detection.relaxed.collision_start_margin_time =
93-
node.declare_parameter<double>(ns + ".collision_detection.relaxed.collision_start_margin_time");
94-
ip.collision_detection.relaxed.collision_end_margin_time =
95-
node.declare_parameter<double>(ns + ".collision_detection.relaxed.collision_end_margin_time");
90+
getOrDeclareParameter<double>(node, ns + ".collision_detection.state_transit_margin_time");
91+
ip.collision_detection.normal.collision_start_margin_time = getOrDeclareParameter<double>(
92+
node, ns + ".collision_detection.normal.collision_start_margin_time");
93+
ip.collision_detection.normal.collision_end_margin_time = getOrDeclareParameter<double>(
94+
node, ns + ".collision_detection.normal.collision_end_margin_time");
95+
ip.collision_detection.relaxed.collision_start_margin_time = getOrDeclareParameter<double>(
96+
node, ns + ".collision_detection.relaxed.collision_start_margin_time");
97+
ip.collision_detection.relaxed.collision_end_margin_time = getOrDeclareParameter<double>(
98+
node, ns + ".collision_detection.relaxed.collision_end_margin_time");
9699
ip.collision_detection.keep_detection_vel_thr =
97-
node.declare_parameter<double>(ns + ".collision_detection.keep_detection_vel_thr");
100+
getOrDeclareParameter<double>(node, ns + ".collision_detection.keep_detection_vel_thr");
98101

99-
ip.occlusion.enable = node.declare_parameter<bool>(ns + ".occlusion.enable");
102+
ip.occlusion.enable = getOrDeclareParameter<bool>(node, ns + ".occlusion.enable");
100103
ip.occlusion.occlusion_attention_area_length =
101-
node.declare_parameter<double>(ns + ".occlusion.occlusion_attention_area_length");
102-
ip.occlusion.enable_creeping = node.declare_parameter<bool>(ns + ".occlusion.enable_creeping");
104+
getOrDeclareParameter<double>(node, ns + ".occlusion.occlusion_attention_area_length");
105+
ip.occlusion.enable_creeping =
106+
getOrDeclareParameter<bool>(node, ns + ".occlusion.enable_creeping");
103107
ip.occlusion.occlusion_creep_velocity =
104-
node.declare_parameter<double>(ns + ".occlusion.occlusion_creep_velocity");
105-
ip.occlusion.peeking_offset = node.declare_parameter<double>(ns + ".occlusion.peeking_offset");
106-
ip.occlusion.free_space_max = node.declare_parameter<int>(ns + ".occlusion.free_space_max");
107-
ip.occlusion.occupied_min = node.declare_parameter<int>(ns + ".occlusion.occupied_min");
108-
ip.occlusion.do_dp = node.declare_parameter<bool>(ns + ".occlusion.do_dp");
108+
getOrDeclareParameter<double>(node, ns + ".occlusion.occlusion_creep_velocity");
109+
ip.occlusion.peeking_offset =
110+
getOrDeclareParameter<double>(node, ns + ".occlusion.peeking_offset");
111+
ip.occlusion.free_space_max = getOrDeclareParameter<int>(node, ns + ".occlusion.free_space_max");
112+
ip.occlusion.occupied_min = getOrDeclareParameter<int>(node, ns + ".occlusion.occupied_min");
113+
ip.occlusion.do_dp = getOrDeclareParameter<bool>(node, ns + ".occlusion.do_dp");
109114
ip.occlusion.before_creep_stop_time =
110-
node.declare_parameter<double>(ns + ".occlusion.before_creep_stop_time");
115+
getOrDeclareParameter<double>(node, ns + ".occlusion.before_creep_stop_time");
111116
ip.occlusion.min_vehicle_brake_for_rss =
112-
node.declare_parameter<double>(ns + ".occlusion.min_vehicle_brake_for_rss");
117+
getOrDeclareParameter<double>(node, ns + ".occlusion.min_vehicle_brake_for_rss");
113118
ip.occlusion.max_vehicle_velocity_for_rss =
114-
node.declare_parameter<double>(ns + ".occlusion.max_vehicle_velocity_for_rss");
115-
ip.occlusion.denoise_kernel = node.declare_parameter<double>(ns + ".occlusion.denoise_kernel");
119+
getOrDeclareParameter<double>(node, ns + ".occlusion.max_vehicle_velocity_for_rss");
120+
ip.occlusion.denoise_kernel =
121+
getOrDeclareParameter<double>(node, ns + ".occlusion.denoise_kernel");
116122
ip.occlusion.possible_object_bbox =
117-
node.declare_parameter<std::vector<double>>(ns + ".occlusion.possible_object_bbox");
123+
getOrDeclareParameter<std::vector<double>>(node, ns + ".occlusion.possible_object_bbox");
118124
ip.occlusion.ignore_parked_vehicle_speed_threshold =
119-
node.declare_parameter<double>(ns + ".occlusion.ignore_parked_vehicle_speed_threshold");
125+
getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_parked_vehicle_speed_threshold");
120126
}
121127

122128
void IntersectionModuleManager::launchNewModules(
@@ -263,10 +269,10 @@ MergeFromPrivateModuleManager::MergeFromPrivateModuleManager(rclcpp::Node & node
263269
{
264270
const std::string ns(getModuleName());
265271
auto & mp = merge_from_private_area_param_;
266-
mp.stop_duration_sec = node.declare_parameter<double>(ns + ".stop_duration_sec");
272+
mp.stop_duration_sec = getOrDeclareParameter<double>(node, ns + ".stop_duration_sec");
267273
mp.attention_area_length =
268274
node.get_parameter("intersection.common.attention_area_length").as_double();
269-
mp.stop_line_margin = node.declare_parameter<double>(ns + ".stop_line_margin");
275+
mp.stop_line_margin = getOrDeclareParameter<double>(node, ns + ".stop_line_margin");
270276
mp.path_interpolation_ds =
271277
node.get_parameter("intersection.common.path_interpolation_ds").as_double();
272278
}

0 commit comments

Comments
 (0)