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(intersection): suppress pass judge sudden stop #963

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
use_intersection_area: false
path_interpolation_ds: 0.1 # [m]
consider_wrong_direction_vehicle: false
disable_pass_judge_sudden_stop: false
enable_peeking_pass_judge: false
stuck_vehicle:
turn_direction:
left: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,10 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
getOrDeclareParameter<double>(node, ns + ".common.path_interpolation_ds");
ip.common.consider_wrong_direction_vehicle =
getOrDeclareParameter<bool>(node, ns + ".common.consider_wrong_direction_vehicle");
ip.common.disable_pass_judge_sudden_stop =
getOrDeclareParameter<bool>(node, ns + ".common.disable_pass_judge_sudden_stop");
ip.common.enable_peeking_pass_judge =
getOrDeclareParameter<bool>(node, ns + ".common.enable_peeking_pass_judge");

ip.stuck_vehicle.turn_direction.left =
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.turn_direction.left");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -978,7 +978,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
const auto intersection_stop_lines_opt = util::generateIntersectionStopLines(
first_conflicting_area, dummy_first_attention_area, planner_data_, interpolated_path_info,
planner_param_.stuck_vehicle.use_stuck_stopline, planner_param_.common.stop_line_margin,
peeking_offset, path);
planner_param_.common.enable_peeking_pass_judge, peeking_offset, path);
if (!intersection_stop_lines_opt) {
return IntersectionModule::Indecisive{"failed to generate intersection_stop_lines"};
}
Expand Down Expand Up @@ -1085,7 +1085,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
logger_, "is_over_default_stop_line && !is_over_pass_judge_line && keep_detection");
// do nothing
} else if (
(was_safe && is_over_default_stop_line && is_over_pass_judge_line && is_go_out_) ||
(was_safe &&
(is_over_default_stop_line || planner_param_.common.disable_pass_judge_sudden_stop) &&
is_over_pass_judge_line && is_go_out_) ||
is_permanent_go_) {
// is_go_out_: previous RTC approval
// activated_: current RTC approval
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ class IntersectionModule : public SceneModuleInterface
double stop_overshoot_margin; //! overshoot margin for stuck, collision detection
bool use_intersection_area;
bool consider_wrong_direction_vehicle;
bool disable_pass_judge_sudden_stop;
bool enable_peeking_pass_judge;
double path_interpolation_ds;
} common;
struct StuckVehicle
Expand Down
6 changes: 3 additions & 3 deletions planning/behavior_velocity_intersection_module/src/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,7 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
const lanelet::CompoundPolygon3d & first_detection_area,
const std::shared_ptr<const PlannerData> & planner_data,
const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline,
const double stop_line_margin, const double peeking_offset,
const double stop_line_margin, const bool enable_peeking_pass_judge, const double peeking_offset,
autoware_auto_planning_msgs::msg::PathWithLaneId * original_path)
{
const auto & path_ip = interpolated_path_info.path;
Expand Down Expand Up @@ -416,8 +416,8 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
intersection_stop_lines_temp.default_stop_line;
}
if (
intersection_stop_lines_temp.occlusion_peeking_stop_line >
intersection_stop_lines_temp.pass_judge_line) {
enable_peeking_pass_judge && (intersection_stop_lines_temp.occlusion_peeking_stop_line >
intersection_stop_lines_temp.pass_judge_line)) {
intersection_stop_lines_temp.pass_judge_line =
intersection_stop_lines_temp.occlusion_peeking_stop_line;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
const lanelet::CompoundPolygon3d & first_detection_area,
const std::shared_ptr<const PlannerData> & planner_data,
const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline,
const double stop_line_margin, const double peeking_offset,
const double stop_line_margin, const bool enable_peeking_pass_judge, const double peeking_offset,
autoware_auto_planning_msgs::msg::PathWithLaneId * original_path);

std::optional<size_t> getFirstPointInsidePolygon(
Expand Down
Loading