Skip to content

Commit 8e8b0e8

Browse files
yuki-takagi-66takayuki5168
authored andcommitted
feat(obstacle_cruise_planner)!: ignore to garze against unknwon objects (autowarefoundation#7177) (#1331)
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent bf0e56f commit 8e8b0e8

File tree

3 files changed

+19
-6
lines changed

3 files changed

+19
-6
lines changed

planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,8 @@
8787
obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop
8888

8989
stop:
90-
max_lat_margin: 0.3 # lateral margin between obstacle and trajectory band with ego's width
90+
max_lat_margin: 0.3 # lateral margin between the obstacles except for unknown and ego's footprint
91+
max_lat_margin_against_unknown: -0.3 # lateral margin between the unknown obstacles and ego's footprint
9192
crossing_obstacle:
9293
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]
9394

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -195,6 +195,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
195195
double prediction_resampling_time_horizon;
196196
// max lateral margin
197197
double max_lat_margin_for_stop;
198+
double max_lat_margin_for_stop_against_unknown;
198199
double max_lat_margin_for_cruise;
199200
double max_lat_margin_for_slow_down;
200201
double lat_hysteresis_margin_for_slow_down;

planning/obstacle_cruise_planner/src/node.cpp

+16-5
Original file line numberDiff line numberDiff line change
@@ -247,6 +247,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
247247

248248
max_lat_margin_for_stop =
249249
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");
250252
max_lat_margin_for_cruise =
251253
node.declare_parameter<double>("behavior_determination.cruise.max_lat_margin");
252254
enable_yield = node.declare_parameter<bool>("behavior_determination.cruise.yield.enable_yield");
@@ -311,6 +313,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
311313

312314
tier4_autoware_utils::updateParam<double>(
313315
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);
314319
tier4_autoware_utils::updateParam<double>(
315320
parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise);
316321
tier4_autoware_utils::updateParam<bool>(
@@ -680,8 +685,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
680685
}();
681686

682687
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});
685690
if (max_lat_margin < min_lat_dist_to_traj_poly) {
686691
RCLCPP_INFO_EXPRESSION(
687692
get_logger(), enable_debug_info_,
@@ -1171,7 +1176,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
11711176
if (!isStopObstacle(obstacle.classification.label)) {
11721177
return std::nullopt;
11731178
}
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)) {
11751186
return std::nullopt;
11761187
}
11771188

@@ -1204,7 +1215,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12041215
calcObstacleMaxLength(obstacle.shape) + p.decimate_trajectory_step_length +
12051216
std::hypot(
12061217
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));
12081219
if (collision_points.empty()) {
12091220
RCLCPP_INFO_EXPRESSION(
12101221
get_logger(), enable_debug_info_,
@@ -1230,7 +1241,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12301241

12311242
// calculate collision points with trajectory with lateral stop margin
12321243
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);
12341245

12351246
const auto collision_point = polygon_utils::getCollisionPoint(
12361247
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);

0 commit comments

Comments
 (0)