33 #include <lanelet2_core/geometry/Lanelet.h> 34 #include <lanelet2_core/geometry/Polygon.h> 36 #include "Utilities.h" 39 template <
typename LaneletT,
typename MatchT>
40 std::vector<MatchT> toMatchVector(std::vector<std::pair<double, LaneletT>> pairVec) {
41 std::vector<MatchT> matchVec;
42 matchVec.reserve(2 * pairVec.size());
43 for (
const auto& pair : pairVec) {
45 match.distance = pair.first;
46 match.lanelet = pair.second;
47 matchVec.push_back(match);
48 match.lanelet = pair.second.invert();
49 matchVec.push_back(match);
53 std::sort(matchVec.begin(), matchVec.end(),
54 [](
const auto& lhs,
const auto& rhs) {
return lhs.distance < rhs.distance; });
59 template <
typename LaneletT,
typename MatchT>
60 std::vector<MatchT> getProbabilisticMatchesImpl(
const std::vector<std::pair<double, LaneletT>>& pairVec,
62 std::vector<MatchT> matchVec;
63 matchVec.reserve(2 * pairVec.size());
64 for (
const auto& pair : pairVec) {
66 match.distance = pair.first;
67 match.lanelet = pair.second;
69 matchVec.push_back(match);
70 match.lanelet = pair.second.invert();
72 matchVec.push_back(match);
76 std::sort(matchVec.begin(), matchVec.end(),
77 [](
const auto& lhs,
const auto& rhs) {
return lhs.mahalanobisDistSq < rhs.mahalanobisDistSq; });
97 return getProbabilisticMatchesImpl<Lanelet, LaneletMatchProbabilistic>(pairVec, obj);
103 return getProbabilisticMatchesImpl<ConstLanelet, ConstLaneletMatchProbabilistic>(pairVec, obj);
std::vector< LaneletMatchProbabilistic > getProbabilisticMatches(LaneletMap &map, const ObjectWithCovariance2d &obj, double maxDist)
get probabilistic lanelet matches of an object with a maximum deterministic euler distance of maxDist...
double getMahalanobisDistSq(const ConstLanelet &lanelet, const ObjectWithCovariance2d &obj)
Compute squared mahalanobis distance based on pose and covariance, hull is not used.
LaneletLayer laneletLayer
std::vector< LaneletMatch > getDeterministicMatches(LaneletMap &map, const Object2d &obj, double maxDist)
get deterministic lanelet matches of an object with a maximum distance of maxDist, sorted ascending by distance
auto findWithin(LayerT &map, const Object2d &obj, double maxDist) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>>
Find all primitives as close as or closer than maxDist to an object.