3 #include <boost/geometry/algorithms/equals.hpp>
13 namespace bgi = boost::geometry::index;
18 #pragma GCC diagnostic push
19 #pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
20 template <
typename Po
int>
21 auto centerpoint(Point
p1, Point
p2) {
22 bg::add_point(
p1,
p2);
23 bg::multiply_value(
p1, 0.5);
31 using SegmentTree = bgi::rtree<BasicSegment2d, bgi::linear<2>>;
32 using PointNode = std::pair<BasicPoint2d, ConstLineString2d::const_iterator>;
33 using PointTree = bgi::rtree<PointNode, bgi::linear<16>>;
46 const bool result = intersectsLeft(seg) || intersectsRight(seg) || crossesEntry(seg) || crossesExit(seg);
52 if (!boost::geometry::equals(it->first, seg.first)) {
61 if (!boost::geometry::equals(it->first, seg.first)) {
68 bool secondCrossesBounds(
const BasicSegment2d& seg,
bool left)
const {
70 for (
auto it = segmentTree.qbegin(bgi::intersects(seg)); it != segmentTree.qend(); ++it) {
71 using boost::geometry::equals;
72 if (!equals(it->first, seg.second) && !equals(it->second, seg.second)) {
80 if (geometry::intersects(seg,
entry_)) {
87 if (geometry::intersects(seg,
exit_)) {
93 template <
typename Func>
95 return forEachNearestPointUntilImpl(iter,
leftPts_, std::forward<Func>(f));
97 template <
typename Func>
99 return forEachNearestPointUntilImpl(iter,
rightPts_, std::forward<Func>(f));
103 template <
typename Func>
105 for (
auto qIt = tree.qbegin(boost::geometry::index::nearest(iter->basicPoint(),
unsigned(tree.size())));
106 qIt != tree.qend(); ++qIt) {
107 if (f(qIt->second)) {
113 std::vector<PointNode> nodes;
114 nodes.reserve(ls.
size());
115 for (
auto it = ls.
begin(); it != ls.
end(); ++it) {
116 nodes.emplace_back(it->basicPoint(), it);
121 std::vector<BasicSegment2d> segments;
123 auto makeSegment = [](
const auto& seg) {
return BasicSegment2d(seg.first.basicPoint(), seg.second.basicPoint()); };
125 segments.push_back(makeSegment(line.
segment(i)));
134 std::pair<ConstLineString2d::const_iterator, OptDistance> findClosestNonintersectingPoint(
136 const BoundChecker& bounds,
const Point3d& lastPoint,
bool isLeft) {
144 if (candidate < currPosition) {
152 auto candidateDistance =
bg::distance(*candidate, *otherPoint) / 2;
161 BasicSegment2d boundConnection(otherPoint->basicPoint(), candidate->basicPoint());
162 BasicSegment2d invBoundConnection(boundConnection.second, boundConnection.first);
163 auto centerlinePointCand = centerpoint(boundConnection.first, boundConnection.second);
165 if (!bounds.intersects(centerlineCandidate) && !bounds.secondCrossesBounds(boundConnection, isLeft) &&
166 !bounds.secondCrossesBounds(invBoundConnection, !isLeft)) {
168 closestPosition = candidate;
173 bounds.forEachNearestPointLeftUntil(otherPoint, nonintersectingPointLoop);
175 bounds.forEachNearestPointRightUntil(otherPoint, nonintersectingPointLoop);
180 std::shared_ptr<ConstLineString3d> calculateCenterline(
const ConstLineString2d& leftBound,
181 const ConstLineString2d& rightBound) {
182 LineString3d centerlinePoints(
InvalId);
185 if (leftBound.empty() || rightBound.empty()) {
186 return std::make_shared<ConstLineString3d>(centerlinePoints);
192 centerlinePoints.push_back(makeCenterpoint(leftBound.front(), rightBound.front()));
194 auto leftCurrent = leftBound.begin();
195 auto rightCurrent = rightBound.begin();
197 if (*leftCurrent == *rightCurrent) {
200 while (leftCurrent != leftBound.end() || rightCurrent != rightBound.end()) {
207 std::tie(leftCandidate, leftCandidateDistance) =
208 findClosestNonintersectingPoint(std::next(leftCurrent), rightCurrent, bounds, centerlinePoints.back(),
true);
211 std::tie(rightCandidate, rightCandidateDistance) =
212 findClosestNonintersectingPoint(std::next(rightCurrent), leftCurrent, bounds, centerlinePoints.back(),
false);
214 if (leftCandidateDistance && (!rightCandidateDistance || leftCandidateDistance <= rightCandidateDistance)) {
215 assert(leftCandidate != leftBound.end());
217 const auto& leftPoint = leftBound[size_t(leftCandidate - leftBound.begin())];
218 const auto& rightPoint = rightBound[size_t(rightCurrent - rightBound.begin())];
219 centerlinePoints.push_back(makeCenterpoint(leftPoint, rightPoint));
220 leftCurrent = leftCandidate;
221 }
else if (rightCandidateDistance && (!leftCandidateDistance || leftCandidateDistance > rightCandidateDistance)) {
222 assert(rightCandidate != rightBound.end());
224 const auto& leftPoint = leftBound[size_t(leftCurrent - leftBound.begin())];
225 const auto& rightPoint = rightBound[size_t(rightCandidate - rightBound.begin())];
226 centerlinePoints.push_back(makeCenterpoint(leftPoint, rightPoint));
227 rightCurrent = rightCandidate;
235 if (!(leftCurrent == std::prev(leftBound.end()) && rightCurrent == std::prev(rightBound.end()))) {
236 centerlinePoints.push_back(makeCenterpoint(leftBound.back(), rightBound.back()));
239 return std::make_shared<ConstLineString3d>(centerlinePoints);
241 #pragma GCC diagnostic pop
285 if (!hasCustomCenterline()) {
286 std::atomic_store_explicit(¢erline_, std::shared_ptr<ConstLineString3d>(), std::memory_order_release);
291 stream <<
"[id: " << obj.
id();
293 stream <<
", inverted";
297 stream <<
" (inverted)";
301 stream <<
" (inverted)";
303 return stream <<
"]";
310 std::any_of(regelems.begin(), regelems.end(), [&
id](
const auto& elem) { return elem->id() == id; });