Skip to content

Commit ecb33b2

Browse files
authored
Merge pull request #1458 from tier4/hotfix/v0.29.0/cherry-pick-avoidance
perf(static_obstacle_avoidance): improve logic to reduce computational cost (autowarefoundation#8432)
2 parents 91d0e85 + a4563aa commit ecb33b2

File tree

3 files changed

+15
-23
lines changed
  • planning/behavior_path_planner

3 files changed

+15
-23
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

+13-15
Original file line numberDiff line numberDiff line change
@@ -61,32 +61,30 @@ bool isCentroidWithinLanelet(
6161
const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold)
6262
{
6363
const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose;
64-
const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position);
65-
if (
66-
std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) >
67-
yaw_threshold) {
64+
if (!boost::geometry::within(
65+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pose.position))
66+
.basicPoint(),
67+
lanelet.polygon2d().basicPolygon())) {
6868
return false;
6969
}
7070

71-
return boost::geometry::within(
72-
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pose.position))
73-
.basicPoint(),
74-
lanelet.polygon2d().basicPolygon());
71+
const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position);
72+
return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) <
73+
yaw_threshold;
7574
}
7675

7776
bool isPolygonOverlapLanelet(
7877
const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold)
7978
{
80-
const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose;
81-
const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position);
82-
if (
83-
std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) >
84-
yaw_threshold) {
79+
const auto lanelet_polygon = utils::toPolygon2d(lanelet);
80+
if (!isPolygonOverlapLanelet(object, lanelet_polygon)) {
8581
return false;
8682
}
8783

88-
const auto lanelet_polygon = utils::toPolygon2d(lanelet);
89-
return isPolygonOverlapLanelet(object, lanelet_polygon);
84+
const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose;
85+
const auto closest_pose = lanelet::utils::getClosestCenterPose(lanelet, object_pose.position);
86+
return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, object_pose)) <
87+
yaw_threshold;
9088
}
9189

9290
bool isPolygonOverlapLanelet(

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -926,11 +926,6 @@ BehaviorModuleOutput StaticObstacleAvoidanceModule::plan()
926926
spline_shift_path = helper_->getPreviousSplineShiftPath();
927927
}
928928

929-
// post processing
930-
{
931-
postProcess(); // remove old shift points
932-
}
933-
934929
BehaviorModuleOutput output;
935930

936931
const auto is_ignore_signal = [this](const UUID & uuid) {

planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -2253,10 +2253,9 @@ std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
22532253
Pose p_reference_ego_front = reference_path.points.front().point.pose;
22542254
Pose p_spline_ego_front = spline_path.points.front().point.pose;
22552255
double next_longitudinal_distance = parameters->resample_interval_for_output;
2256+
const auto offset = arc_length_array.at(ego_idx);
22562257
for (size_t i = 0; i < points_size; ++i) {
2257-
const auto distance_from_ego =
2258-
autoware::motion_utils::calcSignedArcLength(reference_path.points, ego_idx, i);
2259-
if (distance_from_ego > object_check_forward_distance) {
2258+
if (arc_length_array.at(i) > object_check_forward_distance + offset) {
22602259
break;
22612260
}
22622261

0 commit comments

Comments
 (0)