Utilities.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 "Utilities.h"
32 
33 #include <lanelet2_core/geometry/Lanelet.h>
34 #include <lanelet2_core/geometry/Polygon.h>
35 
36 #include <cmath>
37 
38 namespace {
39 
40 // from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp
41 // Result is always positive; not similar to fmod()
42 double positiveFloatModulo(double x, double y) {
43  double fmod = std::fmod(x, y);
44  if (fmod > 0.) {
45  return fmod;
46  }
47  double fmodPositive = fmod + std::abs(y);
48  assert(fmodPositive > 0.);
49  return fmodPositive;
50 }
51 
52 // from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp
53 double normalizeAngleRadians(double x) { return positiveFloatModulo((x + M_PI), 2.0 * M_PI) - M_PI; }
54 
55 // from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp
56 double angleDifference(double targetAngle, double sourceAngle) {
57  double angleDiff = targetAngle - sourceAngle;
58  return normalizeAngleRadians(angleDiff);
59 }
60 
61 // from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp
62 double yawFromIsometry2d(const Eigen::Isometry2d& pose) {
63  Eigen::Rotation2D<double> rot;
64  rot.fromRotationMatrix(pose.linear());
65  return rot.smallestAngle();
66 }
67 } // namespace
68 
69 namespace lanelet {
70 namespace matching {
71 namespace utils {
72 
74  if (obj.positionCovariance.isZero()) {
75  throw MatchingError("Covariance must not be zero");
76  }
77  if (fabs(obj.positionCovariance.determinant()) < 10e-9) {
78  throw MatchingError("Determinant must not be zero");
79  }
80  auto centerline2d = lanelet::utils::to2D(lanelet.centerline());
81  ArcCoordinates closestOnCenter = geometry::toArcCoordinates(centerline2d, obj.pose.translation());
82  BasicPoint2d pAt = geometry::interpolatedPointAtDistance(centerline2d, closestOnCenter.length);
83  BasicPoint2d pBefore =
84  geometry::interpolatedPointAtDistance(centerline2d, std::max(closestOnCenter.length - 0.5, 0.));
85  BasicPoint2d pAfter = geometry::interpolatedPointAtDistance(centerline2d, closestOnCenter.length + 0.5);
86  BasicPoint2d pDirection = pAfter - pBefore;
87 
88  double yawCenter = normalizeAngleRadians(std::atan2(pDirection.y(), pDirection.x()));
89  double yawObj = normalizeAngleRadians(yawFromIsometry2d(obj.pose));
90  double yawDiff = angleDifference(yawCenter, yawObj);
91 
92  // using approximation orientationCovariance = 1./obj.vonMisesKappa
93  double mahaDistYawSq = (yawDiff * yawDiff) * (obj.vonMisesKappa * obj.vonMisesKappa);
94 
95  BasicPoint2d pDiff = obj.pose.translation() - pAt;
96  double mahaDistPosSq = pDiff.transpose() * obj.positionCovariance.inverse() * pDiff;
97 
98  return mahaDistYawSq + mahaDistPosSq;
99 }
100 
101 } // namespace utils
102 } // namespace matching
103 } // namespace lanelet
traits::BasicPointT< traits::PointType< LineStringT > > interpolatedPointAtDistance(LineStringT lineString, double dist)
Pose2d pose
Pose of the object in map coordinates.
Definition: Types.h:55
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
Thrown when matching is not possible.
Definition: Exceptions.h:43
ConstLineString3d centerline() const
double vonMisesKappa
kappa as defined in https://en.wikipedia.org/wiki/Von_Mises_distribution
Definition: Types.h:61
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
PositionCovariance2d positionCovariance
Definition: Types.h:60
ArcCoordinates toArcCoordinates(const LineString2dT &lineString, const BasicPoint2d &point)


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