Skip to content

Commit b7f9c8c

Browse files
add feature
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 4f97fc0 commit b7f9c8c

File tree

3 files changed

+22
-6
lines changed

3 files changed

+22
-6
lines changed

planning/behavior_velocity_planner/include/scene_module/detection_area/scene.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,8 @@ class DetectionAreaModule : public SceneModuleInterface
5858
double dead_line_margin;
5959
bool use_pass_judge_line;
6060
double state_clear_time;
61+
double distance_to_judge_over_stop_line;
62+
bool suppress_pass_judge_when_stopping;
6163
};
6264

6365
public:
@@ -82,7 +84,8 @@ class DetectionAreaModule : public SceneModuleInterface
8284

8385
bool isOverLine(
8486
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
85-
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const;
87+
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose,
88+
const double margin) const;
8689

8790
bool hasEnoughBrakingDistance(
8891
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const;

planning/behavior_velocity_planner/src/scene_module/detection_area/manager.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,10 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
6969
planner_param_.dead_line_margin = node.declare_parameter(ns + ".dead_line_margin", 5.0);
7070
planner_param_.use_pass_judge_line = node.declare_parameter(ns + ".use_pass_judge_line", false);
7171
planner_param_.state_clear_time = node.declare_parameter(ns + ".state_clear_time", 2.0);
72+
planner_param_.distance_to_judge_over_stop_line =
73+
node.declare_parameter(ns + ".distance_to_judge_over_stop_line", 0.0);
74+
planner_param_.suppress_pass_judge_when_stopping =
75+
node.declare_parameter(ns + ".suppress_pass_judge_when_stopping", false);
7276
}
7377

7478
void DetectionAreaModuleManager::launchNewModules(

planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp

+14-5
Original file line numberDiff line numberDiff line change
@@ -231,7 +231,11 @@ bool DetectionAreaModule::modifyPathVelocity(
231231

232232
// Check state
233233
if (canClearStopState()) {
234-
state_ = State::GO;
234+
if (
235+
!planner_param_.suppress_pass_judge_when_stopping ||
236+
planner_data_->current_velocity->twist.linear.x > 1e-3) {
237+
state_ = State::GO;
238+
}
235239
last_obstacle_found_time_ = {};
236240
return true;
237241
}
@@ -252,7 +256,7 @@ bool DetectionAreaModule::modifyPathVelocity(
252256
const auto & dead_line_pose = dead_line_point->second;
253257
debug_data_.dead_line_poses.push_back(dead_line_pose);
254258

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

270274
// Ignore objects detected after stop_line if not in STOP state
271-
if (state_ != State::STOP && isOverLine(original_path, self_pose, stop_pose)) {
275+
if (
276+
state_ != State::STOP &&
277+
isOverLine(
278+
original_path, self_pose, stop_pose, -planner_param_.distance_to_judge_over_stop_line)) {
272279
return true;
273280
}
274281

@@ -355,15 +362,17 @@ bool DetectionAreaModule::canClearStopState() const
355362

356363
bool DetectionAreaModule::isOverLine(
357364
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
358-
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const
365+
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose,
366+
const double margin) const
359367
{
360368
const PointWithSearchRangeIndex src_point_with_search_range_index =
361369
planning_utils::findFirstNearSearchRangeIndex(path.points, self_pose.position);
362370
const PointWithSearchRangeIndex dst_point_with_search_range_index = {
363371
line_pose.position, planning_utils::getPathIndexRangeIncludeLaneId(path, lane_id_)};
364372

365373
return planning_utils::calcSignedArcLengthWithSearchIndex(
366-
path.points, src_point_with_search_range_index, dst_point_with_search_range_index) < 0;
374+
path.points, src_point_with_search_range_index, dst_point_with_search_range_index) <
375+
margin;
367376
}
368377

369378
bool DetectionAreaModule::hasEnoughBrakingDistance(

0 commit comments

Comments
 (0)