Skip to content

Commit 3c3de30

Browse files
committed
fix: set parameters optionally
1 parent 7287561 commit 3c3de30

File tree

2 files changed

+54
-33
lines changed

2 files changed

+54
-33
lines changed

perception/multi_object_tracker/config/input_channels.param.yaml

+36-24
Original file line numberDiff line numberDiff line change
@@ -3,67 +3,79 @@
33
input_channels:
44
detected_objects:
55
topic: "/perception/object_recognition/detection/objects"
6-
name: "detected_objects"
7-
name_short: "all"
86
expected_frequency: 10.0
7+
optional:
8+
name: "detected_objects"
9+
short_name: "all"
910
# LIDAR - rule-based
1011
lidar_clustering:
1112
topic: "/perception/object_recognition/detection/clustering/objects"
12-
name: "clustering"
13-
name_short: "Lcl"
1413
expected_frequency: 10.0
14+
optional:
15+
name: "clustering"
16+
short_name: "Lcl"
1517
# LIDAR - DNN
1618
lidar_centerpoint:
1719
topic: "/perception/object_recognition/detection/centerpoint/objects"
18-
name: "centerpoint"
19-
name_short: "Lcp"
2020
expected_frequency: 10.0
21+
optional:
22+
name: "centerpoint"
23+
short_name: "Lcp"
2124
lidar_centerpoint_validated:
2225
topic: "/perception/object_recognition/detection/centerpoint/validation/objects"
23-
name: "centerpoint"
24-
name_short: "Lcp"
2526
expected_frequency: 10.0
27+
optional:
28+
name: "centerpoint"
29+
short_name: "Lcp"
2630
lidar_apollo:
2731
topic: "/perception/object_recognition/detection/apollo/objects"
28-
name: "apollo"
29-
name_short: "Lap"
3032
expected_frequency: 10.0
33+
optional:
34+
name: "apollo"
35+
short_name: "Lap"
3136
lidar_apollo_validated:
3237
topic: "/perception/object_recognition/detection/apollo/validation/objects"
33-
name: "apollo"
34-
name_short: "Lap"
3538
expected_frequency: 10.0
39+
optional:
40+
name: "apollo"
41+
short_name: "Lap"
3642
# LIDAR-CAMERA - DNN
3743
lidar_pointpainitng:
3844
topic: "/perception/object_recognition/detection/pointpainting/objects"
39-
name: "pointpainting"
40-
name_short: "Lpp"
4145
expected_frequency: 10.0
46+
optional:
47+
name: "pointpainting"
48+
short_name: "Lpp"
4249
lidar_pointpainting_validated:
4350
topic: "/perception/object_recognition/detection/pointpainting/validation/objects"
44-
name: "pointpainting"
45-
name_short: "Lpp"
4651
expected_frequency: 10.0
52+
optional:
53+
name: "pointpainting"
54+
short_name: "Lpp"
4755
# CAMERA-LIDAR
4856
camera_lidar_fusion:
4957
topic: "/perception/object_recognition/detection/clustering/camera_lidar_fusion/objects"
50-
name: "camera_lidar_fusion"
51-
name_short: "CLf"
5258
expected_frequency: 10.0
59+
optional:
60+
name: "camera_lidar_fusion"
61+
short_name: "CLf"
5362
# CAMERA-LIDAR+TRACKER
5463
detection_by_tracker:
5564
topic: "/perception/object_recognition/detection/detection_by_tracker/objects"
56-
name: "detection_by_tracker"
57-
name_short: "dbT"
5865
expected_frequency: 10.0
66+
optional:
67+
name: "detection_by_tracker"
68+
short_name: "dbT"
5969
# RADAR
6070
radar:
6171
topic: "/sensing/radar/detected_objects"
62-
name: "radar"
63-
name_short: "R"
6472
expected_frequency: 30.0
73+
optional:
74+
name: "radar"
75+
short_name: "R"
6576
radar_far:
6677
topic: "/perception/object_recognition/detection/radar/far_objects"
67-
name: "radar_far"
68-
name_short: "Rf"
6978
expected_frequency: 30.0
79+
optional:
80+
name: "radar_far"
81+
short_name: "Rf"

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+18-9
Original file line numberDiff line numberDiff line change
@@ -100,18 +100,27 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
100100
}
101101

102102
for (const auto & selected_input_channel : selected_input_channels) {
103+
// required parameters, no default value
103104
const std::string input_topic_name =
104105
declare_parameter<std::string>("input_channels." + selected_input_channel + ".topic");
105-
const std::string input_name_long =
106-
declare_parameter<std::string>("input_channels." + selected_input_channel + ".name");
107-
const std::string input_name_short =
108-
declare_parameter<std::string>("input_channels." + selected_input_channel + ".name_short");
109-
const double input_expected_frequency =
110-
declare_parameter<double>("input_channels." + selected_input_channel + ".expected_frequency");
111106
input_topic_names.push_back(input_topic_name);
112-
input_names_long.push_back(input_name_long);
113-
input_names_short.push_back(input_name_short);
114-
input_expected_rates.push_back(input_expected_frequency);
107+
108+
// required parameter, but can set a default value
109+
const double default_expected_rate = 10.0;
110+
const double expected_rate = declare_parameter<double>(
111+
"input_channels." + selected_input_channel + ".expected_rate", default_expected_rate);
112+
input_expected_rates.push_back(expected_rate);
113+
114+
// optional parameters
115+
const std::string default_name = selected_input_channel;
116+
const std::string name_long = declare_parameter<std::string>(
117+
"input_channels." + selected_input_channel + ".optional.name", default_name);
118+
input_names_long.push_back(name_long);
119+
120+
const std::string default_name_short = selected_input_channel.substr(0, 3);
121+
const std::string name_short = declare_parameter<std::string>(
122+
"input_channels." + selected_input_channel + ".optional.short_name", default_name_short);
123+
input_names_short.push_back(name_short);
115124
}
116125

117126
input_channel_size_ = input_topic_names.size();

0 commit comments

Comments
 (0)