Namespaces | |
| utils | |
Classes | |
| struct | ConstLaneletMatch |
| struct | ConstLaneletMatchProbabilistic |
| struct | LaneletMatch |
| struct | LaneletMatchProbabilistic |
| struct | Object2d |
| struct | ObjectWithCovariance2d |
Typedefs | |
| using | Hull2d = BasicPolygon2d |
| using | Pose2d = Eigen::Transform< double, 2, Eigen::Isometry, Eigen::DontAlign > |
| a 2d pose More... | |
| using | PositionCovariance2d = Eigen::Matrix< double, 2, 2, Eigen::DontAlign > |
| a covariance of a 2d position More... | |
Functions | |
| 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 More... | |
| std::vector< ConstLaneletMatch > | getDeterministicMatches (const LaneletMap &map, const Object2d &obj, double maxDist) |
| 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, sorted ascending by Mahalanobis distance More... | |
| std::vector< ConstLaneletMatchProbabilistic > | getProbabilisticMatches (const LaneletMap &map, const ObjectWithCovariance2d &obj, double maxDist) |
| template<typename LayerT > | |
| 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. More... | |
| template<typename LayerT > | |
| bool | isWithin (const LayerT &map, const Object2d &obj) |
| Determine whether an object is (at least partially) within any primitive of the layer. More... | |
| template<typename MatchVectorT > | |
| MatchVectorT | removeNonRuleCompliantMatches (const MatchVectorT &matches, const lanelet::traffic_rules::TrafficRulesPtr &trafficRulesPtr) |
| Remove non traffic rule compliant probabilistic lanelet matches. More... | |
| using lanelet::matching::Hull2d = typedef BasicPolygon2d |
| using lanelet::matching::Pose2d = typedef Eigen::Transform<double, 2, Eigen::Isometry, Eigen::DontAlign> |
| using lanelet::matching::PositionCovariance2d = typedef Eigen::Matrix<double, 2, 2, Eigen::DontAlign> |
| std::vector< LaneletMatch > lanelet::matching::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
Definition at line 86 of file LaneletMatching.cpp.
| std::vector< ConstLaneletMatch > lanelet::matching::getDeterministicMatches | ( | const LaneletMap & | map, |
| const Object2d & | obj, | ||
| double | maxDist | ||
| ) |
Definition at line 90 of file LaneletMatching.cpp.
| std::vector< LaneletMatchProbabilistic > lanelet::matching::getProbabilisticMatches | ( | LaneletMap & | map, |
| const ObjectWithCovariance2d & | obj, | ||
| double | maxDist | ||
| ) |
get probabilistic lanelet matches of an object with a maximum deterministic euler distance of maxDist, sorted ascending by Mahalanobis distance
| MatchingError | if the orientationCovarianceRadians or the determinant of the position covariance is zero |
for the distance computation see D. Petrich, T. Dang, D. Kasper, G. Breuel and C. Stiller, "Map-based long term motion prediction for vehicles in traffic environments," 16th International IEEE Conference on Intelligent Transportation Systems (ITSC 2013), The Hague, 2013, pp. 2166-2172. doi: 10.1109/ITSC.2013.6728549 https://ieeexplore.ieee.org/document/6728549
Definition at line 94 of file LaneletMatching.cpp.
| std::vector< ConstLaneletMatchProbabilistic > lanelet::matching::getProbabilisticMatches | ( | const LaneletMap & | map, |
| const ObjectWithCovariance2d & | obj, | ||
| double | maxDist | ||
| ) |
Definition at line 100 of file LaneletMatching.cpp.
| bool lanelet::matching::isCloseTo | ( | const LayerT & | map, |
| const Object2d & | obj, | ||
| double | maxDist | ||
| ) |
Determine whether an object is within a maximum distance to any primitive of the layer.
Definition at line 70 of file LaneletMatching.h.
| bool lanelet::matching::isWithin | ( | const LayerT & | map, |
| const Object2d & | obj | ||
| ) |
Determine whether an object is (at least partially) within any primitive of the layer.
Definition at line 79 of file LaneletMatching.h.
| MatchVectorT lanelet::matching::removeNonRuleCompliantMatches | ( | const MatchVectorT & | matches, |
| const lanelet::traffic_rules::TrafficRulesPtr & | trafficRulesPtr | ||
| ) |
Remove non traffic rule compliant probabilistic lanelet matches.
Definition at line 87 of file LaneletMatching.h.