Apollo  6.0
Open source self driving car software
Classes | Typedefs | Functions | Variables
apollo::common::math Namespace Reference

apollo::common::math More...

Classes

class  AABox2d
 Implements a class of (undirected) axes-aligned bounding boxes in 2-D. This class is referential-agnostic. More...
 
class  AABoxKDTree2d
 The class of KD-tree of Aligned Axis Bounding Box(AABox). More...
 
class  AABoxKDTree2dNode
 The class of KD-tree node of axis-aligned bounding box. More...
 
class  AABoxKDTreeParams
 Contains parameters of axis-aligned bounding box. More...
 
class  Angle
 The Angle class uses an integer to represent an angle, and supports commonly-used operations such as addition and subtraction, as well as the use of trigonometric functions. More...
 
class  Box2d
 Rectangular (undirected) bounding box in 2-D. More...
 
class  CartesianFrenetConverter
 
class  EulerAnglesZXY
 Implements a class of Euler angles (actually, Tait-Bryan angles), with intrinsic sequence ZXY. More...
 
struct  Factorial
 
struct  Factorial< 0 >
 
class  HermiteSpline
 
class  KalmanFilter
 Implements a discrete-time Kalman filter. More...
 
class  LineSegment2d
 Line segment in 2-D. More...
 
class  MpcOsqp
 
class  PathMatcher
 
class  Polygon2d
 The class of polygon in 2-D. More...
 
class  QpSolver
 
class  Vec2d
 Implements a class of 2-dimensional vectors. More...
 

Typedefs

using Angle8 = Angle< int8_t >
 
using Angle16 = Angle< int16_t >
 
using Angle32 = Angle< int32_t >
 
using Angle64 = Angle< int64_t >
 
using EulerAnglesZXYf = EulerAnglesZXY< float >
 
using EulerAnglesZXYd = EulerAnglesZXY< double >
 

Functions

template<typename T >
Angle< T > operator+ (Angle< T > lhs, Angle< T > rhs)
 Sums two angles. More...
 
template<typename T >
Angle< T > operator- (Angle< T > lhs, Angle< T > rhs)
 Subtracts two angles. More...
 
template<typename T , typename Scalar >
Angle< T > operator* (Angle< T > lhs, Scalar rhs)
 Multiplies an Angle by a scalar. More...
 
template<typename T , typename Scalar >
Angle< T > operator* (Scalar lhs, Angle< T > rhs)
 Multiplies an Angle by a scalar. More...
 
template<typename T , typename Scalar >
Angle< T > operator/ (Angle< T > lhs, Scalar rhs)
 Divides an Angle by a scalar. More...
 
template<typename T >
double operator/ (Angle< T > lhs, Angle< T > rhs)
 Divides an Angle by a scalar. More...
 
template<typename T >
bool operator== (Angle< T > lhs, Angle< T > rhs)
 Tests two Angle objects for equality. More...
 
template<typename T >
bool operator!= (Angle< T > lhs, Angle< T > rhs)
 Tests two Angle objects for inequality. More...
 
float sin (Angle16 a)
 
float cos (Angle16 a)
 
float tan (Angle16 a)
 
float sin (Angle8 a)
 
float cos (Angle8 a)
 
float tan (Angle8 a)
 
template<std::size_t N>
double EvaluatePolynomial (const std::array< double, N+1 > &coef, const double p)
 
template<std::size_t N, std::size_t M>
std::array< double, N+1 > FitPolynomial (const std::array< Eigen::Vector2d, M > &points, double *ptr_error_square=nullptr)
 
double IntegrateBySimpson (const std::vector< double > &funv_vec, const double dx, const std::size_t nsteps)
 
double IntegrateByTrapezoidal (const std::vector< double > &funv_vec, const double dx, const std::size_t nsteps)
 
template<std::size_t N>
std::pair< std::array< double, N >, std::array< double, N > > GetGaussLegendrePoints ()
 Get the points and weights for different ordered Gauss-Legendre integration. Currently support order 2 - 10. Other input order will trigger compiling error. More...
 
template<>
std::pair< std::array< double, 2 >, std::array< double, 2 > > GetGaussLegendrePoints< 2 > ()
 
template<>
std::pair< std::array< double, 3 >, std::array< double, 3 > > GetGaussLegendrePoints< 3 > ()
 
template<>
std::pair< std::array< double, 4 >, std::array< double, 4 > > GetGaussLegendrePoints< 4 > ()
 
template<>
std::pair< std::array< double, 5 >, std::array< double, 5 > > GetGaussLegendrePoints< 5 > ()
 
template<>
std::pair< std::array< double, 6 >, std::array< double, 6 > > GetGaussLegendrePoints< 6 > ()
 
template<>
std::pair< std::array< double, 7 >, std::array< double, 7 > > GetGaussLegendrePoints< 7 > ()
 
template<>
std::pair< std::array< double, 8 >, std::array< double, 8 > > GetGaussLegendrePoints< 8 > ()
 
template<>
std::pair< std::array< double, 9 >, std::array< double, 9 > > GetGaussLegendrePoints< 9 > ()
 
template<>
std::pair< std::array< double, 10 >, std::array< double, 10 > > GetGaussLegendrePoints< 10 > ()
 
template<std::size_t N>
double IntegrateByGaussLegendre (const std::function< double(double)> &func, const double lower_bound, const double upper_bound)
 Compute the integral of a target single-variable function from a lower bound to an upper bound, by 5-th Gauss-Legendre method Given a target function and integral lower and upper bound, compute the integral approximation using 5th order Gauss-Legendre integration. The target function must be a smooth function. Example: target function: auto func = [](const double x) {return x * x;}; double integral = gauss_legendre(func, -2, 3); This gives you the approximated integral of function x^2 in bound [-2, 3]. More...
 
template<typename T >
lerp (const T &x0, const double t0, const T &x1, const double t1, const double t)
 Linear interpolation between two points of type T. More...
 
double slerp (const double a0, const double t0, const double a1, const double t1, const double t)
 Spherical linear interpolation between two angles. The two angles are within range [-M_PI, M_PI). More...
 
SLPoint InterpolateUsingLinearApproximation (const SLPoint &p0, const SLPoint &p1, const double w)
 
PathPoint InterpolateUsingLinearApproximation (const PathPoint &p0, const PathPoint &p1, const double s)
 
TrajectoryPoint InterpolateUsingLinearApproximation (const TrajectoryPoint &tp0, const TrajectoryPoint &tp1, const double t)
 
void SolveLQRProblem (const Eigen::MatrixXd &A, const Eigen::MatrixXd &B, const Eigen::MatrixXd &Q, const Eigen::MatrixXd &R, const Eigen::MatrixXd &M, const double tolerance, const uint max_num_iteration, Eigen::MatrixXd *ptr_K)
 Solver for discrete-time linear quadratic problem. More...
 
void SolveLQRProblem (const Eigen::MatrixXd &A, const Eigen::MatrixXd &B, const Eigen::MatrixXd &Q, const Eigen::MatrixXd &R, const double tolerance, const uint max_num_iteration, Eigen::MatrixXd *ptr_K)
 Solver for discrete-time linear quadratic problem. More...
 
double Sqr (const double x)
 
double CrossProd (const Vec2d &start_point, const Vec2d &end_point_1, const Vec2d &end_point_2)
 Cross product between two 2-D vectors from the common start point, and end at two other points. More...
 
double InnerProd (const Vec2d &start_point, const Vec2d &end_point_1, const Vec2d &end_point_2)
 Inner product between two 2-D vectors from the common start point, and end at two other points. More...
 
double CrossProd (const double x0, const double y0, const double x1, const double y1)
 Cross product between two vectors. One vector is formed by 1st and 2nd parameters of the function. The other vector is formed by 3rd and 4th parameters of the function. More...
 
double InnerProd (const double x0, const double y0, const double x1, const double y1)
 Inner product between two vectors. One vector is formed by 1st and 2nd parameters of the function. The other vector is formed by 3rd and 4th parameters of the function. More...
 
double WrapAngle (const double angle)
 Wrap angle to [0, 2 * PI). More...
 
double NormalizeAngle (const double angle)
 Normalize angle to [-PI, PI). More...
 
double AngleDiff (const double from, const double to)
 Calculate the difference between angle from and to. More...
 
int RandomInt (const int s, const int t, unsigned int rand_seed=1)
 Get a random integer between two integer values by a random seed. More...
 
double RandomDouble (const double s, const double t, unsigned int rand_seed=1)
 Get a random double between two integer values by a random seed. More...
 
template<typename T >
Square (const T value)
 Compute squared value. More...
 
template<typename T >
Clamp (const T value, T bound1, T bound2)
 Clamp a value between two bounds. If the value goes beyond the bounds, return one of the bounds, otherwise, return the original value. More...
 
double Gaussian (const double u, const double std, const double x)
 
double Sigmoid (const double x)
 
Eigen::Vector2d RotateVector2d (const Eigen::Vector2d &v_in, const double theta)
 
std::pair< double, double > RFUToFLU (const double x, const double y)
 
std::pair< double, double > FLUToRFU (const double x, const double y)
 
void L2Norm (int feat_dim, float *feat_data)
 
std::pair< double, double > Cartesian2Polar (double x, double y)
 
template<class T >
std::enable_if<!std::numeric_limits< T >::is_integer, bool >::type almost_equal (T x, T y, int ulp)
 
template<typename T , unsigned int N>
Eigen::Matrix< T, N, N > PseudoInverse (const Eigen::Matrix< T, N, N > &m, const double epsilon=1.0e-6)
 Computes the Moore-Penrose pseudo-inverse of a given square matrix, rounding all eigenvalues with absolute value bounded by epsilon to zero. More...
 
template<typename T , unsigned int M, unsigned int N>
Eigen::Matrix< T, N, M > PseudoInverse (const Eigen::Matrix< T, M, N > &m, const double epsilon=1.0e-6)
 Computes the Moore-Penrose pseudo-inverse of a given matrix, rounding all eigenvalues with absolute value bounded by epsilon to zero. More...
 
template<typename T , unsigned int L, unsigned int N, unsigned int O>
bool ContinuousToDiscrete (const Eigen::Matrix< T, L, L > &m_a, const Eigen::Matrix< T, L, N > &m_b, const Eigen::Matrix< T, O, L > &m_c, const Eigen::Matrix< T, O, N > &m_d, const double ts, Eigen::Matrix< T, L, L > *ptr_a_d, Eigen::Matrix< T, L, N > *ptr_b_d, Eigen::Matrix< T, O, L > *ptr_c_d, Eigen::Matrix< T, O, N > *ptr_d_d)
 Computes bilinear transformation of the continuous to discrete form for state space representation This assumes equation format of. More...
 
bool ContinuousToDiscrete (const Eigen::MatrixXd &m_a, const Eigen::MatrixXd &m_b, const Eigen::MatrixXd &m_c, const Eigen::MatrixXd &m_d, const double ts, Eigen::MatrixXd *ptr_a_d, Eigen::MatrixXd *ptr_b_d, Eigen::MatrixXd *ptr_c_d, Eigen::MatrixXd *ptr_d_d)
 
template<typename T , int M, int N, typename D >
void DenseToCSCMatrix (const Eigen::Matrix< T, M, N > &dense_matrix, std::vector< T > *data, std::vector< D > *indices, std::vector< D > *indptr)
 
double QuaternionToHeading (const double qw, const double qx, const double qy, const double qz)
 
template<typename T >
QuaternionToHeading (const Eigen::Quaternion< T > &q)
 
template<typename T >
Eigen::Quaternion< T > HeadingToQuaternion (T heading)
 
Eigen::Vector3d QuaternionRotate (const Quaternion &orientation, const Eigen::Vector3d &original)
 
Eigen::Vector3d InverseQuaternionRotate (const Quaternion &orientation, const Eigen::Vector3d &rotated)
 
double GoldenSectionSearch (const std::function< double(double)> &func, const double lower_bound, const double upper_bound, const double tol=1e-6)
 Given a unimodal function defined on the interval, find a value on the interval to minimize the function. Reference: https://en.wikipedia.org/wiki/Golden-section_search. More...
 
Vec2d operator* (const double ratio, const Vec2d &vec)
 Multiplies the given Vec2d by a given scalar. More...
 

Variables

const float SIN_TABLE [SIN_TABLE_SIZE]
 
constexpr double kMathEpsilon = 1e-10
 

Detailed Description

apollo::common::math

The math namespace deals with a number of useful mathematical objects.

Typedef Documentation

◆ Angle16

using apollo::common::math::Angle16 = typedef Angle<int16_t>

◆ Angle32

using apollo::common::math::Angle32 = typedef Angle<int32_t>

◆ Angle64

using apollo::common::math::Angle64 = typedef Angle<int64_t>

◆ Angle8

using apollo::common::math::Angle8 = typedef Angle<int8_t>

◆ EulerAnglesZXYd

◆ EulerAnglesZXYf

Function Documentation

◆ almost_equal()

template<class T >
std::enable_if<!std::numeric_limits<T>::is_integer, bool>::type apollo::common::math::almost_equal ( x,
y,
int  ulp 
)

◆ AngleDiff()

double apollo::common::math::AngleDiff ( const double  from,
const double  to 
)

Calculate the difference between angle from and to.

Parameters
fromthe start angle
fromthe end angle
Returns
The difference between from and to. The range is between [-PI, PI).

◆ Cartesian2Polar()

std::pair<double, double> apollo::common::math::Cartesian2Polar ( double  x,
double  y 
)

◆ Clamp()

template<typename T >
T apollo::common::math::Clamp ( const T  value,
bound1,
bound2 
)

Clamp a value between two bounds. If the value goes beyond the bounds, return one of the bounds, otherwise, return the original value.

Parameters
valueThe original value to be clamped.
bound1One bound to clamp the value.
bound2The other bound to clamp the value.
Returns
The clamped value.

◆ ContinuousToDiscrete() [1/2]

template<typename T , unsigned int L, unsigned int N, unsigned int O>
bool apollo::common::math::ContinuousToDiscrete ( const Eigen::Matrix< T, L, L > &  m_a,
const Eigen::Matrix< T, L, N > &  m_b,
const Eigen::Matrix< T, O, L > &  m_c,
const Eigen::Matrix< T, O, N > &  m_d,
const double  ts,
Eigen::Matrix< T, L, L > *  ptr_a_d,
Eigen::Matrix< T, L, N > *  ptr_b_d,
Eigen::Matrix< T, O, L > *  ptr_c_d,
Eigen::Matrix< T, O, N > *  ptr_d_d 
)

Computes bilinear transformation of the continuous to discrete form for state space representation This assumes equation format of.

dot_x = Ax + Bu y = Cx + Du

Parameters
m_a,m_b,m_c,m_dare the state space matrix control matrix
Returns
true or false.

◆ ContinuousToDiscrete() [2/2]

bool apollo::common::math::ContinuousToDiscrete ( const Eigen::MatrixXd &  m_a,
const Eigen::MatrixXd &  m_b,
const Eigen::MatrixXd &  m_c,
const Eigen::MatrixXd &  m_d,
const double  ts,
Eigen::MatrixXd *  ptr_a_d,
Eigen::MatrixXd *  ptr_b_d,
Eigen::MatrixXd *  ptr_c_d,
Eigen::MatrixXd *  ptr_d_d 
)

◆ cos() [1/2]

float apollo::common::math::cos ( Angle16  a)

◆ cos() [2/2]

float apollo::common::math::cos ( Angle8  a)

◆ CrossProd() [1/2]

double apollo::common::math::CrossProd ( const Vec2d start_point,
const Vec2d end_point_1,
const Vec2d end_point_2 
)

Cross product between two 2-D vectors from the common start point, and end at two other points.

Parameters
start_pointThe common start point of two vectors in 2-D.
end_point_1The end point of the first vector.
end_point_2The end point of the second vector.
Returns
The cross product result.

◆ CrossProd() [2/2]

double apollo::common::math::CrossProd ( const double  x0,
const double  y0,
const double  x1,
const double  y1 
)

Cross product between two vectors. One vector is formed by 1st and 2nd parameters of the function. The other vector is formed by 3rd and 4th parameters of the function.

Parameters
x0The x coordinate of the first vector.
y0The y coordinate of the first vector.
x1The x coordinate of the second vector.
y1The y coordinate of the second vector.
Returns
The cross product result.

◆ DenseToCSCMatrix()

template<typename T , int M, int N, typename D >
void apollo::common::math::DenseToCSCMatrix ( const Eigen::Matrix< T, M, N > &  dense_matrix,
std::vector< T > *  data,
std::vector< D > *  indices,
std::vector< D > *  indptr 
)

◆ EvaluatePolynomial()

template<std::size_t N>
double apollo::common::math::EvaluatePolynomial ( const std::array< double, N+1 > &  coef,
const double  p 
)

◆ FitPolynomial()

template<std::size_t N, std::size_t M>
std::array<double, N + 1> apollo::common::math::FitPolynomial ( const std::array< Eigen::Vector2d, M > &  points,
double *  ptr_error_square = nullptr 
)

◆ FLUToRFU()

std::pair<double, double> apollo::common::math::FLUToRFU ( const double  x,
const double  y 
)
inline

◆ Gaussian()

double apollo::common::math::Gaussian ( const double  u,
const double  std,
const double  x 
)

◆ GetGaussLegendrePoints()

template<std::size_t N>
std::pair<std::array<double, N>, std::array<double, N> > apollo::common::math::GetGaussLegendrePoints ( )

Get the points and weights for different ordered Gauss-Legendre integration. Currently support order 2 - 10. Other input order will trigger compiling error.

◆ GetGaussLegendrePoints< 10 >()

template<>
std::pair<std::array<double, 10>, std::array<double, 10> > apollo::common::math::GetGaussLegendrePoints< 10 > ( )
inline

◆ GetGaussLegendrePoints< 2 >()

template<>
std::pair<std::array<double, 2>, std::array<double, 2> > apollo::common::math::GetGaussLegendrePoints< 2 > ( )
inline

◆ GetGaussLegendrePoints< 3 >()

template<>
std::pair<std::array<double, 3>, std::array<double, 3> > apollo::common::math::GetGaussLegendrePoints< 3 > ( )
inline

◆ GetGaussLegendrePoints< 4 >()

template<>
std::pair<std::array<double, 4>, std::array<double, 4> > apollo::common::math::GetGaussLegendrePoints< 4 > ( )
inline

◆ GetGaussLegendrePoints< 5 >()

template<>
std::pair<std::array<double, 5>, std::array<double, 5> > apollo::common::math::GetGaussLegendrePoints< 5 > ( )
inline

◆ GetGaussLegendrePoints< 6 >()

template<>
std::pair<std::array<double, 6>, std::array<double, 6> > apollo::common::math::GetGaussLegendrePoints< 6 > ( )
inline

◆ GetGaussLegendrePoints< 7 >()

template<>
std::pair<std::array<double, 7>, std::array<double, 7> > apollo::common::math::GetGaussLegendrePoints< 7 > ( )
inline

◆ GetGaussLegendrePoints< 8 >()

template<>
std::pair<std::array<double, 8>, std::array<double, 8> > apollo::common::math::GetGaussLegendrePoints< 8 > ( )
inline

◆ GetGaussLegendrePoints< 9 >()

template<>
std::pair<std::array<double, 9>, std::array<double, 9> > apollo::common::math::GetGaussLegendrePoints< 9 > ( )
inline

◆ GoldenSectionSearch()

double apollo::common::math::GoldenSectionSearch ( const std::function< double(double)> &  func,
const double  lower_bound,
const double  upper_bound,
const double  tol = 1e-6 
)

Given a unimodal function defined on the interval, find a value on the interval to minimize the function. Reference: https://en.wikipedia.org/wiki/Golden-section_search.

Parameters
funcThe target single-variable function to minimize.
lower_boundThe lower bound of the interval.
upper_boundThe upper bound of the interval.
tolThe tolerance of error.
Returns
The value that minimize the function fun.

◆ HeadingToQuaternion()

template<typename T >
Eigen::Quaternion<T> apollo::common::math::HeadingToQuaternion ( heading)
inline

◆ InnerProd() [1/2]

double apollo::common::math::InnerProd ( const Vec2d start_point,
const Vec2d end_point_1,
const Vec2d end_point_2 
)

Inner product between two 2-D vectors from the common start point, and end at two other points.

Parameters
start_pointThe common start point of two vectors in 2-D.
end_point_1The end point of the first vector.
end_point_2The end point of the second vector.
Returns
The inner product result.

◆ InnerProd() [2/2]

double apollo::common::math::InnerProd ( const double  x0,
const double  y0,
const double  x1,
const double  y1 
)

Inner product between two vectors. One vector is formed by 1st and 2nd parameters of the function. The other vector is formed by 3rd and 4th parameters of the function.

Parameters
x0The x coordinate of the first vector.
y0The y coordinate of the first vector.
x1The x coordinate of the second vector.
y1The y coordinate of the second vector.
Returns
The inner product result.

◆ IntegrateByGaussLegendre()

template<std::size_t N>
double apollo::common::math::IntegrateByGaussLegendre ( const std::function< double(double)> &  func,
const double  lower_bound,
const double  upper_bound 
)

Compute the integral of a target single-variable function from a lower bound to an upper bound, by 5-th Gauss-Legendre method Given a target function and integral lower and upper bound, compute the integral approximation using 5th order Gauss-Legendre integration. The target function must be a smooth function. Example: target function: auto func = [](const double x) {return x * x;}; double integral = gauss_legendre(func, -2, 3); This gives you the approximated integral of function x^2 in bound [-2, 3].

reference: https://en.wikipedia.org/wiki/Gaussian_quadrature http://www.mymathlib.com/quadrature/gauss_legendre.html

Parameters
funcThe target single-variable function
lower_boundThe lower bound of the integral
upper_boundThe upper bound of the integral
Returns
The integral result

◆ IntegrateBySimpson()

double apollo::common::math::IntegrateBySimpson ( const std::vector< double > &  funv_vec,
const double  dx,
const std::size_t  nsteps 
)

◆ IntegrateByTrapezoidal()

double apollo::common::math::IntegrateByTrapezoidal ( const std::vector< double > &  funv_vec,
const double  dx,
const std::size_t  nsteps 
)

◆ InterpolateUsingLinearApproximation() [1/3]

SLPoint apollo::common::math::InterpolateUsingLinearApproximation ( const SLPoint &  p0,
const SLPoint &  p1,
const double  w 
)

◆ InterpolateUsingLinearApproximation() [2/3]

PathPoint apollo::common::math::InterpolateUsingLinearApproximation ( const PathPoint &  p0,
const PathPoint &  p1,
const double  s 
)

◆ InterpolateUsingLinearApproximation() [3/3]

TrajectoryPoint apollo::common::math::InterpolateUsingLinearApproximation ( const TrajectoryPoint &  tp0,
const TrajectoryPoint &  tp1,
const double  t 
)

◆ InverseQuaternionRotate()

Eigen::Vector3d apollo::common::math::InverseQuaternionRotate ( const Quaternion &  orientation,
const Eigen::Vector3d &  rotated 
)
inline

◆ L2Norm()

void apollo::common::math::L2Norm ( int  feat_dim,
float *  feat_data 
)
inline

◆ lerp()

template<typename T >
T apollo::common::math::lerp ( const T &  x0,
const double  t0,
const T &  x1,
const double  t1,
const double  t 
)

Linear interpolation between two points of type T.

Parameters
x0The coordinate of the first point.
t0The interpolation parameter of the first point.
x1The coordinate of the second point.
t1The interpolation parameter of the second point.
tThe interpolation parameter for interpolation.
xThe coordinate of the interpolated point.
Returns
Interpolated point.

◆ NormalizeAngle()

double apollo::common::math::NormalizeAngle ( const double  angle)

Normalize angle to [-PI, PI).

Parameters
anglethe original value of the angle.
Returns
The normalized value of the angle.

◆ operator!=()

template<typename T >
bool apollo::common::math::operator!= ( Angle< T >  lhs,
Angle< T >  rhs 
)

Tests two Angle objects for inequality.

Parameters
lhsAn Angle object
rhsAn Angle object
Returns
lhs != rhs

◆ operator*() [1/3]

Vec2d apollo::common::math::operator* ( const double  ratio,
const Vec2d vec 
)

Multiplies the given Vec2d by a given scalar.

◆ operator*() [2/3]

template<typename T , typename Scalar >
Angle<T> apollo::common::math::operator* ( Angle< T >  lhs,
Scalar  rhs 
)

Multiplies an Angle by a scalar.

Parameters
lhsAn Angle object
rhsA scalar
Returns
Result of multiplication

◆ operator*() [3/3]

template<typename T , typename Scalar >
Angle<T> apollo::common::math::operator* ( Scalar  lhs,
Angle< T >  rhs 
)

Multiplies an Angle by a scalar.

Parameters
lhsAn Angle object
rhsA scalar
Returns
Result of multiplication

◆ operator+()

template<typename T >
Angle<T> apollo::common::math::operator+ ( Angle< T >  lhs,
Angle< T >  rhs 
)

Sums two angles.

Parameters
lhsAn Angle object
rhsAn Angle object
Returns
Result of addition

◆ operator-()

template<typename T >
Angle<T> apollo::common::math::operator- ( Angle< T >  lhs,
Angle< T >  rhs 
)

Subtracts two angles.

Parameters
lhsAn Angle object
rhsAn Angle object
Returns
Result of subtraction

◆ operator/() [1/2]

template<typename T , typename Scalar >
Angle<T> apollo::common::math::operator/ ( Angle< T >  lhs,
Scalar  rhs 
)

Divides an Angle by a scalar.

Parameters
lhsAn Angle object
rhsA scalar
Returns
Result of division

◆ operator/() [2/2]

template<typename T >
double apollo::common::math::operator/ ( Angle< T >  lhs,
Angle< T >  rhs 
)

Divides an Angle by a scalar.

Parameters
lhsAn Angle object
rhsA scalar
Returns
Result of division

◆ operator==()

template<typename T >
bool apollo::common::math::operator== ( Angle< T >  lhs,
Angle< T >  rhs 
)

Tests two Angle objects for equality.

Parameters
lhsAn Angle object
rhsAn Angle object
Returns
lhs == rhs

◆ PseudoInverse() [1/2]

template<typename T , unsigned int N>
Eigen::Matrix<T, N, N> apollo::common::math::PseudoInverse ( const Eigen::Matrix< T, N, N > &  m,
const double  epsilon = 1.0e-6 
)

Computes the Moore-Penrose pseudo-inverse of a given square matrix, rounding all eigenvalues with absolute value bounded by epsilon to zero.

Parameters
mThe square matrix to be pseudo-inverted
epsilonA small positive real number (optional; default is 1.0e-6).
Returns
Moore-Penrose pseudo-inverse of the given matrix.

◆ PseudoInverse() [2/2]

template<typename T , unsigned int M, unsigned int N>
Eigen::Matrix<T, N, M> apollo::common::math::PseudoInverse ( const Eigen::Matrix< T, M, N > &  m,
const double  epsilon = 1.0e-6 
)

Computes the Moore-Penrose pseudo-inverse of a given matrix, rounding all eigenvalues with absolute value bounded by epsilon to zero.

Parameters
mThe matrix to be pseudo-inverted
epsilonA small positive real number (optional; default is 1.0e-6).
Returns
Moore-Penrose pseudo-inverse of the given matrix.

◆ QuaternionRotate()

Eigen::Vector3d apollo::common::math::QuaternionRotate ( const Quaternion &  orientation,
const Eigen::Vector3d &  original 
)
inline

◆ QuaternionToHeading() [1/2]

double apollo::common::math::QuaternionToHeading ( const double  qw,
const double  qx,
const double  qy,
const double  qz 
)
inline

◆ QuaternionToHeading() [2/2]

template<typename T >
T apollo::common::math::QuaternionToHeading ( const Eigen::Quaternion< T > &  q)
inline

◆ RandomDouble()

double apollo::common::math::RandomDouble ( const double  s,
const double  t,
unsigned int  rand_seed = 1 
)

Get a random double between two integer values by a random seed.

Parameters
sThe lower bound of the random double.
tThe upper bound of the random double.
random_seedThe random seed.
Returns
A random double between s and t based on the input random_seed.

◆ RandomInt()

int apollo::common::math::RandomInt ( const int  s,
const int  t,
unsigned int  rand_seed = 1 
)

Get a random integer between two integer values by a random seed.

Parameters
sThe lower bound of the random integer.
tThe upper bound of the random integer.
random_seedThe random seed.
Returns
A random integer between s and t based on the input random_seed.

◆ RFUToFLU()

std::pair<double, double> apollo::common::math::RFUToFLU ( const double  x,
const double  y 
)
inline

◆ RotateVector2d()

Eigen::Vector2d apollo::common::math::RotateVector2d ( const Eigen::Vector2d &  v_in,
const double  theta 
)

◆ Sigmoid()

double apollo::common::math::Sigmoid ( const double  x)
inline

◆ sin() [1/2]

float apollo::common::math::sin ( Angle16  a)

◆ sin() [2/2]

float apollo::common::math::sin ( Angle8  a)

◆ slerp()

double apollo::common::math::slerp ( const double  a0,
const double  t0,
const double  a1,
const double  t1,
const double  t 
)

Spherical linear interpolation between two angles. The two angles are within range [-M_PI, M_PI).

Parameters
a0The value of the first angle.
t0The interpolation parameter of the first angle.
a1The value of the second angle.
t1The interpolation parameter of the second angle.
tThe interpolation parameter for interpolation.
aThe value of the spherically interpolated angle.
Returns
Interpolated angle.

◆ SolveLQRProblem() [1/2]

void apollo::common::math::SolveLQRProblem ( const Eigen::MatrixXd &  A,
const Eigen::MatrixXd &  B,
const Eigen::MatrixXd &  Q,
const Eigen::MatrixXd &  R,
const Eigen::MatrixXd &  M,
const double  tolerance,
const uint  max_num_iteration,
Eigen::MatrixXd *  ptr_K 
)

Solver for discrete-time linear quadratic problem.

Parameters
AThe system dynamic matrix
BThe control matrix
QThe cost matrix for system state
RThe cost matrix for control output
Mis the cross term between x and u, i.e. x'Qx + u'Ru + 2x'Mu
toleranceThe numerical tolerance for solving Discrete Algebraic Riccati equation (DARE)
max_num_iterationThe maximum iterations for solving ARE
ptr_KThe feedback control matrix (pointer)

◆ SolveLQRProblem() [2/2]

void apollo::common::math::SolveLQRProblem ( const Eigen::MatrixXd &  A,
const Eigen::MatrixXd &  B,
const Eigen::MatrixXd &  Q,
const Eigen::MatrixXd &  R,
const double  tolerance,
const uint  max_num_iteration,
Eigen::MatrixXd *  ptr_K 
)

Solver for discrete-time linear quadratic problem.

Parameters
AThe system dynamic matrix
BThe control matrix
QThe cost matrix for system state
RThe cost matrix for control output
toleranceThe numerical tolerance for solving Discrete Algebraic Riccati equation (DARE)
max_num_iterationThe maximum iterations for solving ARE
ptr_KThe feedback control matrix (pointer)

◆ Sqr()

double apollo::common::math::Sqr ( const double  x)

◆ Square()

template<typename T >
T apollo::common::math::Square ( const T  value)
inline

Compute squared value.

Parameters
valueThe target value to get its squared value.
Returns
Squared value of the input value.

◆ tan() [1/2]

float apollo::common::math::tan ( Angle16  a)

◆ tan() [2/2]

float apollo::common::math::tan ( Angle8  a)

◆ WrapAngle()

double apollo::common::math::WrapAngle ( const double  angle)

Wrap angle to [0, 2 * PI).

Parameters
anglethe original value of the angle.
Returns
The wrapped value of the angle.

Variable Documentation

◆ kMathEpsilon

constexpr double apollo::common::math::kMathEpsilon = 1e-10

◆ SIN_TABLE

const float apollo::common::math::SIN_TABLE[SIN_TABLE_SIZE]