Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(crosswalk): add option to slowdown at occluded crosswalks #6122

Merged
Changes from 1 commit
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
800457f
Add barebone function to add virtual occluded object
maxime-clem Dec 18, 2023
0f8b6f6
Switching to a simpler slowdown based approach
maxime-clem Jan 16, 2024
397196c
add detection areas at the front&back of the crosswalk
maxime-clem Jan 16, 2024
85179bb
Improve time buffer
maxime-clem Jan 17, 2024
0ff684e
Comment out SVG debug code
maxime-clem Jan 17, 2024
baa4eef
Check that ego did not already pass the crosswalk
maxime-clem Jan 18, 2024
99e688f
Add ROS params
maxime-clem Jan 19, 2024
aecd605
Split hpp/cpp
maxime-clem Jan 19, 2024
67f17b9
Add docstring
maxime-clem Jan 19, 2024
39c5861
Small refactor (point2d,point2d) -> segment2d
maxime-clem Jan 19, 2024
cfe7113
Remove svg code
maxime-clem Jan 19, 2024
18d726b
Refactor timers
maxime-clem Jan 19, 2024
fd7633e
Calculate the detection range based on the distance from the crosswalk
maxime-clem Jan 22, 2024
d736dab
Add option to ignore crosswalk with traffic light + apply max decel/jerk
maxime-clem Jan 22, 2024
830ee7e
Small refactor
maxime-clem Jan 23, 2024
610496c
[WIP] option to ignore occlusions behind predicted objects
maxime-clem Jan 23, 2024
882927c
[DEBUG] launch behavior_velocity_planner in gdb+konsole
maxime-clem Jan 24, 2024
6c2e993
Fix masking behind predicted objects
maxime-clem Jan 24, 2024
65687bd
Revert "[DEBUG] launch behavior_velocity_planner in gdb+konsole"
maxime-clem Jan 24, 2024
0622e47
pre-commit
maxime-clem Jan 24, 2024
891dc96
Refactor and add param to NOT ignore behind pedestrians
maxime-clem Jan 26, 2024
ea4193b
Change params to set the ignore vel threshold for each label
maxime-clem Jan 26, 2024
5a8901b
rename param
maxime-clem Jan 29, 2024
20736ad
fix timer
maxime-clem Feb 2, 2024
b681fe7
add ego lateral offset to detection range
maxime-clem Feb 2, 2024
f48deca
ignore occlusions only if the traffic light is red
maxime-clem Feb 3, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
Change params to set the ignore vel threshold for each label
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
  • Loading branch information
maxime-clem committed Feb 19, 2024
commit ea4193b739efdb81029d53885849e309db0ea1d1
Original file line number Diff line number Diff line change
@@ -80,6 +80,8 @@
occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid
ignore_with_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored
ignore_behind_predicted_objects: true # [-] if true, occlusions behind predicted objects are ignored
do_not_ignore_behind_pedestrians: true # [-] if true, occlusions behind pedestrians are not ignored
min_objects_velocity: 0.5 # [m/s] minimum velocity for a predicted object to be ignored
ignore_velocity_thresholds:
default: 0.5 # [m/s] occlusions are only ignored behind objects with a higher or equal velocity
custom_labels: ["PEDESTRIAN"] # labels for which to define a non-default velocity threshold (see autoware_auto_perception_msgs::msg::ObjectClassification for all the labels)
custom_thresholds: [0.0] # velocities of the custom labels
extra_objects_size: 0.5 # [m] extra size added to the objects when masking the occlusions
28 changes: 24 additions & 4 deletions planning/behavior_velocity_crosswalk_module/src/manager.cpp
Original file line number Diff line number Diff line change
@@ -17,6 +17,7 @@
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <tier4_autoware_utils/ros/parameter.hpp>

#include <algorithm>
#include <limits>
#include <memory>
#include <set>
@@ -138,10 +139,29 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_with_traffic_light");
cp.occlusion_ignore_behind_predicted_objects =
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
cp.occlusion_do_not_ignore_behind_pedestrians =
getOrDeclareParameter<bool>(node, ns + ".occlusion.do_not_ignore_behind_pedestrians");
cp.occlusion_ignore_velocity_threshold =
getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_velocity_threshold");

cp.occlusion_ignore_velocity_thresholds.resize(
autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN + 1,
getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_velocity_thresholds.default"));
const auto get_label = [](const std::string & s) {
if (s == "CAR") return autoware_auto_perception_msgs::msg::ObjectClassification::CAR;
if (s == "TRUCK") return autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK;
if (s == "BUS") return autoware_auto_perception_msgs::msg::ObjectClassification::BUS;
if (s == "TRAILER") return autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER;
if (s == "MOTORCYCLE")
return autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE;
if (s == "BICYCLE") return autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE;
if (s == "PEDESTRIAN")
return autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN;
return autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN;
};
const auto custom_labels = getOrDeclareParameter<std::vector<std::string>>(
node, ns + ".occlusion.ignore_velocity_thresholds.custom_labels");
const auto custom_velocities = getOrDeclareParameter<std::vector<double>>(
node, ns + ".occlusion.ignore_velocity_thresholds.custom_thresholds");
for (auto idx = 0UL; idx < std::min(custom_labels.size(), custom_velocities.size()); ++idx) {
cp.occlusion_ignore_velocity_thresholds[get_label(custom_labels[idx])] = custom_velocities[idx];
}
cp.occlusion_extra_objects_size =
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_predicted_objects_size");
}
Original file line number Diff line number Diff line change
@@ -96,16 +96,12 @@ std::vector<lanelet::BasicPolygon2d> calculate_detection_areas(

std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects(
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
const double velocity_threshold, const bool skip_pedestrians, const double inflate_size)
const std::vector<double> velocity_thresholds, const double inflate_size)
{
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> selected_objects;
for (const auto & o : objects) {
const auto skip =
(skip_pedestrians &&
o.classification.front().label ==
autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN) ||
o.kinematics.initial_twist_with_covariance.twist.linear.x >= velocity_threshold;
if (!skip) {
const auto vel_threshold = velocity_thresholds[o.classification.front().label];
if (o.kinematics.initial_twist_with_covariance.twist.linear.x >= vel_threshold) {
auto selected_object = o;
selected_object.shape.dimensions.x += inflate_size;
selected_object.shape.dimensions.y += inflate_size;
@@ -161,8 +157,8 @@ bool is_crosswalk_occluded(

if (params.occlusion_ignore_behind_predicted_objects) {
const auto objects = select_and_inflate_objects(
dynamic_objects, params.occlusion_ignore_velocity_threshold,
params.occlusion_do_not_ignore_behind_pedestrians, params.occlusion_extra_objects_size);
dynamic_objects, params.occlusion_ignore_velocity_thresholds,
params.occlusion_extra_objects_size);
clear_occlusions_behind_objects(grid_map, objects);
}
const auto min_nb_of_cells = std::ceil(params.occlusion_min_size / grid_map.getResolution());
Original file line number Diff line number Diff line change
@@ -164,8 +164,7 @@ class CrosswalkModule : public SceneModuleInterface
int occlusion_occupied_min;
bool occlusion_ignore_with_traffic_light;
bool occlusion_ignore_behind_predicted_objects;
bool occlusion_do_not_ignore_behind_pedestrians;
double occlusion_ignore_velocity_threshold;
std::vector<double> occlusion_ignore_velocity_thresholds;
double occlusion_extra_objects_size;
};