Skip to content

Commit 17f998e

Browse files
author
Anh Nguyen
authored
Merge branch 'main' into chore/rework_param_map_loader
2 parents 45529fb + b574523 commit 17f998e

File tree

18 files changed

+139
-53
lines changed

18 files changed

+139
-53
lines changed

common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.cpp

+87-19
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,12 @@ void TargetObjectTypePanel::setParameters()
6060
modules_ = {
6161
"avoidance",
6262
"avoidance_by_lane_change",
63+
"dynamic_avoidance",
6364
"lane_change",
65+
"start_planner",
66+
"goal_planner",
67+
"crosswalk",
68+
"surround_obstacle_checker",
6469
"obstacle_cruise (inside)",
6570
"obstacle_cruise (outside)",
6671
"obstacle_stop",
@@ -89,15 +94,8 @@ void TargetObjectTypePanel::setParameters()
8994
ParamNameEnableObject param_name;
9095
param_name.node =
9196
"/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner";
92-
param_name.ns = "avoidance.target_object";
93-
param_name.name.emplace("car", "car.is_target");
94-
param_name.name.emplace("truck", "truck.is_target");
95-
param_name.name.emplace("bus", "bus.is_target");
96-
param_name.name.emplace("trailer", "trailer.is_target");
97-
param_name.name.emplace("unknown", "unknown.is_target");
98-
param_name.name.emplace("bicycle", "bicycle.is_target");
99-
param_name.name.emplace("motorcycle", "motorcycle.is_target");
100-
param_name.name.emplace("pedestrian", "pedestrian.is_target");
97+
param_name.ns = "avoidance.target_filtering.target_type";
98+
param_name.name = default_param_name.name;
10199
param_names_.emplace(module, param_name);
102100
}
103101

@@ -107,15 +105,8 @@ void TargetObjectTypePanel::setParameters()
107105
ParamNameEnableObject param_name;
108106
param_name.node =
109107
"/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner";
110-
param_name.ns = "avoidance_by_lane_change.target_object";
111-
param_name.name.emplace("car", "car.is_target");
112-
param_name.name.emplace("truck", "truck.is_target");
113-
param_name.name.emplace("bus", "bus.is_target");
114-
param_name.name.emplace("trailer", "trailer.is_target");
115-
param_name.name.emplace("unknown", "unknown.is_target");
116-
param_name.name.emplace("bicycle", "bicycle.is_target");
117-
param_name.name.emplace("motorcycle", "motorcycle.is_target");
118-
param_name.name.emplace("pedestrian", "pedestrian.is_target");
108+
param_name.ns = "avoidance_by_lane_change.target_filtering.target_type";
109+
param_name.name = default_param_name.name;
119110
param_names_.emplace(module, param_name);
120111
}
121112

@@ -130,6 +121,64 @@ void TargetObjectTypePanel::setParameters()
130121
param_names_.emplace(module, param_name);
131122
}
132123

124+
// start_planner
125+
{
126+
const auto module = "start_planner";
127+
ParamNameEnableObject param_name;
128+
param_name.node =
129+
"/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner";
130+
param_name.ns = "start_planner.path_safety_check.target_filtering.object_types_to_check";
131+
param_name.name.emplace("car", "check_car");
132+
param_name.name.emplace("truck", "check_truck");
133+
param_name.name.emplace("bus", "check_bus");
134+
param_name.name.emplace("trailer", "check_trailer");
135+
param_name.name.emplace("unknown", "check_unknown");
136+
param_name.name.emplace("bicycle", "check_bicycle");
137+
param_name.name.emplace("motorcycle", "check_motorcycle");
138+
param_name.name.emplace("pedestrian", "check_pedestrian");
139+
param_names_.emplace(module, param_name);
140+
}
141+
142+
// goal_planner
143+
{
144+
const auto module = "goal_planner";
145+
ParamNameEnableObject param_name;
146+
param_name.node =
147+
"/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner";
148+
param_name.ns = "goal_planner.path_safety_check.target_filtering.object_types_to_check";
149+
param_name.name.emplace("car", "check_car");
150+
param_name.name.emplace("truck", "check_truck");
151+
param_name.name.emplace("bus", "check_bus");
152+
param_name.name.emplace("trailer", "check_trailer");
153+
param_name.name.emplace("unknown", "check_unknown");
154+
param_name.name.emplace("bicycle", "check_bicycle");
155+
param_name.name.emplace("motorcycle", "check_motorcycle");
156+
param_name.name.emplace("pedestrian", "check_pedestrian");
157+
param_names_.emplace(module, param_name);
158+
}
159+
160+
// dynamic_avoidance
161+
{
162+
const auto module = "dynamic_avoidance";
163+
ParamNameEnableObject param_name;
164+
param_name.node =
165+
"/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner";
166+
param_name.ns = "dynamic_avoidance.target_object";
167+
param_name.name = default_param_name.name;
168+
param_names_.emplace(module, param_name);
169+
}
170+
171+
// crosswalk
172+
{
173+
const auto module = "crosswalk";
174+
ParamNameEnableObject param_name;
175+
param_name.node =
176+
"/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner";
177+
param_name.ns = "crosswalk.object_filtering.target_object";
178+
param_name.name = default_param_name.name;
179+
param_names_.emplace(module, param_name);
180+
}
181+
133182
// obstacle cruise (inside)
134183
{
135184
const auto module = "obstacle_cruise (inside)";
@@ -152,6 +201,24 @@ void TargetObjectTypePanel::setParameters()
152201
param_names_.emplace(module, param_name);
153202
}
154203

204+
// surround_obstacle_check
205+
{
206+
const auto module = "surround_obstacle_checker";
207+
ParamNameEnableObject param_name;
208+
param_name.node =
209+
"/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker";
210+
param_name.ns = "";
211+
param_name.name.emplace("car", "car.enable_check");
212+
param_name.name.emplace("truck", "truck.enable_check");
213+
param_name.name.emplace("bus", "bus.enable_check");
214+
param_name.name.emplace("trailer", "trailer.enable_check");
215+
param_name.name.emplace("unknown", "unknown.enable_check");
216+
param_name.name.emplace("bicycle", "bicycle.enable_check");
217+
param_name.name.emplace("motorcycle", "motorcycle.enable_check");
218+
param_name.name.emplace("pedestrian", "pedestrian.enable_check");
219+
param_names_.emplace(module, param_name);
220+
}
221+
155222
// obstacle stop
156223
{
157224
const auto module = "obstacle_stop";
@@ -225,7 +292,8 @@ void TargetObjectTypePanel::updateMatrix()
225292
continue;
226293
}
227294

228-
std::string param_name = module_params.ns + "." + module_params.name.at(target);
295+
std::string param_name =
296+
(module_params.ns.empty() ? "" : module_params.ns + ".") + module_params.name.at(target);
229297
auto parameter_result = parameters_client->get_parameters({param_name});
230298

231299
if (!parameter_result.empty()) {

control/joy_controller/config/joy_controller.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
/**:
22
ros__parameters:
3-
joy_type: DS4
3+
joy_type: $(var joy_type)
44
update_rate: 10.0
55
accel_ratio: 3.0
66
brake_ratio: 5.0

control/joy_controller/launch/joy_controller.launch.xml

+1-2
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,7 @@
3030
<remap from="service/emergency_stop" to="/api/autoware/set/emergency"/>
3131
<remap from="service/autoware_engage" to="/api/autoware/set/engage"/>
3232

33-
<param from="$(var config_file)"/>
34-
<param name="joy_type" value="$(var joy_type)"/>
33+
<param from="$(var config_file)" allow_substs="true"/>
3534
</node>
3635

3736
<node pkg="joy" exec="joy_node" name="joy_node" output="screen">

control/trajectory_follower_node/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -62,4 +62,5 @@ ament_auto_package(
6262
param
6363
test
6464
launch
65+
config
6566
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
/**:
2+
ros__parameters:
3+
use_external_target_vel: $(var use_external_target_vel)
4+
external_target_vel: $(var external_target_vel)
5+
lateral_deviation: $(var lateral_deviation)

control/trajectory_follower_node/launch/simple_trajectory_follower.launch.xml

+1-3
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,7 @@
55

66
<!-- engage_transition_manager -->
77
<node pkg="trajectory_follower_node" exec="simple_trajectory_follower_exe" name="simple_trajectory_follower" output="screen">
8-
<param name="use_external_target_vel" value="$(var use_external_target_vel)"/>
9-
<param name="external_target_vel" value="$(var external_target_vel)"/>
10-
<param name="lateral_deviation" value="$(var lateral_deviation)"/>
8+
<param from="$(find-pkg-share trajectory_follower_node)/config/simple_trajectory_follower.param.yaml" allow_substs="true"/>
119

1210
<remap from="input/kinematics" to="/localization/kinematic_state"/>
1311
<remap from="input/trajectory" to="/planning/scenario_planning/trajectory"/>

control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
update_rate: 10.0
44
system_emergency_heartbeat_timeout: 0.5
55
use_emergency_handling: false
6-
check_external_emergency_heartbeat: false
6+
check_external_emergency_heartbeat: $(var check_external_emergency_heartbeat)
77
use_start_request: false
88
enable_cmd_limit_filter: true
99
filter_activated_count_threshold: 5

control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml

+1-6
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11
<launch>
22
<arg name="config_file" default="$(find-pkg-share vehicle_cmd_gate)/config/vehicle_cmd_gate.param.yaml"/>
3-
<arg name="use_emergency_handling" default="false"/>
43
<arg name="check_external_emergency_heartbeat" default="true"/>
5-
<arg name="use_start_request" default="false"/>
64

75
<!-- vehicle info -->
86
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>
@@ -44,10 +42,7 @@
4442
<remap from="~/service/external_emergency_stop" to="~/external_emergency_stop"/>
4543
<remap from="~/service/clear_external_emergency_stop" to="~/clear_external_emergency_stop"/>
4644

47-
<param from="$(var config_file)"/>
45+
<param from="$(var config_file)" allow_substs="true"/>
4846
<param from="$(var vehicle_info_param_file)"/>
49-
<param name="use_emergency_handling" value="$(var use_emergency_handling)"/>
50-
<param name="check_external_emergency_heartbeat" value="$(var check_external_emergency_heartbeat)"/>
51-
<param name="use_start_request" value="$(var use_start_request)"/>
5247
</node>
5348
</launch>

control/vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -331,6 +331,9 @@ std::shared_ptr<VehicleCmdGate> generateNode()
331331
{"--ros-args", "--params-file", vehicle_cmd_gate_dir + "/config/vehicle_cmd_gate.param.yaml",
332332
"--ros-args", "--params-file", vehicle_info_util_dir + "/config/vehicle_info.param.yaml"});
333333

334+
node_options.append_parameter_override(
335+
"check_external_emergency_heartbeat", true); // This parameter has to be set when launching.
336+
334337
const auto override = [&](const auto s, const std::vector<double> v) {
335338
node_options.append_parameter_override<std::vector<double>>(s, v);
336339
};

planning/behavior_velocity_intersection_module/config/intersection.param.yaml

+3-1
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,9 @@
5656
duration: 3.0
5757
object_dist_to_stopline: 10.0
5858
ignore_on_amber_traffic_light:
59-
object_expected_deceleration: 2.0
59+
object_expected_deceleration:
60+
car: 2.0
61+
bike: 5.0
6062
ignore_on_red_traffic_light:
6163
object_margin_to_path: 2.0
6264
avoid_collision_by_acceleration:

planning/behavior_velocity_intersection_module/src/manager.cpp

+7-2
Original file line numberDiff line numberDiff line change
@@ -127,9 +127,14 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
127127
ip.collision_detection.yield_on_green_traffic_light.object_dist_to_stopline =
128128
getOrDeclareParameter<double>(
129129
node, ns + ".collision_detection.yield_on_green_traffic_light.object_dist_to_stopline");
130-
ip.collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration =
130+
ip.collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration.car =
131131
getOrDeclareParameter<double>(
132-
node, ns + ".collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration");
132+
node,
133+
ns + ".collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration.car");
134+
ip.collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration.bike =
135+
getOrDeclareParameter<double>(
136+
node,
137+
ns + ".collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration.bike");
133138
ip.collision_detection.ignore_on_red_traffic_light.object_margin_to_path =
134139
getOrDeclareParameter<double>(
135140
node, ns + ".collision_detection.ignore_on_red_traffic_light.object_margin_to_path");

planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,11 @@ class IntersectionModule : public SceneModuleInterface
123123
} yield_on_green_traffic_light;
124124
struct IgnoreOnAmberTrafficLight
125125
{
126-
double object_expected_deceleration;
126+
struct ObjectExpectedDeceleration
127+
{
128+
double car;
129+
double bike;
130+
} object_expected_deceleration;
127131
} ignore_on_amber_traffic_light;
128132
struct IgnoreOnRedTrafficLight
129133
{

planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp

+10-5
Original file line numberDiff line numberDiff line change
@@ -176,18 +176,23 @@ void IntersectionModule::updateObjectInfoManagerCollision(
176176
for (auto & object_info : object_info_manager_.attentionObjects()) {
177177
const auto & predicted_object = object_info->predicted_object();
178178
bool safe_under_traffic_control = false;
179+
const auto label = predicted_object.classification.at(0).label;
180+
const auto expected_deceleration =
181+
(label == autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE ||
182+
label == autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE)
183+
? planner_param_.collision_detection.ignore_on_amber_traffic_light
184+
.object_expected_deceleration.bike
185+
: planner_param_.collision_detection.ignore_on_amber_traffic_light
186+
.object_expected_deceleration.car;
179187
if (
180188
traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED &&
181-
object_info->can_stop_before_stopline(
182-
planner_param_.collision_detection.ignore_on_amber_traffic_light
183-
.object_expected_deceleration)) {
189+
object_info->can_stop_before_stopline(expected_deceleration)) {
184190
safe_under_traffic_control = true;
185191
}
186192
if (
187193
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED &&
188194
object_info->can_stop_before_ego_lane(
189-
planner_param_.collision_detection.ignore_on_amber_traffic_light
190-
.object_expected_deceleration,
195+
expected_deceleration,
191196
planner_param_.collision_detection.ignore_on_red_traffic_light.object_margin_to_path,
192197
ego_lane)) {
193198
safe_under_traffic_control = true;

planning/obstacle_avoidance_planner/launch/obstacle_avoidance_planner.launch.xml

+1-3
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,11 @@
22
<arg name="input_path_topic" default="input/path"/>
33
<arg name="output_path_topic" default="output/path"/>
44
<arg name="enable_debug_info" default="false"/>
5-
<arg name="param_path" default="$(find-pkg-share obstacle_avoidance_planner)/param/obstacle_avoidance_planner.param.yaml"/>
6-
5+
<arg name="param_path" default="$(find-pkg-share obstacle_avoidance_planner)/config/obstacle_avoidance_planner.param.yaml"/>
76
<node pkg="obstacle_avoidance_planner" exec="obstacle_avoidance_planner_node" name="obstacle_avoidance_planner" output="screen">
87
<remap from="~/input/path" to="$(var input_path_topic)"/>
98
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
109
<remap from="~/output/path" to="$(var output_path_topic)"/>
11-
1210
<param from="$(var param_path)"/>
1311
<param name="enable_debug_info" value="$(var enable_debug_info)"/>
1412
</node>

planning/obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml

-2
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
<!-- vehicle info -->
77
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>
88

9-
<arg name="enable_slow_down" default="false"/>
109
<arg name="input_objects" default="/perception/object_recognition/objects"/>
1110
<arg name="input_pointcloud" default="input/pointcloud"/>
1211
<arg name="input_trajectory" default="input/trajectory"/>
@@ -21,7 +20,6 @@
2120
<param from="$(var adaptive_cruise_control_param_path)"/>
2221
<param from="$(var obstacle_stop_planner_param_path)"/>
2322
<param from="$(var vehicle_info_param_file)"/>
24-
<param name="enable_slow_down" value="$(var enable_slow_down)"/>
2523
<!-- remap topic name -->
2624
<remap from="~/output/stop_reason" to="/planning/scenario_planning/status/stop_reason"/>
2725
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>

vehicle/external_cmd_converter/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -15,4 +15,5 @@ rclcpp_components_register_node(external_cmd_converter
1515

1616
ament_auto_package(INSTALL_TO_SHARE
1717
launch
18+
config
1819
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
/**:
2+
ros__parameters:
3+
csv_path_accel_map: $(var csv_path_accel_map)
4+
csv_path_brake_map: $(var csv_path_brake_map)
5+
ref_vel_gain: $(var ref_vel_gain)
6+
timer_rate: $(var timer_rate)
7+
wait_for_first_topic: $(var wait_for_first_topic)
8+
control_command_timeout: $(var control_command_timeout)
9+
emergency_stop_timeout: $(var emergency_stop_timeout)

vehicle/external_cmd_converter/launch/external_cmd_converter.launch.xml

+2-7
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
<?xml version="1.0"?>
22
<launch>
3+
<arg name="external_cmd_converter_param" default="$(find-pkg-share external_cmd_converter)/config/external_cmd_converter.param.yaml"/>
34
<!-- map file -->
45
<arg name="csv_path_accel_map" default="$(find-pkg-share raw_vehicle_cmd_converter)/data/default/accel_map.csv"/>
56
<arg name="csv_path_brake_map" default="$(find-pkg-share raw_vehicle_cmd_converter)/data/default/brake_map.csv"/>
@@ -24,13 +25,7 @@
2425

2526
<!-- node -->
2627
<node pkg="external_cmd_converter" exec="external_cmd_converter_node" name="external_cmd_converter" output="screen">
27-
<param name="csv_path_accel_map" value="$(var csv_path_accel_map)"/>
28-
<param name="csv_path_brake_map" value="$(var csv_path_brake_map)"/>
29-
<param name="ref_vel_gain" value="$(var ref_vel_gain)"/>
30-
<param name="timer_rate" value="$(var timer_rate)"/>
31-
<param name="wait_for_first_topic" value="$(var wait_for_first_topic)"/>
32-
<param name="control_command_timeout" value="$(var control_command_timeout)"/>
33-
<param name="emergency_stop_timeout" value="$(var emergency_stop_timeout)"/>
28+
<param from="$(var external_cmd_converter_param)" allow_substs="true"/>
3429
<remap from="in/external_control_cmd" to="$(var in/external_control_cmd)"/>
3530
<remap from="in/shift_cmd" to="$(var in/shift_cmd)"/>
3631
<remap from="in/emergency_stop" to="$(var in/emergency_stop)"/>

0 commit comments

Comments
 (0)