Skip to content

Commit def11e8

Browse files
zulfaqar-azmi-t4kyoichi-sugahara
authored andcommitted
refactor(lane_change): remove std::optional from lanes polygon (autowarefoundation#9288)
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent cc16dae commit def11e8

File tree

4 files changed

+31
-32
lines changed

4 files changed

+31
-32
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -311,9 +311,9 @@ struct PathSafetyStatus
311311

312312
struct LanesPolygon
313313
{
314-
std::optional<lanelet::BasicPolygon2d> current;
315-
std::optional<lanelet::BasicPolygon2d> target;
316-
std::optional<lanelet::BasicPolygon2d> expanded_target;
314+
lanelet::BasicPolygon2d current;
315+
lanelet::BasicPolygon2d target;
316+
lanelet::BasicPolygon2d expanded_target;
317317
lanelet::BasicPolygon2d target_neighbor;
318318
std::vector<lanelet::BasicPolygon2d> preceding_target;
319319
};

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -150,16 +150,15 @@ std::optional<size_t> getLeadingStaticObjectIdx(
150150
const std::vector<ExtendedPredictedObject> & objects,
151151
const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold);
152152

153-
std::optional<lanelet::BasicPolygon2d> createPolygon(
153+
lanelet::BasicPolygon2d create_polygon(
154154
const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist);
155155

156156
ExtendedPredictedObject transform(
157157
const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters,
158158
const LaneChangeParameters & lane_change_parameters);
159159

160-
bool isCollidedPolygonsInLanelet(
161-
const std::vector<Polygon2d> & collided_polygons,
162-
const std::optional<lanelet::BasicPolygon2d> & lanes_polygon);
160+
bool is_collided_polygons_in_lanelet(
161+
const std::vector<Polygon2d> & collided_polygons, const lanelet::BasicPolygon2d & lanes_polygon);
163162

164163
/**
165164
* @brief Generates expanded lanelets based on the given direction and offsets.

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+10-10
Original file line numberDiff line numberDiff line change
@@ -506,7 +506,7 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path)
506506
dist_to_terminal - min_dist_buffer - calculation::calc_stopping_distance(lc_param_ptr);
507507

508508
const auto distance_to_last_fit_width = std::invoke([&]() -> double {
509-
const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current.value();
509+
const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current;
510510
if (utils::isEgoWithinOriginalLane(curr_lanes_poly, getEgoPose(), *bpp_param_ptr)) {
511511
return utils::lane_change::calculation::calc_dist_to_last_fit_width(
512512
lanes_ptr->current, path.points.front().point.pose, *bpp_param_ptr);
@@ -724,7 +724,7 @@ bool NormalLaneChange::hasFinishedLaneChange() const
724724
if (has_passed_end_pose) {
725725
const auto & lanes_polygon = common_data_ptr_->lanes_polygon_ptr->target;
726726
return !boost::geometry::disjoint(
727-
lanes_polygon.value(),
727+
lanes_polygon,
728728
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(current_pose.position)));
729729
}
730730

@@ -751,7 +751,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const
751751
return false;
752752
}
753753

754-
const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current.value();
754+
const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current;
755755
if (!utils::isEgoWithinOriginalLane(
756756
curr_lanes_poly, getEgoPose(), planner_data_->parameters,
757757
lane_change_parameters_->cancel.overhang_tolerance)) {
@@ -827,7 +827,7 @@ bool NormalLaneChange::isAbleToStopSafely() const
827827
const auto stop_dist =
828828
-(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc));
829829

830-
const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current.value();
830+
const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current;
831831
double dist = 0.0;
832832
for (size_t idx = nearest_idx; idx < status_.lane_change_path.path.points.size() - 1; ++idx) {
833833
dist += calcSignedArcLength(status_.lane_change_path.path.points, idx, idx + 1);
@@ -1166,7 +1166,7 @@ FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets(
11661166
const auto & route_handler = getRouteHandler();
11671167
const auto & common_parameters = planner_data_->parameters;
11681168
const auto check_optional_polygon = [](const auto & object, const auto & polygon) {
1169-
return polygon && isPolygonOverlapLanelet(object, *polygon);
1169+
return !polygon.empty() && isPolygonOverlapLanelet(object, polygon);
11701170
};
11711171

11721172
// get backward lanes
@@ -2043,7 +2043,7 @@ bool NormalLaneChange::is_collided(
20432043
const auto & current_polygon = lanes_polygon_ptr->current;
20442044
const auto & expanded_target_polygon = lanes_polygon_ptr->target;
20452045

2046-
if (!current_polygon.has_value() || !expanded_target_polygon.has_value()) {
2046+
if (current_polygon.empty() || expanded_target_polygon.empty()) {
20472047
return !is_collided;
20482048
}
20492049

@@ -2083,9 +2083,9 @@ bool NormalLaneChange::is_collided(
20832083
}
20842084

20852085
const auto collision_in_current_lanes =
2086-
utils::lane_change::isCollidedPolygonsInLanelet(collided_polygons, current_polygon);
2087-
const auto collision_in_target_lanes =
2088-
utils::lane_change::isCollidedPolygonsInLanelet(collided_polygons, expanded_target_polygon);
2086+
utils::lane_change::is_collided_polygons_in_lanelet(collided_polygons, current_polygon);
2087+
const auto collision_in_target_lanes = utils::lane_change::is_collided_polygons_in_lanelet(
2088+
collided_polygons, expanded_target_polygon);
20892089

20902090
if (!collision_in_current_lanes && !collision_in_target_lanes) {
20912091
utils::path_safety_checker::updateCollisionCheckDebugMap(
@@ -2171,7 +2171,7 @@ bool NormalLaneChange::is_valid_start_point(
21712171
const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y);
21722172

21732173
const auto & target_neighbor_poly = common_data_ptr->lanes_polygon_ptr->target_neighbor;
2174-
const auto & target_lane_poly = common_data_ptr_->lanes_polygon_ptr->target.value();
2174+
const auto & target_lane_poly = common_data_ptr_->lanes_polygon_ptr->target;
21752175

21762176
return boost::geometry::covered_by(lc_start_point, target_neighbor_poly) ||
21772177
boost::geometry::covered_by(lc_start_point, target_lane_poly);

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

+15-15
Original file line numberDiff line numberDiff line change
@@ -951,12 +951,13 @@ std::optional<size_t> getLeadingStaticObjectIdx(
951951
return leading_obj_idx;
952952
}
953953

954-
std::optional<lanelet::BasicPolygon2d> createPolygon(
954+
lanelet::BasicPolygon2d create_polygon(
955955
const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist)
956956
{
957957
if (lanes.empty()) {
958958
return {};
959959
}
960+
960961
const auto polygon_3d = lanelet::utils::getPolygonFromArcLength(lanes, start_dist, end_dist);
961962
return lanelet::utils::to2D(polygon_3d).basicPolygon();
962963
}
@@ -994,12 +995,11 @@ ExtendedPredictedObject transform(
994995
return extended_object;
995996
}
996997

997-
bool isCollidedPolygonsInLanelet(
998-
const std::vector<Polygon2d> & collided_polygons,
999-
const std::optional<lanelet::BasicPolygon2d> & lanes_polygon)
998+
bool is_collided_polygons_in_lanelet(
999+
const std::vector<Polygon2d> & collided_polygons, const lanelet::BasicPolygon2d & lanes_polygon)
10001000
{
10011001
const auto is_in_lanes = [&](const auto & collided_polygon) {
1002-
return lanes_polygon && boost::geometry::intersects(lanes_polygon.value(), collided_polygon);
1002+
return !lanes_polygon.empty() && !boost::geometry::disjoint(collided_polygon, lanes_polygon);
10031003
};
10041004

10051005
return std::any_of(collided_polygons.begin(), collided_polygons.end(), is_in_lanes);
@@ -1078,28 +1078,28 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr)
10781078
LanesPolygon lanes_polygon;
10791079

10801080
lanes_polygon.current =
1081-
utils::lane_change::createPolygon(lanes->current, 0.0, std::numeric_limits<double>::max());
1081+
utils::lane_change::create_polygon(lanes->current, 0.0, std::numeric_limits<double>::max());
10821082

10831083
lanes_polygon.target =
1084-
utils::lane_change::createPolygon(lanes->target, 0.0, std::numeric_limits<double>::max());
1084+
utils::lane_change::create_polygon(lanes->target, 0.0, std::numeric_limits<double>::max());
10851085

10861086
const auto & lc_param_ptr = common_data_ptr->lc_param_ptr;
10871087
const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets(
10881088
lanes->target, common_data_ptr->direction, lc_param_ptr->lane_expansion_left_offset,
10891089
lc_param_ptr->lane_expansion_right_offset);
1090-
lanes_polygon.expanded_target = utils::lane_change::createPolygon(
1090+
lanes_polygon.expanded_target = utils::lane_change::create_polygon(
10911091
expanded_target_lanes, 0.0, std::numeric_limits<double>::max());
10921092

1093-
lanes_polygon.target_neighbor = *utils::lane_change::createPolygon(
1093+
lanes_polygon.target_neighbor = utils::lane_change::create_polygon(
10941094
lanes->target_neighbor, 0.0, std::numeric_limits<double>::max());
10951095

10961096
lanes_polygon.preceding_target.reserve(lanes->preceding_target.size());
10971097
for (const auto & preceding_lane : lanes->preceding_target) {
10981098
auto lane_polygon =
1099-
utils::lane_change::createPolygon(preceding_lane, 0.0, std::numeric_limits<double>::max());
1099+
utils::lane_change::create_polygon(preceding_lane, 0.0, std::numeric_limits<double>::max());
11001100

1101-
if (lane_polygon) {
1102-
lanes_polygon.preceding_target.push_back(*lane_polygon);
1101+
if (!lane_polygon.empty()) {
1102+
lanes_polygon.preceding_target.push_back(lane_polygon);
11031103
}
11041104
}
11051105
return lanes_polygon;
@@ -1314,7 +1314,7 @@ bool has_blocking_target_object(
13141314

13151315
// filtered_objects includes objects out of target lanes, so filter them out
13161316
if (boost::geometry::disjoint(
1317-
object.initial_polygon, common_data_ptr->lanes_polygon_ptr->target.value())) {
1317+
object.initial_polygon, common_data_ptr->lanes_polygon_ptr->target)) {
13181318
return false;
13191319
}
13201320

@@ -1366,14 +1366,14 @@ bool has_overtaking_turn_lane_object(
13661366
}
13671367

13681368
const auto is_path_overlap_with_target = [&](const LineString2d & path) {
1369-
return !boost::geometry::disjoint(path, common_data_ptr->lanes_polygon_ptr->target.value());
1369+
return !boost::geometry::disjoint(path, common_data_ptr->lanes_polygon_ptr->target);
13701370
};
13711371

13721372
const auto is_object_overlap_with_target = [&](const auto & object) {
13731373
// to compensate for perception issue, or if object is from behind ego, and tries to overtake,
13741374
// but stop all of sudden
13751375
if (!boost::geometry::disjoint(
1376-
object.initial_polygon, common_data_ptr->lanes_polygon_ptr->current.value())) {
1376+
object.initial_polygon, common_data_ptr->lanes_polygon_ptr->current)) {
13771377
return true;
13781378
}
13791379

0 commit comments

Comments
 (0)