@@ -247,6 +247,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
247
247
248
248
max_lat_margin_for_stop =
249
249
node.declare_parameter <double >(" behavior_determination.stop.max_lat_margin" );
250
+ max_lat_margin_for_stop_against_unknown =
251
+ node.declare_parameter <double >(" behavior_determination.stop.max_lat_margin_against_unknown" );
250
252
max_lat_margin_for_cruise =
251
253
node.declare_parameter <double >(" behavior_determination.cruise.max_lat_margin" );
252
254
enable_yield = node.declare_parameter <bool >(" behavior_determination.cruise.yield.enable_yield" );
@@ -311,6 +313,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
311
313
312
314
tier4_autoware_utils::updateParam<double >(
313
315
parameters, " behavior_determination.stop.max_lat_margin" , max_lat_margin_for_stop);
316
+ tier4_autoware_utils::updateParam<double >(
317
+ parameters, " behavior_determination.stop.max_lat_margin_against_unknown" ,
318
+ max_lat_margin_for_stop_against_unknown);
314
319
tier4_autoware_utils::updateParam<double >(
315
320
parameters, " behavior_determination.cruise.max_lat_margin" , max_lat_margin_for_cruise);
316
321
tier4_autoware_utils::updateParam<bool >(
@@ -680,8 +685,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
680
685
}();
681
686
682
687
const double max_lat_margin = std::max (
683
- std::max ( p.max_lat_margin_for_stop , p.max_lat_margin_for_cruise ) ,
684
- p. max_lat_margin_for_slow_down );
688
+ { p.max_lat_margin_for_stop , p.max_lat_margin_for_stop_against_unknown ,
689
+ p. max_lat_margin_for_cruise , p. max_lat_margin_for_slow_down } );
685
690
if (max_lat_margin < min_lat_dist_to_traj_poly) {
686
691
RCLCPP_INFO_EXPRESSION (
687
692
get_logger (), enable_debug_info_,
@@ -1171,7 +1176,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1171
1176
if (!isStopObstacle (obstacle.classification .label )) {
1172
1177
return std::nullopt;
1173
1178
}
1174
- if (p.max_lat_margin_for_stop < precise_lat_dist) {
1179
+
1180
+ const double max_lat_margin_for_stop =
1181
+ (obstacle.classification .label == ObjectClassification::UNKNOWN)
1182
+ ? p.max_lat_margin_for_stop_against_unknown
1183
+ : p.max_lat_margin_for_stop ;
1184
+
1185
+ if (precise_lat_dist > std::max (max_lat_margin_for_stop, 1e-3 )) {
1175
1186
return std::nullopt;
1176
1187
}
1177
1188
@@ -1204,7 +1215,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1204
1215
calcObstacleMaxLength (obstacle.shape ) + p.decimate_trajectory_step_length +
1205
1216
std::hypot (
1206
1217
vehicle_info_.vehicle_length_m ,
1207
- vehicle_info_.vehicle_width_m * 0.5 + p. max_lat_margin_for_stop ));
1218
+ vehicle_info_.vehicle_width_m * 0.5 + max_lat_margin_for_stop));
1208
1219
if (collision_points.empty ()) {
1209
1220
RCLCPP_INFO_EXPRESSION (
1210
1221
get_logger (), enable_debug_info_,
@@ -1230,7 +1241,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1230
1241
1231
1242
// calculate collision points with trajectory with lateral stop margin
1232
1243
const auto traj_polys_with_lat_margin = createOneStepPolygons (
1233
- traj_points, vehicle_info_, ego_odom_ptr_->pose .pose , p. max_lat_margin_for_stop );
1244
+ traj_points, vehicle_info_, ego_odom_ptr_->pose .pose , max_lat_margin_for_stop);
1234
1245
1235
1246
const auto collision_point = polygon_utils::getCollisionPoint (
1236
1247
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);
0 commit comments