LaneletMatching.h
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 #pragma once
32 
35 
36 #include "Exceptions.h"
37 #include "Types.h"
38 #include "Utilities.h"
39 
40 namespace lanelet {
41 namespace matching {
42 
47 std::vector<LaneletMatch> getDeterministicMatches(LaneletMap& map, const Object2d& obj, double maxDist);
48 std::vector<ConstLaneletMatch> getDeterministicMatches(const LaneletMap& map, const Object2d& obj, double maxDist);
49 
61 std::vector<LaneletMatchProbabilistic> getProbabilisticMatches(LaneletMap& map, const ObjectWithCovariance2d& obj,
62  double maxDist);
63 std::vector<ConstLaneletMatchProbabilistic> getProbabilisticMatches(const LaneletMap& map,
64  const ObjectWithCovariance2d& obj, double maxDist);
65 
69 template <typename LayerT>
70 bool isCloseTo(const LayerT& map, const Object2d& obj, double maxDist) {
71  auto closePrimitives = utils::findWithin(map, obj, maxDist);
72  return !closePrimitives.empty();
73 }
74 
78 template <typename LayerT>
79 bool isWithin(const LayerT& map, const Object2d& obj) {
80  return isCloseTo(map, obj, 0.);
81 }
82 
86 template <typename MatchVectorT>
87 MatchVectorT removeNonRuleCompliantMatches(const MatchVectorT& matches,
88  const lanelet::traffic_rules::TrafficRulesPtr& trafficRulesPtr) {
89  MatchVectorT compliantMatches = matches;
90  compliantMatches.erase(
91  std::remove_if(compliantMatches.begin(), compliantMatches.end(),
92  [&trafficRulesPtr](auto& match) { return !trafficRulesPtr->canPass(match.lanelet); }),
93  compliantMatches.end());
94  return compliantMatches;
95 }
96 
97 } // namespace matching
98 } // 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...
MatchVectorT removeNonRuleCompliantMatches(const MatchVectorT &matches, const lanelet::traffic_rules::TrafficRulesPtr &trafficRulesPtr)
Remove non traffic rule compliant probabilistic lanelet matches.
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
bool isCloseTo(const LayerT &map, const Object2d &obj, double maxDist)
Determine whether an object is within a maximum distance to any primitive of the layer.
bool isWithin(const LayerT &map, const Object2d &obj)
Determine whether an object is (at least partially) within any primitive of the layer.
std::shared_ptr< TrafficRules > TrafficRulesPtr


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