@@ -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 >(
@@ -682,8 +687,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
682
687
}();
683
688
684
689
const double max_lat_margin = std::max (
685
- std::max ( p.max_lat_margin_for_stop , p.max_lat_margin_for_cruise ) ,
686
- p. max_lat_margin_for_slow_down );
690
+ { p.max_lat_margin_for_stop , p.max_lat_margin_for_stop_against_unknown ,
691
+ p. max_lat_margin_for_cruise , p. max_lat_margin_for_slow_down } );
687
692
if (max_lat_margin < min_lat_dist_to_traj_poly) {
688
693
RCLCPP_INFO_EXPRESSION (
689
694
get_logger (), enable_debug_info_,
@@ -1174,7 +1179,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1174
1179
if (!isStopObstacle (obstacle.classification .label )) {
1175
1180
return std::nullopt;
1176
1181
}
1177
- if (p.max_lat_margin_for_stop < precise_lat_dist) {
1182
+
1183
+ const double max_lat_margin_for_stop =
1184
+ (obstacle.classification .label == ObjectClassification::UNKNOWN)
1185
+ ? p.max_lat_margin_for_stop_against_unknown
1186
+ : p.max_lat_margin_for_stop ;
1187
+
1188
+ if (precise_lat_dist > std::max (max_lat_margin_for_stop, 1e-3 )) {
1178
1189
return std::nullopt;
1179
1190
}
1180
1191
@@ -1207,7 +1218,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1207
1218
calcObstacleMaxLength (obstacle.shape ) + p.decimate_trajectory_step_length +
1208
1219
std::hypot (
1209
1220
vehicle_info_.vehicle_length_m ,
1210
- vehicle_info_.vehicle_width_m * 0.5 + p. max_lat_margin_for_stop ));
1221
+ vehicle_info_.vehicle_width_m * 0.5 + max_lat_margin_for_stop));
1211
1222
if (collision_points.empty ()) {
1212
1223
RCLCPP_INFO_EXPRESSION (
1213
1224
get_logger (), enable_debug_info_,
@@ -1232,8 +1243,8 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1232
1243
}
1233
1244
1234
1245
// calculate collision points with trajectory with lateral stop margin
1235
- const auto traj_polys_with_lat_margin = createOneStepPolygons (
1236
- traj_points, vehicle_info_, odometry.pose .pose , p. max_lat_margin_for_stop );
1246
+ const auto traj_polys_with_lat_margin =
1247
+ createOneStepPolygons ( traj_points, vehicle_info_, odometry.pose .pose , max_lat_margin_for_stop);
1237
1248
1238
1249
const auto collision_point = polygon_utils::getCollisionPoint (
1239
1250
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);
0 commit comments