@@ -271,6 +271,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
271
271
272
272
max_lat_margin_for_stop =
273
273
node.declare_parameter <double >(" behavior_determination.stop.max_lat_margin" );
274
+ max_lat_margin_for_stop_against_unknown =
275
+ node.declare_parameter <double >(" behavior_determination.stop.max_lat_margin_against_unknown" );
274
276
max_lat_margin_for_cruise =
275
277
node.declare_parameter <double >(" behavior_determination.cruise.max_lat_margin" );
276
278
max_lat_margin_for_slow_down =
@@ -334,6 +336,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
334
336
335
337
tier4_autoware_utils::updateParam<double >(
336
338
parameters, " behavior_determination.stop.max_lat_margin" , max_lat_margin_for_stop);
339
+ tier4_autoware_utils::updateParam<double >(
340
+ parameters, " behavior_determination.stop.max_lat_margin_against_unknown" ,
341
+ max_lat_margin_for_stop_against_unknown);
337
342
tier4_autoware_utils::updateParam<double >(
338
343
parameters, " behavior_determination.cruise.max_lat_margin" , max_lat_margin_for_cruise);
339
344
tier4_autoware_utils::updateParam<double >(
@@ -675,8 +680,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
675
680
}();
676
681
const auto & p = behavior_determination_param_;
677
682
const double max_lat_margin = std::max (
678
- std::max ( p.max_lat_margin_for_stop , p.max_lat_margin_for_cruise ) ,
679
- p. max_lat_margin_for_slow_down );
683
+ { p.max_lat_margin_for_stop , p.max_lat_margin_for_stop_against_unknown ,
684
+ p. max_lat_margin_for_cruise , p. max_lat_margin_for_slow_down } );
680
685
if (max_lat_margin < min_lat_dist_to_traj_poly) {
681
686
RCLCPP_INFO_EXPRESSION (
682
687
get_logger (), enable_debug_info_,
@@ -1009,7 +1014,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1009
1014
if (!isStopObstacle (obstacle.classification .label )) {
1010
1015
return std::nullopt;
1011
1016
}
1012
- if (p.max_lat_margin_for_stop < precise_lat_dist) {
1017
+
1018
+ const double max_lat_margin_for_stop =
1019
+ (obstacle.classification .label == ObjectClassification::UNKNOWN)
1020
+ ? p.max_lat_margin_for_stop_against_unknown
1021
+ : p.max_lat_margin_for_stop ;
1022
+
1023
+ if (precise_lat_dist > std::max (max_lat_margin_for_stop, 1e-3 )) {
1013
1024
return std::nullopt;
1014
1025
}
1015
1026
@@ -1064,7 +1075,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1064
1075
1065
1076
// calculate collision points with trajectory with lateral stop margin
1066
1077
const auto traj_polys_with_lat_margin = createOneStepPolygons (
1067
- traj_points, vehicle_info_, ego_odom_ptr_->pose .pose , p. max_lat_margin_for_stop );
1078
+ traj_points, vehicle_info_, ego_odom_ptr_->pose .pose , max_lat_margin_for_stop);
1068
1079
1069
1080
const auto collision_point = polygon_utils::getCollisionPoint (
1070
1081
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);
0 commit comments