Skip to content

Commit

Permalink
fix: set parameters optionally
Browse files Browse the repository at this point in the history
  • Loading branch information
technolojin committed May 8, 2024
1 parent e9464be commit fadf553
Show file tree
Hide file tree
Showing 2 changed files with 54 additions and 33 deletions.
60 changes: 36 additions & 24 deletions perception/multi_object_tracker/config/input_channels.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,67 +3,79 @@
input_channels:
detected_objects:
topic: "/perception/object_recognition/detection/objects"
name: "detected_objects"
name_short: "all"
expected_frequency: 10.0
optional:
name: "detected_objects"
short_name: "all"
# LIDAR - rule-based
lidar_clustering:
topic: "/perception/object_recognition/detection/clustering/objects"
name: "clustering"
name_short: "Lcl"
expected_frequency: 10.0
optional:
name: "clustering"
short_name: "Lcl"
# LIDAR - DNN
lidar_centerpoint:
topic: "/perception/object_recognition/detection/centerpoint/objects"
name: "centerpoint"
name_short: "Lcp"
expected_frequency: 10.0
optional:
name: "centerpoint"
short_name: "Lcp"
lidar_centerpoint_validated:
topic: "/perception/object_recognition/detection/centerpoint/validation/objects"
name: "centerpoint"
name_short: "Lcp"
expected_frequency: 10.0
optional:
name: "centerpoint"
short_name: "Lcp"
lidar_apollo:
topic: "/perception/object_recognition/detection/apollo/objects"
name: "apollo"
name_short: "Lap"
expected_frequency: 10.0
optional:
name: "apollo"
short_name: "Lap"
lidar_apollo_validated:
topic: "/perception/object_recognition/detection/apollo/validation/objects"
name: "apollo"
name_short: "Lap"
expected_frequency: 10.0
optional:
name: "apollo"
short_name: "Lap"
# LIDAR-CAMERA - DNN
lidar_pointpainitng:
topic: "/perception/object_recognition/detection/pointpainting/objects"
name: "pointpainting"
name_short: "Lpp"
expected_frequency: 10.0
optional:
name: "pointpainting"
short_name: "Lpp"
lidar_pointpainting_validated:
topic: "/perception/object_recognition/detection/pointpainting/validation/objects"
name: "pointpainting"
name_short: "Lpp"
expected_frequency: 10.0
optional:
name: "pointpainting"
short_name: "Lpp"
# CAMERA-LIDAR
camera_lidar_fusion:
topic: "/perception/object_recognition/detection/clustering/camera_lidar_fusion/objects"
name: "camera_lidar_fusion"
name_short: "CLf"
expected_frequency: 10.0
optional:
name: "camera_lidar_fusion"
short_name: "CLf"
# CAMERA-LIDAR+TRACKER
detection_by_tracker:
topic: "/perception/object_recognition/detection/detection_by_tracker/objects"
name: "detection_by_tracker"
name_short: "dbT"
expected_frequency: 10.0
optional:
name: "detection_by_tracker"
short_name: "dbT"
# RADAR
radar:
topic: "/sensing/radar/detected_objects"
name: "radar"
name_short: "R"
expected_frequency: 30.0
optional:
name: "radar"
short_name: "R"
radar_far:
topic: "/perception/object_recognition/detection/radar/far_objects"
name: "radar_far"
name_short: "Rf"
expected_frequency: 30.0
optional:
name: "radar_far"
short_name: "Rf"
27 changes: 18 additions & 9 deletions perception/multi_object_tracker/src/multi_object_tracker_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,18 +100,27 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
}

for (const auto & selected_input_channel : selected_input_channels) {
// required parameters, no default value
const std::string input_topic_name =
declare_parameter<std::string>("input_channels." + selected_input_channel + ".topic");
const std::string input_name_long =
declare_parameter<std::string>("input_channels." + selected_input_channel + ".name");
const std::string input_name_short =
declare_parameter<std::string>("input_channels." + selected_input_channel + ".name_short");
const double input_expected_frequency =
declare_parameter<double>("input_channels." + selected_input_channel + ".expected_frequency");
input_topic_names.push_back(input_topic_name);
input_names_long.push_back(input_name_long);
input_names_short.push_back(input_name_short);
input_expected_rates.push_back(input_expected_frequency);

// required parameter, but can set a default value
const double default_expected_rate = 10.0;
const double expected_rate = declare_parameter<double>(
"input_channels." + selected_input_channel + ".expected_rate", default_expected_rate);
input_expected_rates.push_back(expected_rate);

// optional parameters
const std::string default_name = selected_input_channel;
const std::string name_long = declare_parameter<std::string>(
"input_channels." + selected_input_channel + ".optional.name", default_name);
input_names_long.push_back(name_long);

const std::string default_name_short = selected_input_channel.substr(0, 3);
const std::string name_short = declare_parameter<std::string>(
"input_channels." + selected_input_channel + ".optional.short_name", default_name_short);
input_names_short.push_back(name_short);
}

input_channel_size_ = input_topic_names.size();
Expand Down

0 comments on commit fadf553

Please sign in to comment.