|
38 | 38 | #include <geometry_msgs/msg/detail/pose__struct.hpp>
|
39 | 39 |
|
40 | 40 | #include <boost/geometry/algorithms/detail/disjoint/interface.hpp>
|
41 |
| -#include <boost/geometry/algorithms/difference.hpp> |
42 | 41 |
|
43 | 42 | #include <lanelet2_core/LaneletMap.h>
|
44 | 43 | #include <lanelet2_core/geometry/LineString.h>
|
@@ -1212,18 +1211,11 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr)
|
1212 | 1211 | const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets(
|
1213 | 1212 | lanes->target, common_data_ptr->direction, lc_param_ptr->lane_expansion_left_offset,
|
1214 | 1213 | 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( |
1217 | 1215 | expanded_target_lanes, 0.0, std::numeric_limits<double>::max());
|
1218 | 1216 |
|
1219 | 1217 | lanes_polygon.target_neighbor = *utils::lane_change::createPolygon(
|
1220 | 1218 | 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 |
| - } |
1227 | 1219 |
|
1228 | 1220 | lanes_polygon.preceding_target.reserve(lanes->preceding_target.size());
|
1229 | 1221 | for (const auto & preceding_lane : lanes->preceding_target) {
|
|
0 commit comments