Go to the documentation of this file.
19 #ifndef GEOMETRY__COMMON_2D_HPP_
20 #define GEOMETRY__COMMON_2D_HPP_
40 namespace point_adapter
46 template<
typename Po
intT>
47 inline auto x_(
const PointT & pt)
55 template<
typename Po
intT>
56 inline auto y_(
const PointT & pt)
64 template<
typename Po
intT>
65 inline auto z_(
const PointT & pt)
73 template<
typename Po
intT>
74 inline auto &
xr_(PointT & pt)
82 template<
typename Po
intT>
83 inline auto &
yr_(PointT & pt)
91 template<
typename Po
intT>
92 inline auto &
zr_(PointT & pt)
104 template<
typename T1,
typename T2,
typename T3>
105 inline auto ccw(
const T1 & pt,
const T2 & q,
const T3 & r)
109 return (((
x_(q) -
x_(pt)) * (
y_(r) -
y_(pt))) - ((
y_(q) -
y_(pt)) * (
x_(r) -
x_(pt)))) <= 0.0F;
117 template<
typename T1,
typename T2>
122 return (
x_(pt) *
y_(q)) - (
y_(pt) *
x_(q));
130 template<
typename T1,
typename T2>
131 inline auto dot_2d(
const T1 & pt,
const T2 & q)
135 return (
x_(pt) *
x_(q)) + (
y_(pt) *
y_(q));
215 constexpr
auto FEPS = std::numeric_limits<float32_t>::epsilon();
216 if (fabsf(den) <
FEPS) {
217 if (fabsf(num) <
FEPS) {
222 throw std::runtime_error(
223 "intersection_2d: no unique solution (either collinear or parallel)");
280 return sqrtf(
dot_2d(pt, pt));
297 if (len2 > std::numeric_limits<float32_t>::epsilon()) {
321 if (len2 > std::numeric_limits<float32_t>::epsilon()) {
325 throw std::runtime_error(
326 "closet_line_point_2d: line ill-defined because given points coincide");
361 #endif // GEOMETRY__COMMON_2D_HPP_
T times_2d(const T &p, const float32_t a)
The scalar multiplication operation, p * a.
Definition: common_2d.hpp:192
T get_normal(const T &pt)
compute q s.t. p T q, or p * q = 0 This is the equivalent of a 90 degree ccw rotation
Definition: common_2d.hpp:265
auto cross_2d(const T1 &pt, const T2 &q)
compute p x q = p1 * q2 - p2 * q1
Definition: common_2d.hpp:118
T
Definition: catr_diff.py:22
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:47
This file includes common type definition.
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
t
Definition: catr_diff.py:22
DifferentialState u
Definition: kinematic_bicycle.snippet.hpp:29
T closest_line_point_2d(const T &p, const T &q, const T &r)
Compute the closest point on the line going through p-q to point r.
Definition: common_2d.hpp:316
static T clamp_to(const Interval &i, T val)
Clamp a scalar 'val' onto 'interval'.
Definition: interval.hpp:345
auto dot_2d(const T1 &pt, const T2 &q)
compute p * q = p1 * q1 + p2 * q2
Definition: common_2d.hpp:131
T plus_2d(const T &p, const T &q)
The 2d addition operation, p + q.
Definition: common_2d.hpp:175
DifferentialEquation f
Definition: kinematic_bicycle.snippet.hpp:44
bool bool8_t
Definition: types.hpp:33
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
auto point_line_segment_distance_2d(const T &p, const T &q, const T &r)
Compute the distance from line segment p-q to point r.
Definition: common_2d.hpp:338
auto & yr_(PointT &pt)
Gets a reference to the y value for a point.
Definition: common_2d.hpp:83
constexpr float32_t FEPS
arbitrary small constant: 1.0E-6F
Definition: types.hpp:46
auto norm_2d(const T &pt)
get magnitude of x and y components:
Definition: common_2d.hpp:278
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
T closest_segment_point_2d(const T &p, const T &q, const T &r)
Compute the closest point on line segment p-q to point r Based on equations from https://stackoverflo...
Definition: common_2d.hpp:292
a
Definition: catr_diff.py:22
float float32_t
Definition: types.hpp:36
auto & xr_(PointT &pt)
Gets a reference to the x value for a point.
Definition: common_2d.hpp:74
T minus_2d(const T &p, const T &q)
Compute the 2d difference between two points, p - q.
Definition: common_2d.hpp:145
void rotate_2d(T &pt, const float32_t cos_th, const float32_t sin_th)
rotate point given precomputed sin and cos
Definition: common_2d.hpp:236
T intersection_2d(const T &pt, const T &u, const T &q, const T &v)
solve p + t * u = q + s * v Ref: https://stackoverflow.com/questions/563198/ whats-the-most-efficent-...
Definition: common_2d.hpp:211
T make_unit_vector2d(float th)
Make a 2D unit vector given an angle.
Definition: common_2d.hpp:349
auto y_(const PointT &pt)
Gets the y value for a point.
Definition: common_2d.hpp:56
auto z_(const PointT &pt)
Gets the z value for a point.
Definition: common_2d.hpp:65
auto ccw(const T1 &pt, const T2 &q, const T3 &r)
compute whether line segment rp is counter clockwise relative to line segment qp
Definition: common_2d.hpp:105
auto & zr_(PointT &pt)
Gets a reference to the z value for a point.
Definition: common_2d.hpp:92
Data structure to contain scalar interval bounds.
Definition: interval.hpp:52
DifferentialState v
Definition: linear_tire.snippet.hpp:28
th
Definition: catr_diff.py:22