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);
61 const double ry,
const double rtheta,
62 const double x,
const double y,
double* ptr_s,
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,
80 static double CalculateTheta(
const double rtheta,
const double rkappa,
81 const double l,
const double dl);
83 static double CalculateKappa(
const double rkappa,
const double rdkappa,
84 const double l,
const double dl,
94 const double theta,
const double l,
95 const double kappa_ref);
99 const double theta_ref,
const double theta,
const double kappa_ref,
100 const double kappa,
const double dkappa_ref,
const double l);
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)
CartesianFrenetConverter()=delete
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.