Skip to content

Commit

Permalink
refactor(avoidance): rebuild parameter structure (autowarefoundation#…
Browse files Browse the repository at this point in the history
…6786)

* refactor(avoidance): unify similar param

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(avoidance): rename misreading params

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(avoidance): update parameter namespace

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(avoidance): use prefix th instead of threshold

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(avoidance): rename params

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(AbLC): rename params

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(avoidance): update yaml

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* refactor(AbLC): update yaml

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

---------

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota authored and karishma1911 committed Jun 3, 2024
1 parent 325b0e0 commit 8648159
Show file tree
Hide file tree
Showing 10 changed files with 268 additions and 289 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
target_object:
car:
execute_num: 2 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 1.0 # [s]
th_moving_speed: 1.0 # [m/s]
th_moving_time: 1.0 # [s]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.3 # [m]
lateral_margin:
Expand All @@ -18,8 +18,8 @@
hard_margin_for_parked_vehicle: 0.0 # [m]
truck:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
th_moving_speed: 1.0 # 3.6km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
lateral_margin:
Expand All @@ -28,8 +28,8 @@
hard_margin_for_parked_vehicle: 0.0 # [m]
bus:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
th_moving_speed: 1.0 # 3.6km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
lateral_margin:
Expand All @@ -38,8 +38,8 @@
hard_margin_for_parked_vehicle: 0.0 # [m]
trailer:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
th_moving_speed: 1.0 # 3.6km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
lateral_margin:
Expand All @@ -48,8 +48,8 @@
hard_margin_for_parked_vehicle: 0.0 # [m]
unknown:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
th_moving_speed: 0.28 # 1.0km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
lateral_margin:
Expand All @@ -58,34 +58,34 @@
hard_margin_for_parked_vehicle: 0.0 # [m]
bicycle:
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
th_moving_speed: 0.28 # 1.0km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
motorcycle:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
th_moving_speed: 1.0 # 3.6km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
pedestrian:
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
th_moving_speed: 0.28 # 1.0km/h
th_moving_time: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
lower_distance_for_polygon_expansion: 0.0 # [m]
upper_distance_for_polygon_expansion: 1.0 # [m]

Expand All @@ -101,11 +101,3 @@
bicycle: false # [-]
motorcycle: false # [-]
pedestrian: false # [-]

constraints:
# lateral constraints
lateral:
velocity: [1.0, 1.38, 11.1] # [m/s]
max_accel_values: [0.5, 0.5, 0.5] # [m/ss]
min_jerk_values: [0.2, 0.2, 0.2] # [m/sss]
max_jerk_values: [1.0, 1.0, 1.0] # [m/sss]
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,8 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
const auto get_object_param = [&](std::string && ns) {
ObjectParameter param{};
param.execute_num = getOrDeclareParameter<int>(*node, ns + "execute_num");
param.moving_speed_threshold =
getOrDeclareParameter<double>(*node, ns + "moving_speed_threshold");
param.moving_time_threshold =
getOrDeclareParameter<double>(*node, ns + "moving_time_threshold");
param.moving_speed_threshold = getOrDeclareParameter<double>(*node, ns + "th_moving_speed");
param.moving_time_threshold = getOrDeclareParameter<double>(*node, ns + "th_moving_time");
param.max_expand_ratio = getOrDeclareParameter<double>(*node, ns + "max_expand_ratio");
param.envelope_buffer_margin =
getOrDeclareParameter<double>(*node, ns + "envelope_buffer_margin");
Expand Down Expand Up @@ -121,14 +119,18 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)

p.object_check_goal_distance =
getOrDeclareParameter<double>(*node, ns + "object_check_goal_distance");
p.object_last_seen_threshold =
getOrDeclareParameter<double>(*node, ns + "max_compensation_time");
}

{
const std::string ns = "avoidance.target_filtering.parked_vehicle.";
p.threshold_distance_object_is_on_center =
getOrDeclareParameter<double>(*node, ns + "threshold_distance_object_is_on_center");
getOrDeclareParameter<double>(*node, ns + "th_offset_from_centerline");
p.object_check_shiftable_ratio =
getOrDeclareParameter<double>(*node, ns + "object_check_shiftable_ratio");
getOrDeclareParameter<double>(*node, ns + "th_shiftable_ratio");
p.object_check_min_road_shoulder_width =
getOrDeclareParameter<double>(*node, ns + "object_check_min_road_shoulder_width");
p.object_last_seen_threshold =
getOrDeclareParameter<double>(*node, ns + "object_last_seen_threshold");
getOrDeclareParameter<double>(*node, ns + "min_road_shoulder_width");
}

{
Expand All @@ -137,9 +139,9 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
p.closest_distance_to_wait_and_see_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "closest_distance_to_wait_and_see");
p.time_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.time_threshold");
getOrDeclareParameter<double>(*node, ns + "condition.th_stopped_time");
p.distance_threshold_for_ambiguous_vehicle =
getOrDeclareParameter<double>(*node, ns + "condition.distance_threshold");
getOrDeclareParameter<double>(*node, ns + "condition.th_moving_distance");
p.object_ignore_section_traffic_light_in_front_distance =
getOrDeclareParameter<double>(*node, ns + "ignore_area.traffic_light.front_distance");
p.object_ignore_section_crosswalk_in_front_distance =
Expand Down
Loading

0 comments on commit 8648159

Please sign in to comment.