Skip to content

Commit 0e5878a

Browse files
yuki-takagi-66takayuki5168
authored and
KhalilSelyan
committed
feat(obstacle_cruise_planner)!: ignore to garze against unknwon objects (#7177)
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent bf9ef9d commit 0e5878a

File tree

3 files changed

+20
-7
lines changed

3 files changed

+20
-7
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
@@ -200,6 +200,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
200200
double prediction_resampling_time_horizon;
201201
// max lateral margin
202202
double max_lat_margin_for_stop;
203+
double max_lat_margin_for_stop_against_unknown;
203204
double max_lat_margin_for_cruise;
204205
double max_lat_margin_for_slow_down;
205206
double lat_hysteresis_margin_for_slow_down;

planning/obstacle_cruise_planner/src/node.cpp

+17-6
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>(
@@ -682,8 +687,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
682687
}();
683688

684689
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});
687692
if (max_lat_margin < min_lat_dist_to_traj_poly) {
688693
RCLCPP_INFO_EXPRESSION(
689694
get_logger(), enable_debug_info_,
@@ -1174,7 +1179,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
11741179
if (!isStopObstacle(obstacle.classification.label)) {
11751180
return std::nullopt;
11761181
}
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)) {
11781189
return std::nullopt;
11791190
}
11801191

@@ -1207,7 +1218,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12071218
calcObstacleMaxLength(obstacle.shape) + p.decimate_trajectory_step_length +
12081219
std::hypot(
12091220
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));
12111222
if (collision_points.empty()) {
12121223
RCLCPP_INFO_EXPRESSION(
12131224
get_logger(), enable_debug_info_,
@@ -1232,8 +1243,8 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12321243
}
12331244

12341245
// 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);
12371248

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

0 commit comments

Comments
 (0)