Skip to content

Commit 00a59e6

Browse files
lane change not cancel bug
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent e36f94f commit 00a59e6

File tree

2 files changed

+2
-10
lines changed

2 files changed

+2
-10
lines changed

planning/behavior_path_lane_change_module/src/scene.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1210,7 +1210,7 @@ FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets(
12101210
};
12111211

12121212
if (
1213-
check_optional_polygon(object, lanes_polygon.target) && is_lateral_far &&
1213+
check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far &&
12141214
is_before_terminal()) {
12151215
const auto ahead_of_ego =
12161216
utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object);

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+1-9
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,6 @@
3838
#include <geometry_msgs/msg/detail/pose__struct.hpp>
3939

4040
#include <boost/geometry/algorithms/detail/disjoint/interface.hpp>
41-
#include <boost/geometry/algorithms/difference.hpp>
4241

4342
#include <lanelet2_core/LaneletMap.h>
4443
#include <lanelet2_core/geometry/LineString.h>
@@ -1212,18 +1211,11 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr)
12121211
const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets(
12131212
lanes->target, common_data_ptr->direction, lc_param_ptr->lane_expansion_left_offset,
12141213
lc_param_ptr->lane_expansion_right_offset);
1215-
1216-
const auto expanded_target_polygon = utils::lane_change::createPolygon(
1214+
lanes_polygon.expanded_target = utils::lane_change::createPolygon(
12171215
expanded_target_lanes, 0.0, std::numeric_limits<double>::max());
12181216

12191217
lanes_polygon.target_neighbor = *utils::lane_change::createPolygon(
12201218
lanes->target_neighbor, 0.0, std::numeric_limits<double>::max());
1221-
std::vector<lanelet::BasicPolygon2d> difference;
1222-
boost::geometry::difference(*expanded_target_polygon, *lanes_polygon.target, difference);
1223-
1224-
if (!difference.empty()) {
1225-
lanes_polygon.expanded_target = std::make_optional<lanelet::BasicPolygon2d>(difference.front());
1226-
}
12271219

12281220
lanes_polygon.preceding_target.reserve(lanes->preceding_target.size());
12291221
for (const auto & preceding_lane : lanes->preceding_target) {

0 commit comments

Comments
 (0)