|
17 | 17 | #include <behavior_velocity_planner_common/utilization/util.hpp>
|
18 | 18 | #include <tier4_autoware_utils/ros/parameter.hpp>
|
19 | 19 |
|
| 20 | +#include <algorithm> |
20 | 21 | #include <limits>
|
21 | 22 | #include <memory>
|
22 | 23 | #include <set>
|
@@ -138,10 +139,29 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
|
138 | 139 | getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_with_traffic_light");
|
139 | 140 | cp.occlusion_ignore_behind_predicted_objects =
|
140 | 141 | getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
|
141 |
| - cp.occlusion_do_not_ignore_behind_pedestrians = |
142 |
| - getOrDeclareParameter<bool>(node, ns + ".occlusion.do_not_ignore_behind_pedestrians"); |
143 |
| - cp.occlusion_ignore_velocity_threshold = |
144 |
| - getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_velocity_threshold"); |
| 142 | + |
| 143 | + cp.occlusion_ignore_velocity_thresholds.resize( |
| 144 | + autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN + 1, |
| 145 | + getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_velocity_thresholds.default")); |
| 146 | + const auto get_label = [](const std::string & s) { |
| 147 | + if (s == "CAR") return autoware_auto_perception_msgs::msg::ObjectClassification::CAR; |
| 148 | + if (s == "TRUCK") return autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK; |
| 149 | + if (s == "BUS") return autoware_auto_perception_msgs::msg::ObjectClassification::BUS; |
| 150 | + if (s == "TRAILER") return autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER; |
| 151 | + if (s == "MOTORCYCLE") |
| 152 | + return autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE; |
| 153 | + if (s == "BICYCLE") return autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE; |
| 154 | + if (s == "PEDESTRIAN") |
| 155 | + return autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN; |
| 156 | + return autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; |
| 157 | + }; |
| 158 | + const auto custom_labels = getOrDeclareParameter<std::vector<std::string>>( |
| 159 | + node, ns + ".occlusion.ignore_velocity_thresholds.custom_labels"); |
| 160 | + const auto custom_velocities = getOrDeclareParameter<std::vector<double>>( |
| 161 | + node, ns + ".occlusion.ignore_velocity_thresholds.custom_thresholds"); |
| 162 | + for (auto idx = 0UL; idx < std::min(custom_labels.size(), custom_velocities.size()); ++idx) { |
| 163 | + cp.occlusion_ignore_velocity_thresholds[get_label(custom_labels[idx])] = custom_velocities[idx]; |
| 164 | + } |
145 | 165 | cp.occlusion_extra_objects_size =
|
146 | 166 | getOrDeclareParameter<double>(node, ns + ".occlusion.extra_predicted_objects_size");
|
147 | 167 | }
|
|
0 commit comments