07_matching/main.cpp
Go to the documentation of this file.
1 #include <lanelet2_io/Io.h>
6 
7 // we want assert statements to work in release mode
8 #undef NDEBUG
9 
10 namespace {
11 std::string exampleMapPath = std::string(PKG_DIR) + "/../lanelet2_maps/res/mapping_example.osm";
12 
13 template <typename NumberT>
14 void assertNear(NumberT number1, NumberT number2, NumberT maxDifference) {
15  assert(std::abs(number1 - number2) < maxDifference);
16 }
17 
18 template <typename MatchVectorT>
19 std::string toString(const MatchVectorT& matchVector) {
20  std::string out;
21  for (auto& match : matchVector) {
22  out += std::to_string(match.lanelet.id());
23  if (match.lanelet.inverted()) {
24  out += "inv";
25  }
26  out += " ";
27  }
28  return out;
29 }
30 
31 using namespace lanelet;
32 BasicPolygon2d absoluteHull(const BasicPolygon2d& relativeHull, const matching::Pose2d& pose) {
33  BasicPolygon2d hullPoints;
34  hullPoints.reserve(relativeHull.size());
35  for (const auto& hullPt : relativeHull) {
36  hullPoints.push_back(pose * hullPt);
37  }
38  return hullPoints;
39 }
40 
41 struct MapAndObject {
44 };
45 
46 MapAndObject getSampleMapAndObject() {
47  // load the map
48  projection::UtmProjector projector{Origin({49, 8.4})};
49  LaneletMapPtr map = load(exampleMapPath, projector);
50 
51  // create an object
53  obj.pose.translation() = map->pointLayer.get(41656).basicPoint2d();
54  obj.pose.linear() = Eigen::Rotation2D<double>(150. / 180. * M_PI).matrix();
55  obj.absoluteHull = absoluteHull(
56  matching::Hull2d{BasicPoint2d{-1, -0.9}, BasicPoint2d{2, -0.9}, BasicPoint2d{2, 0.9}, BasicPoint2d{1, 0.9}},
57  obj.pose);
58  obj.positionCovariance = matching::PositionCovariance2d::Identity() * 2.;
59  obj.vonMisesKappa = 1. / (10. / 180. * M_PI); // covariance of 10 degrees
60 
61  return MapAndObject{map, obj};
62 }
63 } // namespace
64 
65 void part1testSetup();
68 void part4matchingUtils();
69 
70 int main() {
71  // this tutorial shows you how to use the matching module.
76  return 0;
77 }
78 
80  using namespace lanelet;
81  MapAndObject mao = getSampleMapAndObject();
82  LaneletMapPtr map = mao.map;
84  assert(map->laneletLayer.exists(42440));
85 }
86 
88  using namespace lanelet;
89 
90  MapAndObject mao = getSampleMapAndObject();
91  LaneletMapPtr map = mao.map;
93 
94  // get matches based on a deterministic assignment
95  auto matches = matching::getDeterministicMatches(*map, obj, 4.);
96 
97  // matches are ordered by distance
98  for (size_t i = 1; i < matches.size(); i++) {
99  assert(matches.at(i).distance >= matches.at(i - 1).distance);
100  }
101 
102  // some checks that the found matches are correct
103  assert(14ul == matches.size());
104  assertNear(0.69, matches.at(8).distance, 0.1);
105  assert(45330 == matches.at(8).lanelet.id());
106  assertNear(0.69, matches.at(9).distance, 0.1);
107  assert(45330 == matches.at(9).lanelet.id());
108 
109  // filter non-rule-compliant matches by providing traffic rules
110  traffic_rules::TrafficRulesPtr trafficRulesPtr =
112  auto compliantMatches = matching::removeNonRuleCompliantMatches(matches, trafficRulesPtr);
113  assert(8ul == compliantMatches.size()); // see part3 for details on the compliant matches
114 }
115 
117  using namespace lanelet;
118 
119  MapAndObject mao = getSampleMapAndObject();
120  LaneletMapPtr map = mao.map;
121  matching::ObjectWithCovariance2d obj = mao.obj;
122 
123  // get matches based on a probabilistic assignment
124  auto matches = matching::getProbabilisticMatches(*map, obj, 4.);
125 
126  // matches are ordered by distance
127  // NOLINTNEXTLINE(clang-analyzer-cplusplus.NewDelete)
128  for (size_t i = 1; i < matches.size(); i++) {
129  assert(matches.at(i).mahalanobisDistSq >= matches.at(i - 1).mahalanobisDistSq);
130  }
131 
132  // some checks that the found matches are correct
133  assertNear(0.288177, matches.at(0).mahalanobisDistSq, 0.001);
134  assert(45334 == matches.at(0).lanelet.id());
135  assert(!matches.at(0).lanelet.inverted()); // best match must be non inverted 45334
136  assert(14ul == matches.size());
137 
138  assert(14ul == matches.size());
139  assert("45334 45356inv 45358inv 45328inv 45332 45344 45330 45344inv 45330inv 45332inv 45328 45356 45358 45334inv " ==
140  toString(matches));
141 
142  // filter non-rule-compliant matches by providing traffic rules
143  traffic_rules::TrafficRulesPtr trafficRulesPtr =
145  auto compliantMatches = matching::removeNonRuleCompliantMatches(matches, trafficRulesPtr);
146  assert(8ul ==
147  compliantMatches
148  .size()); // see list below: should exclude zebra crossing (pedestrian only) and inverted one way lanelets
149  assert("45334 45356inv 45358inv 45332 45330 45328 45356 45358 " == toString(compliantMatches));
150 }
151 
153  using namespace lanelet;
154  using namespace lanelet::matching;
155 
156  MapAndObject mao = getSampleMapAndObject();
157  LaneletMapPtr map = mao.map;
158  matching::ObjectWithCovariance2d obj = mao.obj;
159 
160  LaneletLayer emptyLayer;
161 
162  // check whether an object is close to any element of a layer
163  assert(isCloseTo(map->laneletLayer, obj, 4.));
164  assert(!isCloseTo(emptyLayer, obj, 4.));
165 
166  // check whether an object is within any element of a layer
167  assert(isWithin(map->laneletLayer, obj));
168  assert(!isWithin(emptyLayer, obj));
169 
170  // check that this also works based on the position if no hull is provided
171  Object2d objWithEmptyHull;
172  objWithEmptyHull.pose.translation() = map->pointLayer.get(41656).basicPoint2d();
173  assert(matching::isCloseTo(map->laneletLayer, objWithEmptyHull, 1.));
174 }
part3probabilisticMatching
void part3probabilisticMatching()
Definition: 07_matching/main.cpp:116
UTM.h
LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
TrafficRulesFactory.h
lanelet::matching::ObjectWithCovariance2d::vonMisesKappa
double vonMisesKappa
part2deterministicMatching
void part2deterministicMatching()
Definition: 07_matching/main.cpp:87
Io.h
lanelet::matching::getDeterministicMatches
std::vector< ConstLaneletMatch > getDeterministicMatches(const LaneletMap &map, const Object2d &obj, double maxDist)
LaneletMatching.h
lanelet::projection::UtmProjector
part4matchingUtils
void part4matchingUtils()
Definition: 07_matching/main.cpp:152
lanelet::matching::Pose2d
Eigen::Transform< double, 2, Eigen::Isometry, Eigen::DontAlign > Pose2d
lanelet::matching::removeNonRuleCompliantMatches
MatchVectorT removeNonRuleCompliantMatches(const MatchVectorT &matches, const lanelet::traffic_rules::TrafficRulesPtr &trafficRulesPtr)
part1testSetup
void part1testSetup()
Definition: 07_matching/main.cpp:79
main
int main()
Definition: 07_matching/main.cpp:70
lanelet::Locations::Germany
static constexpr char Germany[]
lanelet::load
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
lanelet::matching::getProbabilisticMatches
std::vector< ConstLaneletMatchProbabilistic > getProbabilisticMatches(const LaneletMap &map, const ObjectWithCovariance2d &obj, double maxDist)
lanelet::Origin
lanelet::matching::Object2d::pose
Pose2d pose
map
map
lanelet::matching::Object2d
BasicPoint2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
lanelet::matching::Object2d::absoluteHull
Hull2d absoluteHull
lanelet::Participants::Vehicle
static constexpr const char Vehicle[]
TrafficRules.h
lanelet::LaneletLayer
lanelet::traffic_rules::TrafficRulesFactory::create
static TrafficRulesUPtr create(const std::string &location, const std::string &participant, TrafficRules::Configuration configuration=TrafficRules::Configuration())
lanelet::matching
lanelet::matching::ObjectWithCovariance2d
lanelet::matching::isWithin
bool isWithin(const LayerT &map, const Object2d &obj)
lanelet::matching::ObjectWithCovariance2d::positionCovariance
PositionCovariance2d positionCovariance
lanelet::matching::isCloseTo
bool isCloseTo(const LayerT &map, const Object2d &obj, double maxDist)
lanelet::BasicPolygon2d
lanelet::traffic_rules::TrafficRulesPtr
std::shared_ptr< TrafficRules > TrafficRulesPtr


lanelet2_examples
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:15