Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
Geometry.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <exception>
20#include <tuple>
21#include <lanelet2_core/primitives/Lanelet.h>
22#include <lanelet2_core/primitives/Point.h>
23#include <lanelet2_core/primitives/Polygon.h>
24#include <lanelet2_core/utility/Optional.h>
25#include <geometry_msgs/msg/pose.hpp>
26#include <geometry_msgs/msg/vector3.hpp>
27#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
28#include <tf2/LinearMath/Quaternion.h>
29#include <tf2/LinearMath/Matrix3x3.h>
30#include <carma_wm/TrackPos.hpp>
31
32namespace carma_wm
33{
38namespace geometry
39{
54TrackPos trackPos(const lanelet::ConstLanelet& lanelet, const lanelet::BasicPoint2d& point);
55
65TrackPos trackPos(const lanelet::BasicPoint2d& p, const lanelet::BasicPoint2d& seg_start,
66 const lanelet::BasicPoint2d& seg_end);
88std::tuple<TrackPos, lanelet::BasicSegment2d> matchSegment(const lanelet::BasicPoint2d& p,
89 const lanelet::BasicLineString2d& line_string);
90
113std::vector<double> local_curvatures(const lanelet::BasicLineString2d& centerline_points);
114
115std::vector<double> local_curvatures(const std::vector<lanelet::BasicPoint2d>& centerline_points);
116
124std::vector<double> local_curvatures(const std::vector<lanelet::ConstLanelet>& lanelets);
125
130lanelet::BasicLineString2d concatenate_line_strings(const lanelet::BasicLineString2d& l1,
131 const lanelet::BasicLineString2d& l2);
132
137lanelet::BasicLineString2d concatenate_lanelets(const std::vector<lanelet::ConstLanelet>& lanelets);
138
148std::vector<Eigen::Vector2d> compute_finite_differences(const lanelet::BasicLineString2d& data);
149
150std::vector<Eigen::Vector2d> compute_finite_differences(const std::vector<lanelet::BasicPoint2d>& data);
151
161std::vector<double> compute_finite_differences(const std::vector<double>& data);
162
175std::vector<Eigen::Vector2d> compute_finite_differences(const std::vector<Eigen::Vector2d>& x,
176 const std::vector<double>& y);
177
181std::vector<double> compute_arc_lengths(const std::vector<lanelet::BasicPoint2d>& data);
182
186std::vector<double> compute_arc_lengths(const lanelet::BasicLineString2d& data);
187
191double compute_euclidean_distance(const Eigen::Vector2d& a, const Eigen::Vector2d& b);
192
196std::vector<Eigen::Vector2d> normalize_vectors(const std::vector<Eigen::Vector2d>& vectors);
197
201std::vector<double> compute_magnitude_of_vectors(const std::vector<Eigen::Vector2d>& vectors);
202
217[[deprecated("computeCurvature is deprecated in favor of using the finite differences-based computeLocalCurvature for "
218 "large curves")]] double
219computeCurvature(const lanelet::BasicPoint2d& p1, const lanelet::BasicPoint2d& p2, const lanelet::BasicPoint2d& p3);
220
231double safeAcos(double x);
232
243double safeAsin(double x);
244
253double getAngleBetweenVectors(const Eigen::Vector2d& vec1, const Eigen::Vector2d& vec2);
254
265lanelet::BasicPolygon2d objectToMapPolygon(const geometry_msgs::msg::Pose& pose, const geometry_msgs::msg::Vector3& size);
266
276void rpyFromQuaternion(const tf2::Quaternion& q, double& roll, double& pitch, double& yaw);
277
287void rpyFromQuaternion(const geometry_msgs::msg::Quaternion& q_msg, double& roll, double& pitch, double& yaw);
288
301std::vector<double> compute_tangent_orientations(const lanelet::BasicLineString2d& centerline);
302
303std::vector<double> compute_tangent_orientations(const std::vector<lanelet::BasicPoint2d>& centerline);
304
316Eigen::Isometry2d build2dEigenTransform(const Eigen::Vector2d& position, const Eigen::Rotation2Dd& rotation);
317
329Eigen::Isometry3d build3dEigenTransform(const Eigen::Vector3d& position, const Eigen::Quaterniond& rotation);
330
331Eigen::Isometry3d build3dEigenTransform(const Eigen::Vector3d& position, const Eigen::AngleAxisd& rotation);
332
341double point_to_point_yaw(const lanelet::BasicPoint2d& cur_point, const lanelet::BasicPoint2d& next_point);
342
353double circular_arc_curvature(const lanelet::BasicPoint2d& cur_point, const lanelet::BasicPoint2d& next_point);
354
366std::vector<double> local_circular_arc_curvatures(const std::vector<lanelet::BasicPoint2d>& points, int lookahead);
367
368} // namespace geometry
369
370} // namespace carma_wm
Position in a track based coordinate system where the axis are downtrack and crosstrack....
Definition: TrackPos.hpp:35
Eigen::Isometry3d build3dEigenTransform(const Eigen::Vector3d &position, const Eigen::Quaterniond &rotation)
Builds a 3D Eigen coordinate frame transform with not applied scaling (only translation and rotation)...
Definition: Geometry.cpp:576
lanelet::BasicPolygon2d objectToMapPolygon(const geometry_msgs::msg::Pose &pose, const geometry_msgs::msg::Vector3 &size)
Uses the provided pose and size vector of an ExternalObject to compute what the polygon would be of t...
Definition: Geometry.cpp:289
std::vector< double > local_curvatures(const lanelet::BasicLineString2d &centerline_points)
Returns a list of local (computed by discrete derivative) curvatures for the input centerlines....
Definition: Geometry.cpp:356
void rpyFromQuaternion(const tf2::Quaternion &q, double &roll, double &pitch, double &yaw)
Extract extrinsic roll-pitch-yaw from quaternion.
Definition: Geometry.cpp:52
double safeAcos(double x)
acos method that caps the input x value for 1 or -1 to avoid undefined output. This is meant to preve...
Definition: Geometry.cpp:34
std::vector< Eigen::Vector2d > normalize_vectors(const std::vector< Eigen::Vector2d > &vectors)
Normalize the vectors in the input list such that their magnitudes = 1.
Definition: Geometry.cpp:510
double point_to_point_yaw(const lanelet::BasicPoint2d &cur_point, const lanelet::BasicPoint2d &next_point)
Computes the 2d orientation of the vector from the provided start point to end point.
Definition: Geometry.cpp:588
double circular_arc_curvature(const lanelet::BasicPoint2d &cur_point, const lanelet::BasicPoint2d &next_point)
Computes the curvature of a circular arc that passes through the two provided points....
Definition: Geometry.cpp:596
double compute_euclidean_distance(const Eigen::Vector2d &a, const Eigen::Vector2d &b)
Compute the Euclidean distance between the two points.
Definition: Geometry.cpp:504
Eigen::Isometry2d build2dEigenTransform(const Eigen::Vector2d &position, const Eigen::Rotation2Dd &rotation)
Builds a 2D Eigen coordinate frame transform with not applied scaling (only translation and rotation)...
Definition: Geometry.cpp:570
std::tuple< TrackPos, lanelet::BasicSegment2d > matchSegment(const lanelet::BasicPoint2d &p, const lanelet::BasicLineString2d &line_string)
Get the TrackPos of the provided point along the linestring and the segment of the line string which ...
Definition: Geometry.cpp:187
double safeAsin(double x)
asin method that caps the input x value for 1 or -1 to avoid undefined output. This is meant to preve...
Definition: Geometry.cpp:45
double getAngleBetweenVectors(const Eigen::Vector2d &vec1, const Eigen::Vector2d &vec2)
Calculates the angle between two vectors.
Definition: Geometry.cpp:65
std::vector< double > compute_tangent_orientations(const lanelet::BasicLineString2d &centerline)
Compute an approximate orientation for the vehicle at each point along the provided centerline.
Definition: Geometry.cpp:559
lanelet::BasicLineString2d concatenate_lanelets(const std::vector< lanelet::ConstLanelet > &lanelets)
Helper function to a list of lanelets together and return the result. Neither LineString is modified ...
Definition: Geometry.cpp:316
std::vector< double > compute_arc_lengths(const std::vector< lanelet::BasicPoint2d > &data)
Compute the arc length at each point around the curve.
Definition: Geometry.cpp:498
lanelet::BasicLineString2d concatenate_line_strings(const lanelet::BasicLineString2d &l1, const lanelet::BasicLineString2d &l2)
Helper function to concatenate 2 linestrings together and return the result. Neither LineString is mo...
Definition: Geometry.cpp:373
double computeCurvature(const lanelet::BasicPoint2d &p1, const lanelet::BasicPoint2d &p2, const lanelet::BasicPoint2d &p3)
Function for computing curvature from 3 points.
Definition: Geometry.cpp:276
TrackPos trackPos(const lanelet::ConstLanelet &lanelet, const lanelet::BasicPoint2d &point)
Returns the TrackPos, computed in 2d, of the provided point relative to the centerline of the provide...
Definition: Geometry.cpp:120
std::vector< double > local_circular_arc_curvatures(const std::vector< lanelet::BasicPoint2d > &points, int lookahead)
Computes the curvature of each point in the provided list by calling circular_arc_curvature using tha...
Definition: Geometry.cpp:610
std::vector< Eigen::Vector2d > compute_finite_differences(const lanelet::BasicLineString2d &data)
Use finite differences methods to compute the derivative of the input data set with respect to index ...
Definition: Geometry.cpp:419
std::vector< double > compute_magnitude_of_vectors(const std::vector< Eigen::Vector2d > &vectors)
Compute the magnitude of each vector in the input list.
Definition: Geometry.cpp:520