1 #define LANELET_LAYER_DEFINITION
5 #include <boost/geometry/algorithms/disjoint.hpp>
6 #include <boost/geometry/algorithms/equals.hpp>
7 #include <boost/geometry/index/rtree.hpp>
19 namespace bgi = boost::geometry::index;
29 return geometry1 == geometry2;
34 return geometry1 == geometry2;
43 struct IdVisitor :
public RuleParameterVisitor {
45 boost::apply_visitor(*
this, from);
48 void operator()(
const ConstPoint3d&
p)
override {
id =
p.id(); }
49 void operator()(
const ConstLineString3d& ls)
override {
id = ls.id(); }
50 void operator()(
const ConstPolygon3d&
p)
override {
id =
p.id(); }
51 void operator()(
const ConstWeakLanelet& ll)
override {
57 void operator()(
const ConstWeakArea& ar)
override {
76 std::unordered_map<Id, T> toMap(
const std::vector<T>& vec) {
77 using Map = std::unordered_map<Id, T>;
78 auto elems =
utils::transform(vec, [](
auto& elem) {
return typename Map::value_type(
getId(elem), elem); });
79 return std::unordered_map<Id, T>(std::make_move_iterator(elems.begin()), std::make_move_iterator(elems.end()));
82 LineString3d uglyRemoveConst(
const ConstLineString3d& ls) {
85 auto data = std::const_pointer_cast<LineStringData>(ls.constData());
86 return LineString3d(data, ls.inverted());
95 return std::hash<lanelet::Id>()(lanelet::IdVisitor().getId(x));
101 using namespace traits;
103 template <
typename RType,
typename Pair>
104 auto getSecond(
const std::vector<Pair>&
p) {
105 std::vector<RType> v;
107 std::transform(
p.cbegin(),
p.cend(), std::back_inserter(v), [](
const auto& elem) { return elem.second; });
111 template <
typename PrimT,
typename LayerT>
112 void assignIdIfInvalid(PrimT&& prim, LayerT& layer) {
113 static_assert(std::is_same<
typename LayerT::PrimitiveT, std::decay_t<PrimT>>::value,
114 "Primitive and layer not identical");
116 prim.setId(layer.uniqueId());
120 struct AssignIdVisitor :
public boost::static_visitor<void> {
121 explicit AssignIdVisitor(LaneletMap* map) :
map_(map) {}
122 void operator()(Point3d
p) { assignIdIfInvalid(
p,
map_->pointLayer); }
123 void operator()(LineString3d l) { assignIdIfInvalid(l,
map_->lineStringLayer); }
124 void operator()(Polygon3d
p) { assignIdIfInvalid(
p,
map_->polygonLayer); }
125 void operator()(
const WeakLanelet& ll) {
129 assignIdIfInvalid(ll.lock(),
map_->laneletLayer);
131 void operator()(
const WeakArea& ar) {
135 assignIdIfInvalid(ar.lock(),
map_->areaLayer);
143 explicit AddVisitor(LaneletMap* map) :
map_(map) {}
145 void operator()(
const Point3d&
p)
override {
map_->add(
p); }
146 void operator()(
const LineString3d& l)
override {
map_->add(l); }
147 void operator()(
const Polygon3d&
p)
override {
map_->add(
p); }
148 void operator()(
const WeakLanelet& ll)
override {
152 map_->add(ll.lock());
154 void operator()(
const WeakArea& ar)
override {
158 map_->add(ar.lock());
165 template <
typename T,
typename MapT,
typename KeyT,
typename Func>
166 std::vector<T> forEachMatchInMultiMap(
const MapT& map,
const KeyT& key, Func&& f) {
167 auto range = map.equal_range(key);
171 template <
typename RetT,
typename TreeT,
typename Func>
172 Optional<RetT> findUntilImpl(TreeT&& tree,
const BoundingBox2d& area,
const Func& func) {
176 auto found = std::find_if(tree.qbegin(bgi::intersects(area)), tree.qend(),
177 [&func](
auto& node) { return func(node.first, node.second); });
178 if (found != tree.qend()) {
179 return RetT(found->second);
184 template <
typename RetT,
typename TreeT,
typename Func>
185 Optional<RetT> nearestUntilImpl(TreeT&& tree,
const BasicPoint2d& point,
const Func& func) {
189 auto found = std::find_if(tree.qbegin(bgi::nearest(point,
unsigned(tree.size()))), tree.qend(),
190 [&func](
auto& node) { return func(node.first, node.second); });
191 if (found != tree.qend()) {
192 return RetT(found->second);
197 template <
typename T>
206 template <
typename ConstLaneletsT,
typename ConstAreasT>
207 LaneletMapUPtr createMapFromConst(
const ConstLaneletsT& fromLanelets,
const ConstAreasT& fromAreas) {
210 auto lanelets =
utils::transform(fromLanelets, [](
const ConstLanelet& llt) {
211 return Lanelet(std::const_pointer_cast<LaneletData>(llt.constData()), llt.inverted());
214 fromAreas, [](
const ConstArea& ar) {
return Area(std::const_pointer_cast<AreaData>(ar.constData())); });
221 template <
typename T>
224 for (
const auto& elem : prim) {
228 std::unordered_multimap<traits::ConstPrimitiveType<traits::OwnedT<T>>, T>
ownedLookup;
234 for (
const auto& param : prim->getParameters()) {
235 for (
const auto& rule : param.second) {
240 std::unordered_multimap<ConstRuleParameter, RegulatoryElementPtr>
ownedLookup;
245 auto insertElement = [area,
this](
auto elem) {
ownedLookup.insert(std::make_pair(elem, area)); };
248 for (
const auto& innerBound : area.
innerBounds()) {
253 regElemLookup.insert(std::make_pair(elem, area));
265 regElemLookup.insert(std::make_pair(elem, ll));
277 template <
typename T>
280 using RTree = bgi::rtree<TreeNode, bgi::quadratic<16>>;
283 std::vector<TreeNode> nodes;
284 nodes.reserve(primitives.size());
285 for (
auto& primitive : primitives) {
286 auto node = treeNode(primitive.second);
287 if (!node.first.isEmpty()) {
288 nodes.push_back(std::move(node));
291 rTree =
RTree(nodes);
296 if (!node.first.isEmpty()) {
302 if (!node.first.isEmpty()) {
313 using RTree = bgi::rtree<TreeNode, bgi::quadratic<16>>;
316 std::vector<TreeNode> nodes;
317 nodes.reserve(primitives.size());
318 std::transform(primitives.begin(), primitives.end(), std::back_inserter(nodes),
319 [](
const auto& elem) { return treeNode(elem.second); });
320 rTree =
RTree(nodes);
328 template <
typename T>
330 : elements_{primitives}, tree_{std::make_unique<Tree>(primitives)} {
331 for (
const auto& prim : primitives) {
332 tree_->usage.add(prim.second);
338 : elements_{primitives}, tree_{std::make_unique<Tree>(primitives)} {
339 for (
const auto& prim : primitives) {
340 tree_->usage.add(prim.second);
346 : elements_{primitives}, tree_{std::make_unique<Tree>(primitives)} {
347 for (
const auto& prim : primitives) {
348 tree_->usage.add(prim.second);
353 template <
typename T>
355 return id !=
InvalId && elements_.find(
id) != elements_.end();
358 template <
typename T>
364 return elements_.at(
id);
365 }
catch (std::out_of_range&) {
370 template <
typename T>
376 return elements_.at(
id);
377 }
catch (std::out_of_range&) {
382 template <
typename T>
384 for (
const auto& elem : element) {
385 tree_->usage.ownedLookup.insert(std::make_pair(elem, element));
387 elements_.insert({element.id(), element});
388 tree_->insert(element);
393 tree_->usage.
add(area);
394 elements_.insert({area.
id(), area});
400 tree_->usage.
add(ll);
401 elements_.insert({ll.
id(), ll});
408 elements_.insert({
p.id(),
p});
414 tree_->usage.
add(element);
415 elements_.insert({element->id(), element});
416 tree_->insert(element);
419 template <
typename T>
422 return forEachMatchInMultiMap<traits::ConstPrimitiveType<typename PrimitiveLayer<T>::PrimitiveT>>(
423 tree_->usage.ownedLookup, primitive, [](
const auto& elem) {
return traits::toConst(elem.second); });
426 template <
typename T>
429 return forEachMatchInMultiMap<typename PrimitiveLayer<T>::PrimitiveT>(tree_->usage.ownedLookup, primitive,
430 [](
const auto& elem) {
return elem.second; });
444 return forEachMatchInMultiMap<Area>(tree_->usage.regElemLookup, regElem,
445 [](
const auto& elem) { return elem.second; });
449 return forEachMatchInMultiMap<ConstArea>(tree_->usage.regElemLookup, regElem,
450 [](
const auto& elem) { return traits::toConst(elem.second); });
454 return forEachMatchInMultiMap<Lanelet>(tree_->usage.regElemLookup, regElem,
455 [](
const auto& elem) { return elem.second; });
459 return forEachMatchInMultiMap<ConstLanelet>(tree_->usage.regElemLookup, regElem,
460 [](
const auto& elem) { return traits::toConst(elem.second); });
463 template <
typename T>
465 template <typename T>
467 template <typename T>
470 template <typename T>
472 return elements_.find(
id);
475 template <
typename T>
477 return elements_.
begin();
480 template <
typename T>
482 return elements_.
end();
485 template <
typename T>
487 return elements_.find(
id);
490 template <
typename T>
492 return elements_.
begin();
495 template <
typename T>
496 typename PrimitiveLayer<T>::iterator PrimitiveLayer<T>::end() {
497 return elements_.end();
499 template <
typename T>
501 std::vector<typename Tree::TreeNode> nodes;
502 tree_->rTree.query(bgi::intersects(area), std::back_inserter(nodes));
503 return getSecond<ConstPrimitiveT, typename Tree::TreeNode>(nodes);
506 template <
typename T>
508 std::vector<typename Tree::TreeNode> nodes;
509 tree_->rTree.query(bgi::intersects(area), std::back_inserter(nodes));
510 return getSecond<PrimitiveT, typename Tree::TreeNode>(nodes);
513 template <
typename T>
516 return findUntilImpl<ConstPrimitiveT>(tree_->rTree, area, func);
519 template <
typename T>
522 return findUntilImpl<PrimitiveT>(tree_->rTree, area, func);
525 template <
typename T>
527 std::vector<typename Tree::TreeNode> nodes;
528 tree_->rTree.query(bgi::nearest(point, n), std::back_inserter(nodes));
529 return getSecond<ConstPrimitiveT, typename Tree::TreeNode>(nodes);
532 template <
typename T>
534 std::vector<typename Tree::TreeNode> nodes;
536 tree_->rTree.query(bgi::nearest(point, n), std::back_inserter(nodes));
537 return getSecond<PrimitiveT, typename Tree::TreeNode>(nodes);
540 template <
typename T>
543 return nearestUntilImpl<ConstPrimitiveT>(tree_->rTree, point, func);
546 template <
typename T>
549 return nearestUntilImpl<PrimitiveT>(tree_->rTree, point, func);
552 template <
typename T>
557 LaneletMapLayers::LaneletMapLayers(
const LaneletLayer::Map& lanelets,
const AreaLayer::Map& areas,
558 const RegulatoryElementLayer::Map& regulatoryElements,
559 const PolygonLayer::Map& polygons,
const LineStringLayer::Map& lineStrings,
560 const PointLayer::Map& points)
561 : laneletLayer(lanelets),
563 regulatoryElementLayer(regulatoryElements),
564 polygonLayer(polygons),
565 lineStringLayer(lineStrings),
566 pointLayer(points) {}
578 if (
lanelet.hasCustomCenterline()) {
582 for (
const auto& regelem :
lanelet.regulatoryElements()) {
583 if (regelem->id() ==
InvalId) {
589 for (
const auto& regElem :
lanelet.regulatoryElements()) {
606 for (
const auto& ls : lss) {
612 if (regelem->id() ==
InvalId) {
625 throw NullptrError(
"Empty regulatory element passed to add()!");
627 if (regElem->id() ==
InvalId) {
634 AssignIdVisitor setIdVisitor(
this);
635 for (
const auto& elems : *regElem) {
636 for (
const auto& elem : elems.second) {
637 boost::apply_visitor(setIdVisitor, elem);
642 AddVisitor visitor(
this);
643 regElem->applyVisitor(visitor);
654 for (
const auto&
p : polygon) {
668 for (
const auto&
p : lineString) {
687 utils::forEach(
lanelet.regulatoryElements(), [&](
auto& regElem) { this->trackParameters(*regElem); });
720 auto add = [&map](
auto& prim) {
721 using T = std::decay_t<decltype(prim)>;
725 auto addLs = [&map](
auto& prim) {
726 map->add(
LineString3d(std::const_pointer_cast<LineStringData>(prim.constData()), prim.inverted()));
728 auto addRe = [&map](
auto& prim) { map->add(std::const_pointer_cast<RegulatoryElement>(prim)); };
739 auto add = [&](
auto& val) { map->add(val); };
748 using LLorAreas = std::vector<boost::variant<ConstLanelet, ConstArea>>;
751 explicit AddToLLorAreaVisitor(LLorAreas& llOrAreas) : llOrAreas_{&llOrAreas} {}
754 llOrAreas_->emplace_back(wll.
lock());
759 llOrAreas_->emplace_back(wa.
lock());
764 LLorAreas* llOrAreas_{};
778 template <
typename PrimitiveT>
780 std::vector<ConstLayerPrimitive<PrimitiveT>> usages;
781 std::copy_if(layer.
begin(), layer.
end(), std::back_inserter(usages),
782 [&
id](
const auto& elem) { return utils::has(elem, id); });
797 llts.insert(llts.end(), lltsInv.begin(), lltsInv.end());
798 auto remove = std::unique(llts.begin(), llts.end());
799 llts.erase(remove, llts.end());
807 areas.insert(areas.end(), areasInv.begin(), areasInv.end());
808 auto remove = std::unique(areas.begin(), areas.end());
809 areas.erase(remove, areas.end());
819 auto points =
utils::concatenateRange(fromLineStrings, [](
auto ls) {
return std::make_pair(ls.begin(), ls.end()); });
826 ls.reserve(fromLanelets.size() * 2 + fromAreas.size() * 3);
827 for (
auto ll : fromLanelets) {
828 ls.push_back(ll.leftBound());
829 ls.push_back(ll.rightBound());
830 if (ll.hasCustomCenterline()) {
831 auto center = ll.centerline();
832 ls.emplace_back(std::const_pointer_cast<LineStringData>(center.constData()), center.inverted());
835 auto appendMultiLs = [&ls](
auto& lsappend) {
836 std::for_each(lsappend.begin(), lsappend.end(), [&ls](
auto& l) { ls.push_back(l); });
838 for (
auto area : fromAreas) {
839 appendMultiLs(area.outerBound());
840 for (
auto inner : area.innerBounds()) {
841 appendMultiLs(inner);
848 return std::make_pair(regelems.begin(), regelems.end());
852 return std::make_pair(regelems.begin(), regelems.end());
856 for (
const auto& regelem : regelems) {
859 for (
const auto& regelem : areaRegelems) {
870 auto points =
utils::concatenateRange(fromPolygons, [](
auto ls) {
return std::make_pair(ls.begin(), ls.end()); });
876 return createMapFromConst(fromLanelets, fromAreas);
880 std::atomic<Id> currId{1000};
888 Id current = currId.load();
889 while (current < newId && !currId.compare_exchange_weak(current, newId)) {
915 for (
const auto& ll : fromLanelets) {
916 utils::forEach(ll.regulatoryElements(), [&](
auto& regelem) { map->trackParameters(*regelem); });
918 for (
const auto& ar : fromAreas) {
919 utils::forEach(ar.regulatoryElements(), [&](
auto& regelem) { map->trackParameters(*regelem); });
939 template <
typename T>
940 class NSmallestElements {
942 explicit NSmallestElements(
size_t n) :
n_{n} {
values_.reserve(n); }
943 bool insert(
double measure, T value) {
945 std::lower_bound(
values_.begin(),
values_.end(), measure, [](
auto& v1,
double v2) { return v1.first < v2; });
950 values_.emplace(pos, measure, value);
955 const auto& values()
const {
return values_; }
956 auto moveValues() {
return std::move(
values_); }
957 bool full()
const {
return values_.size() >=
n_; }
958 bool empty()
const {
return values_.empty(); }
965 template <
typename RetT,
typename LayerT>
966 auto findNearestImpl(LayerT&& map,
const BasicPoint2d& pt,
unsigned count) {
972 NSmallestElements<RetT> closest(count);
973 auto searchFunction = [&closest, &pt](
auto& box,
const RetT& prim) {
975 if (closest.full() && dBox > closest.values().back().first) {
981 map.nearestUntil(pt, searchFunction);
982 return closest.moveValues();
986 template <
typename PrimT>
988 return findNearestImpl<PrimT>(map, pt, count);
991 template <
typename PrimT>
994 return findNearestImpl<traits::ConstPrimitiveType<PrimT>>(map, pt, count);
1000 #define INSTANCIATE_FIND_NEAREST(PRIM) template std::vector<std::pair<double, PRIM>> findNearest<PRIM>(PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
1002 #define INSTANCIATE_CONST_FIND_NEAREST(PRIM, CPRIM) template std::vector<std::pair<double, CPRIM>> findNearest<PRIM>(const PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
1010 #undef INSTANCIATE_FIND_NEAREST
1018 #undef INSTANCIATE_CONST_FIND_NEAREST