Skip to content

Commit

Permalink
Merge pull request #911 from tier4/hotfix/pr5047
Browse files Browse the repository at this point in the history
  • Loading branch information
soblin authored Oct 5, 2023
2 parents 1e57ab6 + 257b961 commit 7ed7190
Show file tree
Hide file tree
Showing 6 changed files with 86 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,14 @@
min_vehicle_brake_for_rss: -2.5 # [m/s^2]
max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph
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]
possible_object_bbox: [1.5, 2.5] # [m x m]
ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h
stop_release_margin_time: 1.5 # [s]
temporal_stop_before_attention_area: false

enable_rtc:
intersection: true # 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_to_occlusion: true

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 @@ -115,6 +115,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
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");
ip.occlusion.temporal_stop_before_attention_area =
node.declare_parameter<bool>(ns + ".occlusion.temporal_stop_before_attention_area");
}

void IntersectionModuleManager::launchNewModules(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,11 @@ IntersectionModule::IntersectionModule(
occlusion_stop_state_machine_.setMarginTime(planner_param_.occlusion.stop_release_margin_time);
occlusion_stop_state_machine_.setState(StateMachine::State::GO);
}
{
temporal_stop_before_attention_state_machine_.setMarginTime(
planner_param_.occlusion.before_creep_stop_time);
temporal_stop_before_attention_state_machine_.setState(StateMachine::State::STOP);
}

decision_state_pub_ =
node_.create_publisher<std_msgs::msg::String>("~/debug/intersection/decision_state", 1);
Expand Down Expand Up @@ -476,7 +481,10 @@ void reactRTCApprovalByDecisionResult(
// NOTE: creep_velocity should be inserted first at closest_idx if !rtc_default_approved

if (!rtc_occlusion_approved && planner_param.occlusion.enable) {
const size_t occlusion_peeking_stop_line = decision_result.occlusion_stop_line_idx;
const size_t occlusion_peeking_stop_line =
decision_result.temporal_stop_before_attention_required
? decision_result.first_attention_stop_line_idx
: decision_result.occlusion_stop_line_idx;
if (planner_param.occlusion.enable_creeping) {
const size_t closest_idx = decision_result.closest_idx;
for (size_t i = closest_idx; i < occlusion_peeking_stop_line; i++) {
Expand Down Expand Up @@ -540,7 +548,9 @@ void reactRTCApprovalByDecisionResult(
}
}
if (!rtc_occlusion_approved && planner_param.occlusion.enable) {
const auto stop_line_idx = decision_result.occlusion_stop_line_idx;
const auto stop_line_idx = decision_result.temporal_stop_before_attention_required
? decision_result.first_attention_stop_line_idx
: decision_result.occlusion_stop_line_idx;
planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path);
debug_data->occlusion_stop_wall_pose =
planning_utils::getAheadPose(stop_line_idx, baselink2front, *path);
Expand Down Expand Up @@ -778,7 +788,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
const auto & intersection_stop_lines = intersection_stop_lines_opt.value();
const auto
[closest_idx, stuck_stop_line_idx_opt, default_stop_line_idx_opt,
occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] = intersection_stop_lines;
first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] =
intersection_stop_lines;

const auto & conflicting_area = intersection_lanelets_.value().conflicting_area();
const auto path_lanelets_opt = util::generatePathLanelets(
Expand Down Expand Up @@ -857,12 +868,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
return IntersectionModule::Indecisive{};
}

if (!occlusion_peeking_stop_line_idx_opt) {
if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) {
RCLCPP_DEBUG(logger_, "occlusion stop line is null");
return IntersectionModule::Indecisive{};
}
const auto collision_stop_line_idx =
is_over_default_stop_line ? closest_idx : default_stop_line_idx;
const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value();
const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value();

const auto & attention_lanelets = intersection_lanelets_.value().attention();
Expand Down Expand Up @@ -938,35 +950,63 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
if (
occlusion_stop_state_machine_.getState() == StateMachine::State::STOP ||
ext_occlusion_requested) {
const double dist_stopline = motion_utils::calcSignedArcLength(
const double dist_default_stopline = motion_utils::calcSignedArcLength(
path->points, path->points.at(closest_idx).point.pose.position,
path->points.at(default_stop_line_idx).point.pose.position);
const bool approached_stop_line =
(std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin);
const bool over_stop_line = (dist_stopline < 0.0);
const bool is_stopped = planner_data_->isVehicleStopped();
if (over_stop_line) {
const bool approached_default_stop_line =
(std::fabs(dist_default_stopline) < planner_param_.common.stop_overshoot_margin);
const bool over_default_stop_line = (dist_default_stopline < 0.0);
const bool is_stopped_at_default =
planner_data_->isVehicleStopped(planner_param_.occlusion.before_creep_stop_time);
if (over_default_stop_line) {
before_creep_state_machine_.setState(StateMachine::State::GO);
}
if (before_creep_state_machine_.getState() == StateMachine::State::GO) {
const double dist_first_attention_stopline = motion_utils::calcSignedArcLength(
path->points, path->points.at(closest_idx).point.pose.position,
path->points.at(first_attention_stop_line_idx).point.pose.position);
const bool approached_first_attention_stop_line =
(std::fabs(dist_first_attention_stopline) < planner_param_.common.stop_overshoot_margin);
const bool over_first_attention_stop_line = (dist_first_attention_stopline < 0.0);
const bool is_stopped_at_first_attention =
planner_data_->isVehicleStopped(planner_param_.occlusion.before_creep_stop_time);
if (planner_param_.occlusion.temporal_stop_before_attention_area) {
if (over_first_attention_stop_line) {
temporal_stop_before_attention_state_machine_.setState(StateMachine::State::GO);
}
if (is_stopped_at_first_attention && approached_first_attention_stop_line) {
temporal_stop_before_attention_state_machine_.setState(StateMachine::State::GO);
}
}
const bool temporal_stop_before_attention_required =
planner_param_.occlusion.temporal_stop_before_attention_area &&
temporal_stop_before_attention_state_machine_.getState() == StateMachine::State::STOP;
if (has_collision_with_margin) {
return IntersectionModule::OccludedCollisionStop{
is_occlusion_cleared_with_margin, closest_idx, collision_stop_line_idx,
occlusion_stop_line_idx};
return IntersectionModule::OccludedCollisionStop{is_occlusion_cleared_with_margin,
temporal_stop_before_attention_required,
closest_idx,
collision_stop_line_idx,
first_attention_stop_line_idx,
occlusion_stop_line_idx};
} else {
return IntersectionModule::PeekingTowardOcclusion{
is_occlusion_cleared_with_margin, closest_idx, collision_stop_line_idx,
occlusion_stop_line_idx};
return IntersectionModule::PeekingTowardOcclusion{is_occlusion_cleared_with_margin,
temporal_stop_before_attention_required,
closest_idx,
collision_stop_line_idx,
first_attention_stop_line_idx,
occlusion_stop_line_idx};
}
} else {
if (is_stopped && approached_stop_line) {
if (is_stopped_at_default && approached_default_stop_line) {
// start waiting at the first stop line
before_creep_state_machine_.setStateWithMarginTime(
StateMachine::State::GO, logger_.get_child("occlusion state_machine"), *clock_);
}
const auto occlusion_stop_line = planner_param_.occlusion.temporal_stop_before_attention_area
? first_attention_stop_line_idx
: occlusion_stop_line_idx;
return IntersectionModule::FirstWaitBeforeOcclusion{
is_occlusion_cleared_with_margin, closest_idx, default_stop_line_idx,
occlusion_stop_line_idx};
is_occlusion_cleared_with_margin, closest_idx, default_stop_line_idx, occlusion_stop_line};
}
} else if (has_collision_with_margin) {
return IntersectionModule::NonOccludedCollisionStop{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@ class IntersectionModule : public SceneModuleInterface
std::vector<double> possible_object_bbox;
double ignore_parked_vehicle_speed_threshold;
double stop_release_margin_time;
bool temporal_stop_before_attention_area;
} occlusion;
};

Expand Down Expand Up @@ -136,15 +137,19 @@ class IntersectionModule : public SceneModuleInterface
// NOTE: if intersection_occlusion is disapproved externally through RTC,
// it indicates "is_forcefully_occluded"
bool is_actually_occlusion_cleared{false};
bool temporal_stop_before_attention_required{false};
size_t closest_idx{0};
size_t collision_stop_line_idx{0};
size_t first_attention_stop_line_idx{0};
size_t occlusion_stop_line_idx{0};
};
struct OccludedCollisionStop
{
bool is_actually_occlusion_cleared{false};
bool temporal_stop_before_attention_required{false};
size_t closest_idx{0};
size_t collision_stop_line_idx{0};
size_t first_attention_stop_line_idx{0};
size_t occlusion_stop_line_idx{0};
};
struct Safe
Expand Down Expand Up @@ -217,6 +222,7 @@ class IntersectionModule : public SceneModuleInterface
StateMachine collision_state_machine_; //! for stable collision checking
StateMachine before_creep_state_machine_; //! for two phase stop
StateMachine occlusion_stop_state_machine_;
StateMachine temporal_stop_before_attention_state_machine_;
// NOTE: uuid_ is base member

// for stuck vehicle detection
Expand Down
8 changes: 8 additions & 0 deletions planning/behavior_velocity_intersection_module/src/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -277,6 +277,8 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
}
}
}
const auto first_attention_stop_line_ip = static_cast<size_t>(occlusion_peeking_line_ip_int);
const bool first_attention_stop_line_valid = occlusion_peeking_line_valid;
occlusion_peeking_line_ip_int += std::ceil(peeking_offset / ds);
const auto occlusion_peeking_line_ip = static_cast<size_t>(
std::clamp<int>(occlusion_peeking_line_ip_int, 0, static_cast<int>(path_ip.points.size()) - 1));
Expand Down Expand Up @@ -322,6 +324,7 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
size_t closest_idx{0};
size_t stuck_stop_line{0};
size_t default_stop_line{0};
size_t first_attention_stop_line{0};
size_t occlusion_peeking_stop_line{0};
size_t pass_judge_line{0};
};
Expand All @@ -331,6 +334,7 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
{&closest_idx_ip, &intersection_stop_lines_temp.closest_idx},
{&stuck_stop_line_ip, &intersection_stop_lines_temp.stuck_stop_line},
{&default_stop_line_ip, &intersection_stop_lines_temp.default_stop_line},
{&first_attention_stop_line_ip, &intersection_stop_lines_temp.first_attention_stop_line},
{&occlusion_peeking_line_ip, &intersection_stop_lines_temp.occlusion_peeking_stop_line},
{&pass_judge_line_ip, &intersection_stop_lines_temp.pass_judge_line},
};
Expand Down Expand Up @@ -365,6 +369,10 @@ std::optional<IntersectionStopLines> generateIntersectionStopLines(
if (default_stop_line_valid) {
intersection_stop_lines.default_stop_line = intersection_stop_lines_temp.default_stop_line;
}
if (first_attention_stop_line_valid) {
intersection_stop_lines.first_attention_stop_line =
intersection_stop_lines_temp.first_attention_stop_line;
}
if (occlusion_peeking_line_valid) {
intersection_stop_lines.occlusion_peeking_stop_line =
intersection_stop_lines_temp.occlusion_peeking_stop_line;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,8 +128,10 @@ struct IntersectionStopLines
size_t closest_idx{0};
// NOTE: null if path does not conflict with first_conflicting_area
std::optional<size_t> stuck_stop_line{std::nullopt};
// NOTE: null if path is over map stop_line OR its value is calculated negative area
// NOTE: null if path is over map stop_line OR its value is calculated negative
std::optional<size_t> default_stop_line{std::nullopt};
// NOTE: null if the index is calculated negative
std::optional<size_t> first_attention_stop_line{std::nullopt};
// NOTE: null if footprints do not change from outside to inside of detection area
std::optional<size_t> occlusion_peeking_stop_line{std::nullopt};
// if the value is calculated negative, its value is 0
Expand Down

0 comments on commit 7ed7190

Please sign in to comment.