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

fix: suppress unintended permits at intersections #829

Merged
merged 4 commits into from
Sep 13, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
Prev Previous commit
Next Next commit
feat(intersection): suppress intersection occlusion chattering (autow…
…arefoundation#4788)

Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
  • Loading branch information
soblin committed Sep 12, 2023
commit c3d91eb6719d943812313258fb45bec70de965f5
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
denoise_kernel: 1.0 # [m]
possible_object_bbox: [1.0, 2.0] # [m x m]
ignore_parked_vehicle_speed_threshold: 0.333 # == 1.2km/h
stop_release_margin_time: 1.0 # [s]

enable_rtc: # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
intersection: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
node.declare_parameter<std::vector<double>>(ns + ".occlusion.possible_object_bbox");
ip.occlusion.ignore_parked_vehicle_speed_threshold =
node.declare_parameter<double>(ns + ".occlusion.ignore_parked_vehicle_speed_threshold");
ip.occlusion.stop_release_margin_time =
node.declare_parameter<double>(ns + ".occlusion.stop_release_margin_time");
}

void IntersectionModuleManager::launchNewModules(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,15 @@ IntersectionModule::IntersectionModule(
turn_direction_ = assigned_lanelet.attributeOr("turn_direction", "else");
collision_state_machine_.setMarginTime(
planner_param_.collision_detection.state_transit_margin_time);
before_creep_state_machine_.setMarginTime(planner_param_.occlusion.before_creep_stop_time);
before_creep_state_machine_.setState(StateMachine::State::STOP);
stuck_private_area_timeout_.setMarginTime(planner_param_.stuck_vehicle.timeout_private_area);
stuck_private_area_timeout_.setState(StateMachine::State::STOP);
{
before_creep_state_machine_.setMarginTime(planner_param_.occlusion.before_creep_stop_time);
before_creep_state_machine_.setState(StateMachine::State::STOP);
}
{
occlusion_stop_state_machine_.setMarginTime(planner_param_.occlusion.stop_release_margin_time);
occlusion_stop_state_machine_.setState(StateMachine::State::GO);
}

decision_state_pub_ =
node_.create_publisher<std_msgs::msg::String>("~/debug/intersection/decision_state", 1);
}
Expand Down Expand Up @@ -646,6 +651,35 @@ void reactRTCApproval(
return;
}

static std::string formatDecisionResult(const IntersectionModule::DecisionResult & decision_result)
{
if (std::holds_alternative<IntersectionModule::Indecisive>(decision_result)) {
return "Indecisive";
}
if (std::holds_alternative<IntersectionModule::Safe>(decision_result)) {
return "Safe";
}
if (std::holds_alternative<IntersectionModule::StuckStop>(decision_result)) {
return "StuckStop";
}
if (std::holds_alternative<IntersectionModule::NonOccludedCollisionStop>(decision_result)) {
return "NonOccludedCollisionStop";
}
if (std::holds_alternative<IntersectionModule::FirstWaitBeforeOcclusion>(decision_result)) {
return "FirstWaitBeforeOcclusion";
}
if (std::holds_alternative<IntersectionModule::PeekingTowardOcclusion>(decision_result)) {
return "PeekingTowardOcclusion";
}
if (std::holds_alternative<IntersectionModule::OccludedCollisionStop>(decision_result)) {
return "OccludedCollisionStop";
}
if (std::holds_alternative<IntersectionModule::TrafficLightArrowSolidOn>(decision_result)) {
return "TrafficLightArrowSolidOn";
}
return "";
}

bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
{
debug_data_ = util::DebugData();
Expand All @@ -657,31 +691,8 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
// calculate the
const auto decision_result = modifyPathVelocityDetail(path, stop_reason);

std::string decision_type = "intersection" + std::to_string(module_id_) + " : ";
if (std::get_if<IntersectionModule::Indecisive>(&decision_result)) {
decision_type += "Indecisive";
}
if (std::get_if<IntersectionModule::StuckStop>(&decision_result)) {
decision_type += "StuckStop";
}
if (std::get_if<IntersectionModule::NonOccludedCollisionStop>(&decision_result)) {
decision_type += "NonOccludedCollisionStop";
}
if (std::get_if<IntersectionModule::FirstWaitBeforeOcclusion>(&decision_result)) {
decision_type += "FirstWaitBeforeOcclusion";
}
if (std::get_if<IntersectionModule::PeekingTowardOcclusion>(&decision_result)) {
decision_type += "PeekingTowardOcclusion";
}
if (std::get_if<IntersectionModule::OccludedCollisionStop>(&decision_result)) {
decision_type += "OccludedCollisionStop";
}
if (std::get_if<IntersectionModule::Safe>(&decision_result)) {
decision_type += "Safe";
}
if (std::get_if<IntersectionModule::TrafficLightArrowSolidOn>(&decision_result)) {
decision_type += "TrafficLightArrowSolidOn";
}
const std::string decision_type =
"intersection" + std::to_string(module_id_) + " : " + formatDecisionResult(decision_result);
std_msgs::msg::String decision_result_msg;
decision_result_msg.data = decision_type;
decision_state_pub_->publish(decision_result_msg);
Expand Down Expand Up @@ -897,10 +908,15 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
first_attention_area.value(), interpolated_path_info,
occlusion_attention_divisions_.value(), parked_attention_objects, occlusion_dist_thr)
: true;
occlusion_stop_state_machine_.setStateWithMarginTime(
is_occlusion_cleared ? StateMachine::State::GO : StateMachine::STOP,
logger_.get_child("occlusion_stop"), *clock_);

// check safety
const bool ext_occlusion_requested = (is_occlusion_cleared && !occlusion_activated_);
if (!is_occlusion_cleared || ext_occlusion_requested) {
if (
occlusion_stop_state_machine_.getState() == StateMachine::State::STOP ||
ext_occlusion_requested) {
const double dist_stopline = motion_utils::calcSignedArcLength(
path->points, path->points.at(closest_idx).point.pose.position,
path->points.at(default_stop_line_idx).point.pose.position);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ class IntersectionModule : public SceneModuleInterface
double denoise_kernel;
std::vector<double> possible_object_bbox;
double ignore_parked_vehicle_speed_threshold;
double stop_release_margin_time;
} occlusion;
};

Expand Down Expand Up @@ -221,6 +222,7 @@ class IntersectionModule : public SceneModuleInterface
// OcclusionState prev_occlusion_state_ = OcclusionState::NONE;
StateMachine collision_state_machine_; //! for stable collision checking
StateMachine before_creep_state_machine_; //! for two phase stop
StateMachine occlusion_stop_state_machine_;
// NOTE: uuid_ is base member

// for stuck vehicle detection
Expand Down