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(detection_area)!: suppression of giving up stopping #1631

Merged
merged 1 commit into from
Nov 22, 2024
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 @@ -58,6 +58,8 @@ class DetectionAreaModule : public SceneModuleInterface
double dead_line_margin;
bool use_pass_judge_line;
double state_clear_time;
double distance_to_judge_over_stop_line;
bool suppress_pass_judge_when_stopping;
};

public:
Expand All @@ -82,7 +84,8 @@ class DetectionAreaModule : public SceneModuleInterface

bool isOverLine(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const;
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose,
const double margin) const;

bool hasEnoughBrakingDistance(
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,10 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
planner_param_.dead_line_margin = node.declare_parameter(ns + ".dead_line_margin", 5.0);
planner_param_.use_pass_judge_line = node.declare_parameter(ns + ".use_pass_judge_line", false);
planner_param_.state_clear_time = node.declare_parameter(ns + ".state_clear_time", 2.0);
planner_param_.distance_to_judge_over_stop_line =
node.declare_parameter(ns + ".distance_to_judge_over_stop_line", 0.0);
planner_param_.suppress_pass_judge_when_stopping =
node.declare_parameter(ns + ".suppress_pass_judge_when_stopping", false);
}

void DetectionAreaModuleManager::launchNewModules(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,11 @@ bool DetectionAreaModule::modifyPathVelocity(

// Check state
if (canClearStopState()) {
state_ = State::GO;
if (
!planner_param_.suppress_pass_judge_when_stopping ||
planner_data_->current_velocity->twist.linear.x > 1e-3) {
state_ = State::GO;
}
last_obstacle_found_time_ = {};
return true;
}
Expand All @@ -252,7 +256,7 @@ bool DetectionAreaModule::modifyPathVelocity(
const auto & dead_line_pose = dead_line_point->second;
debug_data_.dead_line_poses.push_back(dead_line_pose);

if (isOverLine(original_path, self_pose, dead_line_pose)) {
if (isOverLine(original_path, self_pose, dead_line_pose, 0.0)) {
RCLCPP_WARN(logger_, "[detection_area] vehicle is over dead line");
return true;
}
Expand All @@ -268,7 +272,10 @@ bool DetectionAreaModule::modifyPathVelocity(
const auto & stop_pose = stop_point->second;

// Ignore objects detected after stop_line if not in STOP state
if (state_ != State::STOP && isOverLine(original_path, self_pose, stop_pose)) {
if (
state_ != State::STOP &&
isOverLine(
original_path, self_pose, stop_pose, -planner_param_.distance_to_judge_over_stop_line)) {
return true;
}

Expand Down Expand Up @@ -355,15 +362,17 @@ bool DetectionAreaModule::canClearStopState() const

bool DetectionAreaModule::isOverLine(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose,
const double margin) const
{
const PointWithSearchRangeIndex src_point_with_search_range_index =
planning_utils::findFirstNearSearchRangeIndex(path.points, self_pose.position);
const PointWithSearchRangeIndex dst_point_with_search_range_index = {
line_pose.position, planning_utils::getPathIndexRangeIncludeLaneId(path, lane_id_)};

return planning_utils::calcSignedArcLengthWithSearchIndex(
path.points, src_point_with_search_range_index, dst_point_with_search_range_index) < 0;
path.points, src_point_with_search_range_index, dst_point_with_search_range_index) <
margin;
}

bool DetectionAreaModule::hasEnoughBrakingDistance(
Expand Down
Loading