Skip to content

Commit ea4193b

Browse files
committed
Change params to set the ignore vel threshold for each label
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 891dc96 commit ea4193b

File tree

4 files changed

+34
-17
lines changed

4 files changed

+34
-17
lines changed

planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml

+4-2
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,8 @@
8080
occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid
8181
ignore_with_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored
8282
ignore_behind_predicted_objects: true # [-] if true, occlusions behind predicted objects are ignored
83-
do_not_ignore_behind_pedestrians: true # [-] if true, occlusions behind pedestrians are not ignored
84-
min_objects_velocity: 0.5 # [m/s] minimum velocity for a predicted object to be ignored
83+
ignore_velocity_thresholds:
84+
default: 0.5 # [m/s] occlusions are only ignored behind objects with a higher or equal velocity
85+
custom_labels: ["PEDESTRIAN"] # labels for which to define a non-default velocity threshold (see autoware_auto_perception_msgs::msg::ObjectClassification for all the labels)
86+
custom_thresholds: [0.0] # velocities of the custom labels
8587
extra_objects_size: 0.5 # [m] extra size added to the objects when masking the occlusions

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+24-4
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <behavior_velocity_planner_common/utilization/util.hpp>
1818
#include <tier4_autoware_utils/ros/parameter.hpp>
1919

20+
#include <algorithm>
2021
#include <limits>
2122
#include <memory>
2223
#include <set>
@@ -138,10 +139,29 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
138139
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_with_traffic_light");
139140
cp.occlusion_ignore_behind_predicted_objects =
140141
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+
}
145165
cp.occlusion_extra_objects_size =
146166
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_predicted_objects_size");
147167
}

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp

+5-9
Original file line numberDiff line numberDiff line change
@@ -96,16 +96,12 @@ std::vector<lanelet::BasicPolygon2d> calculate_detection_areas(
9696

9797
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects(
9898
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
99-
const double velocity_threshold, const bool skip_pedestrians, const double inflate_size)
99+
const std::vector<double> velocity_thresholds, const double inflate_size)
100100
{
101101
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> selected_objects;
102102
for (const auto & o : objects) {
103-
const auto skip =
104-
(skip_pedestrians &&
105-
o.classification.front().label ==
106-
autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN) ||
107-
o.kinematics.initial_twist_with_covariance.twist.linear.x >= velocity_threshold;
108-
if (!skip) {
103+
const auto vel_threshold = velocity_thresholds[o.classification.front().label];
104+
if (o.kinematics.initial_twist_with_covariance.twist.linear.x >= vel_threshold) {
109105
auto selected_object = o;
110106
selected_object.shape.dimensions.x += inflate_size;
111107
selected_object.shape.dimensions.y += inflate_size;
@@ -161,8 +157,8 @@ bool is_crosswalk_occluded(
161157

162158
if (params.occlusion_ignore_behind_predicted_objects) {
163159
const auto objects = select_and_inflate_objects(
164-
dynamic_objects, params.occlusion_ignore_velocity_threshold,
165-
params.occlusion_do_not_ignore_behind_pedestrians, params.occlusion_extra_objects_size);
160+
dynamic_objects, params.occlusion_ignore_velocity_thresholds,
161+
params.occlusion_extra_objects_size);
166162
clear_occlusions_behind_objects(grid_map, objects);
167163
}
168164
const auto min_nb_of_cells = std::ceil(params.occlusion_min_size / grid_map.getResolution());

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -164,8 +164,7 @@ class CrosswalkModule : public SceneModuleInterface
164164
int occlusion_occupied_min;
165165
bool occlusion_ignore_with_traffic_light;
166166
bool occlusion_ignore_behind_predicted_objects;
167-
bool occlusion_do_not_ignore_behind_pedestrians;
168-
double occlusion_ignore_velocity_threshold;
167+
std::vector<double> occlusion_ignore_velocity_thresholds;
169168
double occlusion_extra_objects_size;
170169
};
171170

0 commit comments

Comments
 (0)