@@ -231,7 +231,11 @@ bool DetectionAreaModule::modifyPathVelocity(
231
231
232
232
// Check state
233
233
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
+ }
235
239
last_obstacle_found_time_ = {};
236
240
return true ;
237
241
}
@@ -252,7 +256,7 @@ bool DetectionAreaModule::modifyPathVelocity(
252
256
const auto & dead_line_pose = dead_line_point->second ;
253
257
debug_data_.dead_line_poses .push_back (dead_line_pose);
254
258
255
- if (isOverLine (original_path, self_pose, dead_line_pose)) {
259
+ if (isOverLine (original_path, self_pose, dead_line_pose, 0.0 )) {
256
260
RCLCPP_WARN (logger_, " [detection_area] vehicle is over dead line" );
257
261
return true ;
258
262
}
@@ -268,7 +272,10 @@ bool DetectionAreaModule::modifyPathVelocity(
268
272
const auto & stop_pose = stop_point->second ;
269
273
270
274
// 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 )) {
272
279
return true ;
273
280
}
274
281
@@ -355,15 +362,17 @@ bool DetectionAreaModule::canClearStopState() const
355
362
356
363
bool DetectionAreaModule::isOverLine (
357
364
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
359
367
{
360
368
const PointWithSearchRangeIndex src_point_with_search_range_index =
361
369
planning_utils::findFirstNearSearchRangeIndex (path.points , self_pose.position );
362
370
const PointWithSearchRangeIndex dst_point_with_search_range_index = {
363
371
line_pose.position , planning_utils::getPathIndexRangeIncludeLaneId (path, lane_id_)};
364
372
365
373
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;
367
376
}
368
377
369
378
bool DetectionAreaModule::hasEnoughBrakingDistance (
0 commit comments