LaneletMatching.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019
3  * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de)
4  * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu)
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its contributors
16  * may be used to endorse or promote products derived from this software without
17  * specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 #include "LaneletMatching.h"
32 
33 #include <lanelet2_core/geometry/Lanelet.h>
34 #include <lanelet2_core/geometry/Polygon.h>
35 
36 #include "Utilities.h"
37 
38 namespace {
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) {
44  MatchT match;
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);
50  }
51 
52  // sort ascending by distance
53  std::sort(matchVec.begin(), matchVec.end(),
54  [](const auto& lhs, const auto& rhs) { return lhs.distance < rhs.distance; });
55 
56  return matchVec;
57 }
58 
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) {
65  MatchT match;
66  match.distance = pair.first;
67  match.lanelet = pair.second;
68  match.mahalanobisDistSq = lanelet::matching::utils::getMahalanobisDistSq(match.lanelet, obj);
69  matchVec.push_back(match);
70  match.lanelet = pair.second.invert();
71  match.mahalanobisDistSq = lanelet::matching::utils::getMahalanobisDistSq(match.lanelet, obj);
72  matchVec.push_back(match);
73  }
74 
75  // sort ascending by mahalanobisDistSq
76  std::sort(matchVec.begin(), matchVec.end(),
77  [](const auto& lhs, const auto& rhs) { return lhs.mahalanobisDistSq < rhs.mahalanobisDistSq; });
78 
79  return matchVec;
80 }
81 } // namespace
82 
83 namespace lanelet {
84 namespace matching {
85 
86 std::vector<LaneletMatch> getDeterministicMatches(LaneletMap& map, const Object2d& obj, double maxDist) {
87  return toMatchVector<Lanelet, LaneletMatch>(utils::findWithin(map.laneletLayer, obj, maxDist));
88 }
89 
90 std::vector<ConstLaneletMatch> getDeterministicMatches(const LaneletMap& map, const Object2d& obj, double maxDist) {
91  return toMatchVector<ConstLanelet, ConstLaneletMatch>(utils::findWithin(map.laneletLayer, obj, maxDist));
92 }
93 
94 std::vector<LaneletMatchProbabilistic> getProbabilisticMatches(LaneletMap& map, const ObjectWithCovariance2d& obj,
95  double maxDist) {
96  auto pairVec = utils::findWithin(map.laneletLayer, obj, maxDist);
97  return getProbabilisticMatchesImpl<Lanelet, LaneletMatchProbabilistic>(pairVec, obj);
98 }
99 
100 std::vector<ConstLaneletMatchProbabilistic> getProbabilisticMatches(const LaneletMap& map,
101  const ObjectWithCovariance2d& obj, double maxDist) {
102  auto pairVec = utils::findWithin(map.laneletLayer, obj, maxDist);
103  return getProbabilisticMatchesImpl<ConstLanelet, ConstLaneletMatchProbabilistic>(pairVec, obj);
104 }
105 
106 } // namespace matching
107 } // namespace lanelet
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.
Definition: Utilities.cpp:73
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.
Definition: Utilities.h:48


lanelet2_matching
Author(s): Maximilian Naumann
autogenerated on Tue Jun 6 2023 02:23:52