Skip to content

Commit 281ff98

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

File tree

3 files changed

+18
-5
lines changed

3 files changed

+18
-5
lines changed

planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml

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

8787
stop:
88-
max_lat_margin: 0.0 # lateral margin between obstacle and trajectory band with ego's width
88+
max_lat_margin: 0.0 # lateral margin between the obstacles except for unknown and ego's footprint
89+
max_lat_margin_against_unknown: -0.3 # lateral margin between the unknown obstacles and ego's footprint
8990
crossing_obstacle:
9091
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]
9192

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

+15-4
Original file line numberDiff line numberDiff line change
@@ -271,6 +271,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
271271

272272
max_lat_margin_for_stop =
273273
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");
274276
max_lat_margin_for_cruise =
275277
node.declare_parameter<double>("behavior_determination.cruise.max_lat_margin");
276278
max_lat_margin_for_slow_down =
@@ -334,6 +336,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
334336

335337
tier4_autoware_utils::updateParam<double>(
336338
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);
337342
tier4_autoware_utils::updateParam<double>(
338343
parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise);
339344
tier4_autoware_utils::updateParam<double>(
@@ -675,8 +680,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
675680
}();
676681
const auto & p = behavior_determination_param_;
677682
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});
680685
if (max_lat_margin < min_lat_dist_to_traj_poly) {
681686
RCLCPP_INFO_EXPRESSION(
682687
get_logger(), enable_debug_info_,
@@ -1009,7 +1014,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
10091014
if (!isStopObstacle(obstacle.classification.label)) {
10101015
return std::nullopt;
10111016
}
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)) {
10131024
return std::nullopt;
10141025
}
10151026

@@ -1064,7 +1075,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
10641075

10651076
// calculate collision points with trajectory with lateral stop margin
10661077
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);
10681079

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

0 commit comments

Comments
 (0)