Apollo 10.0
自动驾驶开放平台
cartesian_frenet_conversion.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
21#pragma once
22
23#include <array>
24
26
27namespace apollo {
28namespace common {
29namespace math {
30
31// Notations:
32// s_condition = [s, s_dot, s_ddot]
33// s: longitudinal coordinate w.r.t reference line.
34// s_dot: ds / dt
35// s_ddot: d(s_dot) / dt
36// d_condition = [d, d_prime, d_pprime]
37// d: lateral coordinate w.r.t. reference line
38// d_prime: dd / ds
39// d_pprime: d(d_prime) / ds
40// l: the same as d.
42 public:
51 static void cartesian_to_frenet(const double rs, const double rx,
52 const double ry, const double rtheta,
53 const double rkappa, const double rdkappa,
54 const double x, const double y,
55 const double v, const double a,
56 const double theta, const double kappa,
57 std::array<double, 3>* const ptr_s_condition,
58 std::array<double, 3>* const ptr_d_condition);
59
60 static void cartesian_to_frenet(const double rs, const double rx,
61 const double ry, const double rtheta,
62 const double x, const double y, double* ptr_s,
63 double* ptr_d);
64
69 static void frenet_to_cartesian(const double rs, const double rx,
70 const double ry, const double rtheta,
71 const double rkappa, const double rdkappa,
72 const std::array<double, 3>& s_condition,
73 const std::array<double, 3>& d_condition,
74 double* const ptr_x, double* const ptr_y,
75 double* const ptr_theta,
76 double* const ptr_kappa, double* const ptr_v,
77 double* const ptr_a);
78
79 // given sl point extract x, y, theta, kappa
80 static double CalculateTheta(const double rtheta, const double rkappa,
81 const double l, const double dl);
82
83 static double CalculateKappa(const double rkappa, const double rdkappa,
84 const double l, const double dl,
85 const double ddl);
86
87 static Vec2d CalculateCartesianPoint(const double rtheta, const Vec2d& rpoint,
88 const double l);
93 static double CalculateLateralDerivative(const double theta_ref,
94 const double theta, const double l,
95 const double kappa_ref);
96
97 // given sl, theta, and road's theta, kappa, extract second order derivative
99 const double theta_ref, const double theta, const double kappa_ref,
100 const double kappa, const double dkappa_ref, const double l);
101};
102
103} // namespace math
104} // namespace common
105} // namespace apollo
static void frenet_to_cartesian(const double rs, const double rx, const double ry, const double rtheta, const double rkappa, const double rdkappa, const std::array< double, 3 > &s_condition, const std::array< double, 3 > &d_condition, double *const ptr_x, double *const ptr_y, double *const ptr_theta, double *const ptr_kappa, double *const ptr_v, double *const ptr_a)
Convert a vehicle state in Frenet frame to Cartesian frame.
static void cartesian_to_frenet(const double rs, const double rx, const double ry, const double rtheta, const double rkappa, const double rdkappa, const double x, const double y, const double v, const double a, const double theta, const double kappa, std::array< double, 3 > *const ptr_s_condition, std::array< double, 3 > *const ptr_d_condition)
Convert a vehicle state in Cartesian frame to Frenet frame.
static Vec2d CalculateCartesianPoint(const double rtheta, const Vec2d &rpoint, const double l)
static double CalculateSecondOrderLateralDerivative(const double theta_ref, const double theta, const double kappa_ref, const double kappa, const double dkappa_ref, const double l)
static double CalculateTheta(const double rtheta, const double rkappa, const double l, const double dl)
static double CalculateLateralDerivative(const double theta_ref, const double theta, const double l, const double kappa_ref)
: given sl, theta, and road's theta, kappa, extract derivative l, second order derivative l:
static double CalculateKappa(const double rkappa, const double rdkappa, const double l, const double dl, const double ddl)
Implements a class of 2-dimensional vectors.
Definition vec2d.h:42
class register implement
Definition arena_queue.h:37
Defines the Vec2d class.