31 #include "Utilities.h" 33 #include <lanelet2_core/geometry/Lanelet.h> 34 #include <lanelet2_core/geometry/Polygon.h> 42 double positiveFloatModulo(
double x,
double y) {
43 double fmod = std::fmod(x, y);
47 double fmodPositive = fmod + std::abs(y);
48 assert(fmodPositive > 0.);
53 double normalizeAngleRadians(
double x) {
return positiveFloatModulo((x + M_PI), 2.0 * M_PI) - M_PI; }
56 double angleDifference(
double targetAngle,
double sourceAngle) {
57 double angleDiff = targetAngle - sourceAngle;
58 return normalizeAngleRadians(angleDiff);
62 double yawFromIsometry2d(
const Eigen::Isometry2d& pose) {
63 Eigen::Rotation2D<double> rot;
64 rot.fromRotationMatrix(pose.linear());
65 return rot.smallestAngle();
80 auto centerline2d = lanelet::utils::to2D(lanelet.
centerline());
88 double yawCenter = normalizeAngleRadians(std::atan2(pDirection.y(), pDirection.x()));
89 double yawObj = normalizeAngleRadians(yawFromIsometry2d(obj.
pose));
90 double yawDiff = angleDifference(yawCenter, yawObj);
98 return mahaDistYawSq + mahaDistPosSq;
traits::BasicPointT< traits::PointType< LineStringT > > interpolatedPointAtDistance(LineStringT lineString, double dist)
Pose2d pose
Pose of the object in map coordinates.
double getMahalanobisDistSq(const ConstLanelet &lanelet, const ObjectWithCovariance2d &obj)
Compute squared mahalanobis distance based on pose and covariance, hull is not used.
Thrown when matching is not possible.
ConstLineString3d centerline() const
double vonMisesKappa
kappa as defined in https://en.wikipedia.org/wiki/Von_Mises_distribution
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
PositionCovariance2d positionCovariance
ArcCoordinates toArcCoordinates(const LineString2dT &lineString, const BasicPoint2d &point)