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

Classes

class  BaseGroundDetector
 
class  ConditionClustering
 
class  Constant
 
class  Constant< double >
 
class  Constant< float >
 
class  ConvexHull2D
 
struct  Edge
 
class  GatedHungarianMatcher
 
class  GraphSegmentor
 
struct  GroundPlaneLiDAR
 
struct  GroundPlaneSpherical
 
struct  HoughLine
 
class  HoughTransfer
 
class  HungarianOptimizer
 
class  PlaneFitGroundDetector
 
struct  PlaneFitGroundDetectorParam
 
struct  PlaneFitPointCandIndices
 
struct  PlanePara
 
class  PtCluster
 
class  SecureMat
 
class  SensorManager
 
class  Universe
 
class  Voxel
 
class  VoxelGridXY
 
class  VoxelGridXYPyramid
 

Functions

template<typename Type >
Type CrossProduct (const Eigen::Matrix< Type, 2, 1 > &point1, const Eigen::Matrix< Type, 2, 1 > &point2, const Eigen::Matrix< Type, 2, 1 > &point3)
 
template<typename PointT >
PointT::Type CrossProduct (const PointT &point1, const PointT &point2, const PointT &point3)
 
template<typename PointT >
PointT::Type CalculateEuclidenDist (const PointT &pt1, const PointT &pt2)
 
template<typename PointT >
PointT::Type CalculateEuclidenDist2DXY (const PointT &pt1, const PointT &pt2)
 
template<typename T >
CalculateCosTheta2DXY (const Eigen::Matrix< T, 3, 1 > &v1, const Eigen::Matrix< T, 3, 1 > &v2)
 
template<typename T >
CalculateTheta2DXY (const Eigen::Matrix< T, 3, 1 > &v1, const Eigen::Matrix< T, 3, 1 > &v2)
 
template<typename T >
Eigen::Matrix< T, 3, 3 > CalculateRotationMat2DXY (const Eigen::Matrix< T, 3, 1 > &v1, const Eigen::Matrix< T, 3, 1 > &v2)
 
template<typename T >
Eigen::Matrix< T, 3, 1 > Calculate2DXYProjectVector (const Eigen::Matrix< T, 3, 1 > &projected_vector, const Eigen::Matrix< T, 3, 1 > &project_vector)
 
template<typename PointT >
void ConvertCartesiantoPolarCoordinate (const PointT &xyz, typename PointT::Type *h_angle_in_degree, typename PointT::Type *v_angle_in_degree, typename PointT::Type *dist)
 
bool PointCamera1ToCamera2 (const Eigen::Vector2d &point, const Eigen::Matrix3d &camera1_intrinsic_inverse, const Eigen::Matrix3d &camera2_intrinsic, const Eigen::Matrix3d &trans_camera1_to_camera2, Eigen::Vector2d *point_out)
 
bool IsCamerasFieldOverlap (const base::PinholeCameraModel &from_camera, const base::PinholeCameraModel &to_camera, const Eigen::Matrix4d &extrinsic, Eigen::Vector2d *up_left, Eigen::Vector2d *low_right)
 
template<typename PointT >
bool IsPointXYInPolygon2DXY (const PointT &point, const base::PointCloud< PointT > &polygon)
 
template<typename PointT >
bool IsPointInBBox (const Eigen::Matrix< typename PointT::Type, 3, 1 > &gnd_c, const Eigen::Matrix< typename PointT::Type, 3, 1 > &dir_x, const Eigen::Matrix< typename PointT::Type, 3, 1 > &dir_y, const Eigen::Matrix< typename PointT::Type, 3, 1 > &dir_z, const Eigen::Matrix< typename PointT::Type, 3, 1 > &size, const PointT &point)
 
template<typename PointCloudT >
void CalculateBBoxSizeCenter2DXY (const PointCloudT &cloud, const Eigen::Vector3f &dir, Eigen::Vector3f *size, Eigen::Vector3d *center, float minimum_edge_length=std::numeric_limits< float >::epsilon())
 
template<typename Type >
void CalculateMostConsistentBBoxDir2DXY (const Eigen::Matrix< Type, 3, 1 > &prev_dir, Eigen::Matrix< Type, 3, 1 > *curr_dir)
 
template<typename Type >
Type CalculateIou2DXY (const Eigen::Matrix< Type, 3, 1 > &center0, const Eigen::Matrix< Type, 3, 1 > &size0, const Eigen::Matrix< Type, 3, 1 > &center1, const Eigen::Matrix< Type, 3, 1 > &size1)
 
template<typename Type >
Type CalculateIOUBBox (const base::BBox2D< Type > &box1, const base::BBox2D< Type > &box2)
 
template<typename PointT >
bool CalculateDistAndDirToSegs (const Eigen::Matrix< typename PointT::Type, 3, 1 > &pt, const base::PointCloud< PointT > &segs, typename PointT::Type *dist, Eigen::Matrix< typename PointT::Type, 3, 1 > *dir)
 
template<typename PointT >
void CalculateDistAndDirToBoundary (const Eigen::Matrix< typename PointT::Type, 3, 1 > &pt, const base::PointCloud< PointT > &left_boundary, const base::PointCloud< PointT > &right_boundary, typename PointT::Type *dist, Eigen::Matrix< typename PointT::Type, 3, 1 > *dir)
 
template<typename PointT >
void CalculateDistAndDirToBoundary (const Eigen::Matrix< typename PointT::Type, 3, 1 > &pt, const apollo::common::EigenVector< base::PointCloud< PointT >> &left_boundary, const apollo::common::EigenVector< base::PointCloud< PointT >> &right_boundary, typename PointT::Type *dist, Eigen::Matrix< typename PointT::Type, 3, 1 > *dir)
 
bool IsPtInRoi (const std::shared_ptr< const apollo::perception::base::HdmapStruct > roi, const apollo::perception::base::PointD pt)
 
bool IsObjectInRoi (const std::shared_ptr< const apollo::perception::base::HdmapStruct > roi, const std::shared_ptr< const apollo::perception::base::Object > obj)
 
bool IsObjectBboxInRoi (const std::shared_ptr< const apollo::perception::base::HdmapStruct > roi, const std::shared_ptr< const apollo::perception::base::Object > obj)
 
bool ObjectInRoiCheck (const std::shared_ptr< const apollo::perception::base::HdmapStruct > roi, const std::vector< std::shared_ptr< apollo::perception::base::Object >> &objs, std::vector< std::shared_ptr< apollo::perception::base::Object >> *valid_objs)
 
void ConnectedComponentAnalysis (const std::vector< std::vector< int >> &graph, std::vector< std::vector< int >> *components)
 
template<typename T >
bool ILess (const T &a, const T &b)
 
template<typename T >
bool ILarger (const T &a, const T &b)
 
template<typename T >
IMedian3 (const T &a, const T &b, const T &c)
 
template<typename T , bool Compare>
void IInsertionSort (T *a, int n)
 
template<typename T >
void IIndexedShuffle (T *a, int *indices, int n, int element_size, int nr_indexed_elements, bool is_sort_indices=true)
 
template<typename T >
void IIndexedShuffle (T *a, T *b, int *indices, int n, int element_size_a, int element_size_b, int nr_indexed_elements, bool is_sort_indices=true)
 
template<typename T >
T * IAlloc (int memory_size)
 
template<typename T >
void IFree (T **mem)
 
template<typename T >
T ** IAlloc2 (int m, int n)
 
template<typename T >
void IFree2 (T ***A)
 
template<class T >
T *** IAlloc3 (int l, int m, int n)
 
template<typename T >
T * IAllocAligned (int memory_size, int alignment_power=4)
 
template<typename T >
void IFreeAligned (T **mem)
 
template<typename T >
int IVerifyAlignment (const T *mem, int alignment_power=4)
 
float IAbs (float a)
 
int IAbs (int a)
 
double IAbs (double a)
 
float IDiv (float a, float b)
 
float IDiv (float a, int b)
 
float IDiv (float a, unsigned int b)
 
double IDiv (int a, int b)
 
double IDiv (unsigned int a, unsigned int b)
 
double IDiv (double a, double b)
 
double IDiv (double a, int b)
 
double IDiv (double a, unsigned int b)
 
float IRec (float a)
 
double IRec (int a)
 
double IRec (unsigned int a)
 
double IRec (double a)
 
float ISqrt (float a)
 
double ISqrt (int a)
 
double ISqrt (unsigned int a)
 
double ISqrt (double a)
 
float ICbrt (float a)
 
double ICbrt (int a)
 
double ICbrt (unsigned int a)
 
double ICbrt (double a)
 
float ISqr (float a)
 
int ISqr (int a)
 
unsigned int ISqr (unsigned int a)
 
double ISqr (double a)
 
int ISqr (char a)
 
int ISqr (unsigned char a)
 
float ICub (float a)
 
int ICub (int a)
 
unsigned int ICub (unsigned int a)
 
double ICub (double a)
 
int ICub (char a)
 
int ICub (unsigned char a)
 
float ILog (float x)
 
double ILog (int x)
 
double ILog (unsigned int x)
 
double ILog (double x)
 
float IExp (float x)
 
double IExp (int x)
 
double IExp (unsigned int x)
 
double IExp (double x)
 
float IPow (float a, float b)
 
float IPow (float a, int b)
 
double IPow (int a, int b)
 
double IPow (unsigned int a, unsigned int b)
 
double IPow (double a, double b)
 
double IPow (double a, int b)
 
template<typename T >
IMin (T a, T b)
 
template<typename T >
IMax (T a, T b)
 
template<typename T >
IAverage (T a, T b)
 
template<typename T >
ISign (T a)
 
template<typename T >
ISignNeverZero (T a)
 
int IRound (int a)
 
int IRound (float a)
 
int IRound (double a)
 
int ICeil (int a)
 
int ICeil (float a)
 
int ICeil (double a)
 
float ISin (float alpha)
 
double ISin (double alpha)
 
float ICos (float alpha)
 
double ICos (double alpha)
 
float ITan (float alpha)
 
double ITan (double alpha)
 
float IAsin (float alpha)
 
double IAsin (double alpha)
 
float IAcos (float alpha)
 
double IAcos (double alpha)
 
float IAtan2 (float y, float x)
 
double IAtan2 (double y, double x)
 
float IRadiansToDegree (float r)
 
double IRadiansToDegree (double r)
 
float IDegreeToRadians (float d)
 
double IDegreeToRadians (double d)
 
unsigned int IHamming (unsigned int a, unsigned int b)
 
unsigned int IHammingLut (unsigned int a, unsigned int b)
 
template<typename T >
void ISwap (T &a, T &b)
 
template<typename T >
void ISwap (T *a, T *b, int n)
 
template<typename T >
void ISwap2 (T *a, T *b)
 
template<typename T >
void ISwap3 (T *a, T *b)
 
template<typename T >
void ISwap4 (T *a, T *b)
 
template<typename T >
IInterval (T a, T min_val, T max_val)
 
template<typename T >
IIntervalHalfopen (T a, T min_val, T max_val)
 
template<typename T >
void IMakeReference (T *a, T **p, int m, int n)
 
template<typename T >
void IMakeReference2x2 (T a[4], T *p[2])
 
template<typename T >
void IMakeReference3x3 (T a[9], T *p[3])
 
template<typename T >
void IMakeReference4x4 (T a[16], T *p[4])
 
template<typename T >
void IMakeReference4x9 (T a[36], T *p[4])
 
template<typename T >
void IMakeReference5x9 (T a[45], T *p[5])
 
template<typename T >
void IMakeReference9x9 (T a[81], T *p[9])
 
template<typename T >
void IMakeReference12x12 (T a[144], T *p[12])
 
template<typename T >
void IMakeConstReference (const T *a, const T **p, int m, int n)
 
template<typename T >
void IMakeConstReference2x2 (const T a[4], const T *p[2])
 
template<typename T >
void IMakeConstReference3x3 (const T a[9], const T *p[3])
 
template<typename T >
void IMakeConstReference4x4 (const T a[16], const T *p[4])
 
template<typename T >
void IMakeConstReference4x9 (const T a[36], const T *p[4])
 
template<typename T >
void IMakeConstReference5x9 (const T a[45], const T *p[5])
 
template<typename T >
void IMakeConstReference9x9 (const T a[81], const T *p[9])
 
template<typename T >
void IMakeConstReference12x12 (const T a[144], const T *p[12])
 
template<typename T >
void IMakeReference (T *a, T ***p, int l, int m, int n)
 
template<typename T >
void IRamp (T *a, int n)
 
void IGaussian2D (float *kernel, int n, const float sigma)
 
void IGaussian2D (double *kernel, int n, const double sigma)
 
template<typename T >
void IMove (const T &a, T *b)
 
template<typename T >
bool IWithin1D (const T x, const T start, const T length)
 
template<typename T >
bool IWithin2D (const T p[2], const T x_upper_left, const T y_upper_left, const T width, const T height)
 
template<typename T >
bool IWithin2D (const T x, const T y, const T x_upper_left, const T y_upper_left, const T width, const T height)
 
template<typename T >
void ICopy (const T *src, T *dst, int n)
 
template<typename T >
void ICopy1 (const T src[1], T dst[1])
 
template<typename T >
void ICopy2 (const T src[2], T dst[2])
 
template<typename T >
void ICopy3 (const T src[3], T dst[3])
 
template<typename T >
void ICopy4 (const T src[4], T dst[4])
 
template<typename T >
void ICopy5 (const T src[5], T dst[5])
 
template<typename T >
void ICopy6 (const T src[6], T dst[6])
 
template<typename T >
void ICopy7 (const T src[7], T dst[7])
 
template<typename T >
void ICopy8 (const T src[8], T dst[8])
 
template<typename T >
void ICopy9 (const T src[9], T dst[9])
 
template<typename T >
void ICopy10 (const T src[10], T dst[10])
 
template<typename T >
void ICopy11 (const T src[11], T dst[11])
 
template<typename T >
void ICopy12 (const T src[12], T dst[12])
 
template<typename T >
void ICopy13 (const T src[13], T dst[13])
 
template<typename T >
void ICopy14 (const T src[14], T dst[14])
 
template<typename T >
void ICopy15 (const T src[15], T dst[15])
 
template<typename T >
void ICopy16 (const T src[16], T dst[16])
 
template<typename T >
void ICopy (const T *const *src, T **dst, int m, int n)
 
template<typename T , typename S >
void ICopy (const T *src, S *dst, int n)
 
template<typename T , typename S >
void ICopy (const T *const *src, S **dst, int m, int n)
 
template<typename T >
void IFill (T *a, int n, T val)
 
template<typename T >
void IFill1 (T a[1], T val)
 
template<typename T >
void IFill2 (T a[2], T val)
 
template<typename T >
void IFill3 (T a[3], T val)
 
template<typename T >
void IFill4 (T a[4], T val)
 
template<typename T >
void IFill5 (T a[5], T val)
 
template<typename T >
void IFill6 (T a[6], T val)
 
template<typename T >
void IFill7 (T a[7], T val)
 
template<typename T >
void IFill8 (T a[8], T val)
 
template<typename T >
void IFill9 (T a[9], T val)
 
template<typename T >
void IFill10 (T a[10], T val)
 
template<typename T >
void IFill11 (T a[11], T val)
 
template<typename T >
void IFill12 (T a[12], T val)
 
template<typename T >
void IFill13 (T a[13], T val)
 
template<typename T >
void IFill14 (T a[14], T val)
 
template<typename T >
void IFill15 (T a[15], T val)
 
template<typename T >
void IFill16 (T a[16], T val)
 
template<typename T >
void IZero (T *a, int n)
 
template<typename T >
void IZero1 (T a[1])
 
template<typename T >
void IZero2 (T a[2])
 
template<typename T >
void IZero3 (T a[3])
 
template<typename T >
void IZero4 (T a[4])
 
template<typename T >
void IZero5 (T a[5])
 
template<typename T >
void IZero6 (T a[6])
 
template<typename T >
void IZero7 (T a[7])
 
template<typename T >
void IZero8 (T a[8])
 
template<typename T >
void IZero9 (T a[9])
 
template<typename T >
void IZero10 (T a[10])
 
template<typename T >
void IZero11 (T a[11])
 
template<typename T >
void IZero12 (T a[12])
 
template<typename T >
void IZero13 (T a[13])
 
template<typename T >
void IZero14 (T a[14])
 
template<typename T >
void IZero15 (T a[15])
 
template<typename T >
void IZero16 (T a[16])
 
template<typename T >
void INeg (T *x, int n)
 
template<typename T >
void INeg1 (T x[1])
 
template<typename T >
void INeg2 (T x[2])
 
template<typename T >
void INeg3 (T x[3])
 
template<typename T >
void INeg4 (T x[4])
 
template<typename T >
void INeg5 (T x[5])
 
template<typename T >
void INeg6 (T x[6])
 
template<typename T >
void INeg7 (T x[7])
 
template<typename T >
void INeg8 (T x[8])
 
template<typename T >
void INeg9 (T x[9])
 
template<typename T >
void INeg10 (T x[10])
 
template<typename T >
void INeg11 (T x[11])
 
template<typename T >
void INeg12 (T x[12])
 
template<typename T >
void INeg13 (T x[13])
 
template<typename T >
void INeg14 (T x[14])
 
template<typename T >
void INeg15 (T x[15])
 
template<typename T >
void INeg16 (T x[16])
 
template<typename T >
void INeg1 (const T x[1], T y[1])
 
template<typename T >
void INeg2 (const T x[2], T y[2])
 
template<typename T >
void INeg3 (const T x[3], T y[3])
 
template<typename T >
void INeg4 (const T x[4], T y[4])
 
template<typename T >
void INeg5 (const T x[5], T y[5])
 
template<typename T >
void INeg6 (const T x[6], T y[6])
 
template<typename T >
void INeg7 (const T x[7], T y[7])
 
template<typename T >
void INeg8 (const T x[8], T y[8])
 
template<typename T >
void INeg9 (const T x[9], T y[9])
 
template<typename T >
void INeg10 (const T x[10], T y[10])
 
template<typename T >
void INeg11 (const T x[11], T y[11])
 
template<typename T >
void INeg12 (const T x[12], T y[12])
 
template<typename T >
void INeg13 (const T x[13], T y[13])
 
template<typename T >
void INeg14 (const T x[14], T y[14])
 
template<typename T >
void INeg15 (const T x[15], T y[15])
 
template<typename T >
void INeg16 (const T x[16], T y[16])
 
template<typename T >
void INegCol (T *A, int c, int m, int n)
 
template<typename T >
void IAdd (T *x, int n, T k)
 
template<typename T >
void IAdd (const T *x, const T *y, int n, T *z)
 
template<typename T >
void IAdd1 (const T x[1], const T y[1], T z[1])
 
template<typename T >
void IAdd2 (const T x[2], const T y[2], T z[2])
 
template<typename T >
void IAdd3 (const T x[3], const T y[3], T z[3])
 
template<typename T >
void IAdd4 (const T x[4], const T y[4], T z[4])
 
template<typename T >
void IAdd5 (const T x[5], const T y[5], T z[5])
 
template<typename T >
void IAdd6 (const T x[6], const T y[6], T z[6])
 
template<typename T >
void IAdd7 (const T x[7], const T y[7], T z[7])
 
template<typename T >
void IAdd8 (const T x[8], const T y[8], T z[8])
 
template<typename T >
void IAdd9 (const T x[9], const T y[9], T z[9])
 
template<typename T >
void IAdd10 (const T x[10], const T y[10], T z[10])
 
template<typename T >
void IAdd11 (const T x[11], const T y[11], T z[11])
 
template<typename T >
void IAdd12 (const T x[12], const T y[12], T z[12])
 
template<typename T >
void IAdd13 (const T x[13], const T y[13], T z[13])
 
template<typename T >
void IAdd14 (const T x[14], const T y[14], T z[14])
 
template<typename T >
void IAdd15 (const T x[15], const T y[15], T z[15])
 
template<typename T >
void IAdd16 (const T x[16], const T y[16], T z[16])
 
template<typename T >
void IAdd20 (const T x[20], const T y[20], T z[20])
 
template<typename T >
void IAdd (const T *x, T *y, int n)
 
template<typename T >
void IAdd1 (const T x[1], T y[1])
 
template<typename T >
void IAdd2 (const T x[2], T y[2])
 
template<typename T >
void IAdd3 (const T x[3], T y[3])
 
template<typename T >
void IAdd4 (const T x[4], T y[4])
 
template<typename T >
void IAdd5 (const T x[5], T y[5])
 
template<typename T >
void IAdd6 (const T x[6], T y[6])
 
template<typename T >
void IAdd7 (const T x[7], T y[7])
 
template<typename T >
void IAdd8 (const T x[8], T y[8])
 
template<typename T >
void IAdd9 (const T x[9], T y[9])
 
template<typename T >
void IAdd10 (const T x[10], T y[10])
 
template<typename T >
void IAdd11 (const T x[11], T y[11])
 
template<typename T >
void IAdd12 (const T x[12], T y[12])
 
template<typename T >
void IAdd13 (const T x[13], T y[13])
 
template<typename T >
void IAdd14 (const T x[14], T y[14])
 
template<typename T >
void IAdd15 (const T x[15], T y[15])
 
template<typename T >
void IAdd16 (const T x[16], T y[16])
 
template<typename T >
void IAdd20 (const T x[20], T y[20])
 
template<typename T >
void IAddScaled (const T *x, T *y, int n, T k)
 
template<typename T >
void IAddScaled1 (const T x[1], T y[1], T k)
 
template<typename T >
void IAddScaled2 (const T x[2], T y[2], T k)
 
template<typename T >
void IAddScaled3 (const T x[3], T y[3], T k)
 
template<typename T >
void IAddScaled4 (const T x[4], T y[4], T k)
 
template<typename T >
void IAddScaled5 (const T x[5], T y[5], T k)
 
template<typename T >
void IAddScaled6 (const T x[6], T y[6], T k)
 
template<typename T >
void IAddScaled7 (const T x[7], T y[7], T k)
 
template<typename T >
void IAddScaled8 (const T x[8], T y[8], T k)
 
template<typename T >
void IAddScaled9 (const T x[9], T y[9], T k)
 
template<typename T >
void IAddScaled (const T *x, const T *y, T *z, int n, T k)
 
template<typename T >
void IAddScaled1 (const T x[1], const T y[1], T z[1], T k)
 
template<typename T >
void IAddScaled2 (const T x[2], const T y[2], T z[2], T k)
 
template<typename T >
void IAddScaled3 (const T x[3], const T y[3], T z[3], T k)
 
template<typename T >
void IAddScaled4 (const T x[4], const T y[4], T z[4], T k)
 
template<typename T >
void IAddScaled5 (const T x[5], const T y[5], T z[5], T k)
 
template<typename T >
void IAddScaled6 (const T x[6], const T y[6], T z[6], T k)
 
template<typename T >
void IAddScaled7 (const T x[7], const T y[7], T z[7], T k)
 
template<typename T >
void IAddScaled8 (const T x[8], const T y[8], T z[8], T k)
 
template<typename T >
void IAddScaled9 (const T x[9], const T y[9], T z[9], T k)
 
template<typename T >
void ISub (T *x, int n, T k)
 
template<typename T >
void ISub (const T *x, const T *y, int n, T *z)
 
template<typename T >
void ISub1 (const T x[1], const T y[1], T z[1])
 
template<typename T >
void ISub2 (const T x[2], const T y[2], T z[2])
 
template<typename T >
void ISub3 (const T x[3], const T y[3], T z[3])
 
template<typename T >
void ISub4 (const T x[4], const T y[4], T z[4])
 
template<typename T >
void ISub5 (const T x[5], const T y[5], T z[5])
 
template<typename T >
void ISub6 (const T x[6], const T y[6], T z[6])
 
template<typename T >
void ISub7 (const T x[7], const T y[7], T z[7])
 
template<typename T >
void ISub8 (const T x[8], const T y[8], T z[8])
 
template<typename T >
void ISub9 (const T x[9], const T y[9], T z[9])
 
template<typename T >
void ISub10 (const T x[10], const T y[10], T z[10])
 
template<typename T >
void ISub11 (const T x[11], const T y[11], T z[11])
 
template<typename T >
void ISub12 (const T x[12], const T y[12], T z[12])
 
template<typename T >
void ISub13 (const T x[13], const T y[13], T z[13])
 
template<typename T >
void ISub14 (const T x[14], const T y[14], T z[14])
 
template<typename T >
void ISub15 (const T x[15], const T y[15], T z[15])
 
template<typename T >
void ISub16 (const T x[16], const T y[16], T z[16])
 
template<typename T >
void ISub (const T *x, T *y, int n)
 
template<typename T >
void ISub1 (const T x[1], T y[1])
 
template<typename T >
void ISub2 (const T x[2], T y[2])
 
template<typename T >
void ISub3 (const T x[3], T y[3])
 
template<typename T >
void ISub4 (const T x[4], T y[4])
 
template<typename T >
void ISub5 (const T x[5], T y[5])
 
template<typename T >
void ISub6 (const T x[6], T y[6])
 
template<typename T >
void ISub7 (const T x[7], T y[7])
 
template<typename T >
void ISub8 (const T x[8], T y[8])
 
template<typename T >
void ISub9 (const T x[9], T y[9])
 
template<typename T >
void ISub10 (const T x[10], T y[10])
 
template<typename T >
void ISub11 (const T x[11], T y[11])
 
template<typename T >
void ISub12 (const T x[12], T y[12])
 
template<typename T >
void ISub13 (const T x[13], T y[13])
 
template<typename T >
void ISub14 (const T x[14], T y[14])
 
template<typename T >
void ISub15 (const T x[15], T y[15])
 
template<typename T >
void ISub16 (const T x[16], T y[16])
 
template<typename T >
void ISubScaled (const T *x, T *y, int n, T k)
 
template<typename T >
void ISubScaled1 (const T x[1], T y[1], T k)
 
template<typename T >
void ISubScaled2 (const T x[2], T y[2], T k)
 
template<typename T >
void ISubScaled3 (const T x[3], T y[3], T k)
 
template<typename T >
void ISubScaled4 (const T x[4], T y[4], T k)
 
template<typename T >
void ISubScaled5 (const T x[5], T y[5], T k)
 
template<typename T >
void ISubScaled6 (const T x[6], T y[6], T k)
 
template<typename T >
void ISubScaled7 (const T x[7], T y[7], T k)
 
template<typename T >
void ISubScaled8 (const T x[8], T y[8], T k)
 
template<typename T >
void ISubScaled9 (const T x[9], T y[9], T k)
 
template<typename T >
void IScale (T *x, int n, T sf)
 
template<typename T >
void IScale1 (T x[1], T sf)
 
template<typename T >
void IScale2 (T x[2], T sf)
 
template<typename T >
void IScale3 (T x[3], T sf)
 
template<typename T >
void IScale4 (T x[4], T sf)
 
template<typename T >
void IScale5 (T x[5], T sf)
 
template<typename T >
void IScale6 (T x[6], T sf)
 
template<typename T >
void IScale7 (T x[7], T sf)
 
template<typename T >
void IScale8 (T x[8], T sf)
 
template<typename T >
void IScale9 (T x[9], T sf)
 
template<typename T >
void IScale10 (T x[10], T sf)
 
template<typename T >
void IScale11 (T x[11], T sf)
 
template<typename T >
void IScale12 (T x[12], T sf)
 
template<typename T >
void IScale13 (T x[13], T sf)
 
template<typename T >
void IScale14 (T x[14], T sf)
 
template<typename T >
void IScale15 (T x[15], T sf)
 
template<typename T >
void IScale16 (T x[16], T sf)
 
template<typename T >
void IScale (const T *x, T *y, int n, T sf)
 
template<typename T >
void IScale1 (const T x[1], T y[1], T sf)
 
template<typename T >
void IScale2 (const T x[2], T y[2], T sf)
 
template<typename T >
void IScale3 (const T x[3], T y[3], T sf)
 
template<typename T >
void IScale4 (const T x[4], T y[4], T sf)
 
template<typename T >
void IScale5 (const T x[5], T y[5], T sf)
 
template<typename T >
void IScale6 (const T x[6], T y[6], T sf)
 
template<typename T >
void IScale7 (const T x[7], T y[7], T sf)
 
template<typename T >
void IScale8 (const T x[8], T y[8], T sf)
 
template<typename T >
void IScale9 (const T x[9], T y[9], T sf)
 
template<typename T >
void IScale10 (const T x[10], T y[10], T sf)
 
template<typename T >
void IScale11 (const T x[11], T y[11], T sf)
 
template<typename T >
void IScale12 (const T x[12], T y[12], T sf)
 
template<typename T >
void IScale13 (const T x[13], T y[13], T sf)
 
template<typename T >
void IScale14 (const T x[14], T y[14], T sf)
 
template<typename T >
void IScale15 (const T x[15], T y[15], T sf)
 
template<typename T >
void IScale16 (const T x[16], T y[16], T sf)
 
template<typename T >
IDot (const T *x, const T *y, int n)
 
template<typename T >
IDot1 (const T x[1], const T y[1])
 
template<typename T >
IDot2 (const T x[2], const T y[2])
 
template<typename T >
IDot3 (const T x[3], const T y[3])
 
template<typename T >
IDot4 (const T x[4], const T y[4])
 
template<typename T >
IDot5 (const T x[5], const T y[5])
 
template<typename T >
IDot6 (const T x[6], const T y[6])
 
template<typename T >
IDot7 (const T x[7], const T y[7])
 
template<typename T >
IDot8 (const T x[8], const T y[8])
 
template<typename T >
IDot9 (const T x[9], const T y[9])
 
template<typename T >
IDot10 (const T x[10], const T y[10])
 
template<typename T >
IDot11 (const T x[11], const T y[11])
 
template<typename T >
IDot12 (const T x[12], const T y[12])
 
template<typename T >
IDot13 (const T x[13], const T y[13])
 
template<typename T >
IDot14 (const T x[14], const T y[14])
 
template<typename T >
IDot15 (const T x[15], const T y[15])
 
template<typename T >
IDot16 (const T x[16], const T y[16])
 
int ISumU (const unsigned char *x, int n)
 
template<typename T >
ISum (const T *x, int n)
 
template<typename T >
ISum1 (const T x[1])
 
template<typename T >
ISum2 (const T x[2])
 
template<typename T >
ISum3 (const T x[3])
 
template<typename T >
ISum4 (const T x[4])
 
template<typename T >
ISum5 (const T x[5])
 
template<typename T >
ISum6 (const T x[6])
 
template<typename T >
ISum7 (const T x[7])
 
template<typename T >
ISum8 (const T x[8])
 
template<typename T >
ISum9 (const T x[9])
 
template<typename T >
ISum10 (const T x[10])
 
template<typename T >
ISum11 (const T x[11])
 
template<typename T >
ISum12 (const T x[12])
 
template<typename T >
ISum13 (const T x[13])
 
template<typename T >
ISum14 (const T x[14])
 
template<typename T >
ISum15 (const T x[15])
 
template<typename T >
ISum16 (const T x[16])
 
template<typename T >
IAbsSum (const T *x, int n)
 
int IMeanU (const unsigned char *x, int n)
 
template<typename T >
IMean (const T *x, int n)
 
template<typename T >
IMean2 (const T x[2])
 
template<typename T >
IMean3 (const T x[3])
 
template<typename T >
IMean4 (const T x[4])
 
template<typename T >
IMean5 (const T x[5])
 
template<typename T >
IMean6 (const T x[6])
 
template<typename T >
IMean7 (const T x[7])
 
template<typename T >
IMean8 (const T x[8])
 
template<typename T >
IMean9 (const T x[9])
 
template<typename T >
IMean10 (const T x[10])
 
template<typename T >
IMean11 (const T x[11])
 
template<typename T >
IMean12 (const T x[12])
 
template<typename T >
IMean13 (const T x[13])
 
template<typename T >
IMean14 (const T x[14])
 
template<typename T >
IMean15 (const T x[15])
 
template<typename T >
IMean16 (const T x[16])
 
template<typename T >
ISdv (const T *x, T mean, int n)
 
int ISquaresumU (const unsigned char *x, int n)
 
template<typename T >
ISquaresum (const T *x, int n)
 
template<typename T >
ISquaresum1 (const T x[1])
 
template<typename T >
ISquaresum2 (const T x[2])
 
template<typename T >
ISquaresum3 (const T x[3])
 
template<typename T >
ISquaresum4 (const T x[4])
 
template<typename T >
ISquaresum5 (const T x[5])
 
template<typename T >
ISquaresum6 (const T x[6])
 
template<typename T >
ISquaresum7 (const T x[7])
 
template<typename T >
ISquaresum8 (const T x[8])
 
template<typename T >
ISquaresum9 (const T x[9])
 
template<typename T >
ISquaresum10 (const T x[10])
 
template<typename T >
ISquaresum11 (const T x[11])
 
template<typename T >
ISquaresum12 (const T x[12])
 
template<typename T >
ISquaresum13 (const T x[13])
 
template<typename T >
ISquaresum14 (const T x[14])
 
template<typename T >
ISquaresum15 (const T x[15])
 
template<typename T >
ISquaresum16 (const T x[16])
 
int ISquaresumDiffU (const unsigned char *x, const unsigned char *y, int n)
 
template<typename T >
ISquaresumDiffU (const T *x, const T *y, int n)
 
template<typename T >
ISquaresumDiffU1 (const T x[1], const T y[1])
 
template<typename T >
ISquaresumDiffU2 (const T x[2], const T y[2])
 
template<typename T >
ISquaresumDiffU3 (const T x[3], const T y[3])
 
template<typename T >
ISquaresumDiffU4 (const T x[4], const T y[4])
 
template<typename T >
ISquaresumDiffU5 (const T x[5], const T y[5])
 
template<typename T >
ISquaresumDiffU6 (const T x[6], const T y[6])
 
template<typename T >
ISquaresumDiffU7 (const T x[7], const T y[7])
 
template<typename T >
ISquaresumDiffU8 (const T x[8], const T y[8])
 
template<typename T >
ISquaresumDiffU9 (const T x[9], const T y[9])
 
template<typename T >
ISquaresumDiffU10 (const T x[10], const T y[10])
 
template<typename T >
ISquaresumDiffU11 (const T x[11], const T y[11])
 
template<typename T >
ISquaresumDiffU12 (const T x[12], const T y[12])
 
template<typename T >
ISquaresumDiffU13 (const T x[13], const T y[13])
 
template<typename T >
ISquaresumDiffU14 (const T x[14], const T y[14])
 
template<typename T >
ISquaresumDiffU15 (const T x[15], const T y[15])
 
template<typename T >
ISquaresumDiffU16 (const T x[16], const T y[16])
 
unsigned int IHammingDiff (const unsigned int *x, const unsigned int *y, int n)
 
unsigned int IHammingDiff2 (const unsigned int x[2], const unsigned int y[2])
 
unsigned int IHammingDiff4 (const unsigned int x[4], const unsigned int y[4])
 
unsigned int IHammingDiff8 (const unsigned int x[8], const unsigned int y[8])
 
unsigned int IHammingDiff16 (const unsigned int x[16], const unsigned int y[16])
 
double IL2Norm (const unsigned char *x, int n)
 
double IL2Norm (const int *x, int n)
 
float IL2Norm (const float *x, int n)
 
double IL2Norm (const double *x, int n)
 
template<typename T >
IL2Norm1 (const T x[1])
 
template<typename T >
IL2Norm2 (const T x[2])
 
template<typename T >
IL2Norm3 (const T x[3])
 
template<typename T >
IL2Norm4 (const T x[4])
 
template<typename T >
IL2Norm5 (const T x[5])
 
template<typename T >
IL2Norm6 (const T x[6])
 
template<typename T >
IL2Norm7 (const T x[7])
 
template<typename T >
IL2Norm8 (const T x[8])
 
template<typename T >
IL2Norm9 (const T x[9])
 
template<typename T >
IL2Norm10 (const T x[10])
 
template<typename T >
IL2Norm11 (const T x[11])
 
template<typename T >
IL2Norm12 (const T x[12])
 
template<typename T >
IL2Norm13 (const T x[13])
 
template<typename T >
IL2Norm14 (const T x[14])
 
template<typename T >
IL2Norm15 (const T x[15])
 
template<typename T >
IL2Norm16 (const T x[16])
 
template<typename T >
IL2NormAdv (T a, T b)
 
template<typename T >
IL2NormAdv (const T x[2])
 
template<typename T >
IInfinityNorm (const T *A, int m, int n)
 
void IUnitize (double *x, int n)
 
void IUnitize (float *x, int n)
 
void ISafeUnitize (double *x, int n)
 
void ISafeUnitize (float *x, int n)
 
void IUnitize (const double *x, double *y, int n)
 
void IUnitize (const float *x, float *y, int n)
 
void ISafeUnitize (const double *x, double *y, int n)
 
void ISafeUnitize (float *x, float *y, int n)
 
template<typename T >
void IUnitize2 (T x[2])
 
template<typename T >
void IUnitize3 (T x[3])
 
template<typename T >
void IUnitize4 (T x[4])
 
template<typename T >
void IUnitize5 (T x[5])
 
template<typename T >
void IUnitize6 (T x[6])
 
template<typename T >
void IUnitize7 (T x[7])
 
template<typename T >
void IUnitize8 (T x[8])
 
template<typename T >
void IUnitize9 (T x[9])
 
template<typename T >
void IUnitize10 (T x[10])
 
template<typename T >
void IUnitize11 (T x[11])
 
template<typename T >
void IUnitize12 (T x[12])
 
template<typename T >
void IUnitize13 (T x[13])
 
template<typename T >
void IUnitize14 (T x[14])
 
template<typename T >
void IUnitize15 (T x[15])
 
template<typename T >
void IUnitize16 (T x[16])
 
template<typename T >
void IUnitize2 (const T x[2], T y[2])
 
template<typename T >
void IUnitize3 (const T x[3], T y[3])
 
template<typename T >
void IUnitize4 (const T x[4], T y[4])
 
template<typename T >
void IUnitize5 (const T x[5], T y[5])
 
template<typename T >
void IUnitize6 (const T x[6], T y[6])
 
template<typename T >
void IUnitize7 (const T x[7], T y[7])
 
template<typename T >
void IUnitize8 (const T x[8], T y[8])
 
template<typename T >
void IUnitize9 (const T x[9], T y[9])
 
template<typename T >
void IUnitize10 (const T x[10], T y[10])
 
template<typename T >
void IUnitize11 (const T x[11], T y[11])
 
template<typename T >
void IUnitize12 (const T x[12], T y[12])
 
template<typename T >
void IUnitize13 (const T x[13], T y[13])
 
template<typename T >
void IUnitize14 (const T x[14], T y[14])
 
template<typename T >
void IUnitize15 (const T x[15], T y[15])
 
template<typename T >
void IUnitize16 (const T x[16], T y[16])
 
template<typename T >
void ISignedUnitize2 (T x[2])
 
template<typename T >
void ISignedUnitize3 (T x[3])
 
template<typename T >
void ISignedUnitize4 (T x[4])
 
template<typename T >
void IHomogeneousUnitize (T *x, int n)
 
template<typename T >
void IHomogeneousUnitize2 (T x[2])
 
template<typename T >
void IHomogeneousUnitize3 (T x[3])
 
template<typename T >
void IHomogeneousUnitize4 (T x[4])
 
template<typename T >
void IHomogeneousUnitize9 (T x[9])
 
template<typename T >
void IHomogeneousUnitize (const T *x, T *y, int n)
 
template<typename T >
void IHomogeneousUnitize2 (const T x[2], T y[2])
 
template<typename T >
void IHomogeneousUnitize3 (const T x[3], T y[3])
 
template<typename T >
void IHomogeneousUnitize4 (const T x[4], T y[4])
 
template<typename T >
void IHomogeneousUnitize9 (const T x[9], T y[9])
 
void ICentroid3 (const double *a, int n, double centroid[3])
 
void ICentroid3 (const float *a, int n, float centroid[3])
 
void ICentroid2 (const double *a, int n, double centroid[2])
 
void ICentroid2 (const float *a, int n, float centroid[2])
 
void ICentroid3 (const double *a, int n, double centroid[3], double *distances)
 
void ICentroid3 (const float *a, int n, float centroid[3], float *distances)
 
void ICentroid2 (const double *a, int n, double centroid[2], double *distances)
 
void ICentroid2 (const float *a, int n, float centroid[2], float *distances)
 
template<typename T >
IMinElement (const T *a, int n)
 
template<typename T >
IMaxElement (const T *a, int n)
 
template<typename T >
IMaxDiagonalElement (const T *a, int n)
 
int IMaxIndex (const double *a, int n)
 
int IMaxIndex (const float *a, int n)
 
int IMaxIndex (const int *a, int n)
 
int IMaxAbsIndex (const double *a, int n)
 
int IMaxAbsIndex (const float *a, int n)
 
int IMaxAbsIndex (const int *a, int n)
 
int IMinAbsIndex (const double *a, int n)
 
int IMinAbsIndex (const float *a, int n)
 
int IMinAbsIndex (const int *a, int n)
 
int IMaxAbsIndexInterval (const double *a, int i1, int i2)
 
int IMaxAbsIndexInterval (const float *a, int i1, int i2)
 
int IMaxAbsIndexInterval (const int *a, int i1, int i2)
 
int IMinAbsIndexInterval (const double *a, int i1, int i2)
 
int IMinAbsIndexInterval (const float *a, int i1, int i2)
 
int IMinAbsIndexInterval (const int *a, int i1, int i2)
 
int IMaxAbsIndexIntervalColumn (const double *a, int i1, int i2, int n)
 
int IMaxAbsIndexIntervalColumn (const float *a, int i1, int i2, int n)
 
int IMaxAbsIndexIntervalColumn (const int *a, int i1, int i2, int n)
 
int IMinAbsIndexIntervalColumn (const double *a, int i1, int i2, int n)
 
int IMinAbsIndexIntervalColumn (const float *a, int i1, int i2, int n)
 
int IMinAbsIndexIntervalColumn (const int *a, int i1, int i2, int n)
 
template<typename T >
int IMaxAbsIndexSubdiagonalColumn (const T *A, int i, int n)
 
template<typename T >
void IMinMaxElements (const T *a, int n, T *min_val, T *max_val)
 
template<typename T >
void IHomogenize (const T *x, T *y, int n)
 
template<typename T >
void IHomogenize1 (const T x[1], T y[2])
 
template<typename T >
void IHomogenize2 (const T x[2], T y[3])
 
template<typename T >
void IHomogenize3 (const T x[3], T y[4])
 
template<typename T >
void ICross (const T x[3], const T y[3], T xxy[3])
 
template<typename T >
void IAxiator (const T x[3], T e_x[9])
 
template<typename T >
void ISqrSkewSymmetric3x3 (const T x[3], T e_x2[9])
 
template<typename T >
void IEye (T *A, int n)
 
template<typename T >
void IEye2x2 (T A[4])
 
template<typename T >
void IEye3x3 (T A[9])
 
template<typename T >
void IEye4x4 (T A[16])
 
template<typename T >
void IUpperTriangular2x2 (T a0, T a1, T a3, T A[4])
 
template<typename T >
void IUpperTriangular3x3 (T a0, T a1, T a2, T a4, T a5, T a8, T A[9])
 
double ITrace2x2 (const double A[4])
 
float ITrace2x2 (const float A[4])
 
double ITrace3x3 (const double A[9])
 
float ITrace3x3 (const float A[9])
 
double IDeterminant2x2 (const double A[4])
 
float IDeterminant2x2 (const float A[4])
 
int IDeterminant2x2 (const int A[4])
 
double IDeterminant3x3 (const double A[9])
 
float IDeterminant3x3 (const float A[9])
 
int IDeterminant3x3 (const int A[9])
 
void ISubdeterminants2x4 (const double x[4], const double y[4], double sd[6])
 
void ISubdeterminants2x4 (const float x[4], const float y[4], float sd[6])
 
void ISubdeterminants2x4 (const int x[4], const int y[4], int sd[6])
 
void ISubdeterminants3x4 (const double x[4], const double y[4], const double z[4], double sd[4])
 
void ISubdeterminants3x4 (const float x[4], const float y[4], const float z[4], float sd[4])
 
void ISubdeterminants3x4 (const int x[4], const int y[4], const int z[4], int sd[4])
 
double IDeterminant4x4 (const double A[16])
 
float IDeterminant4x4 (const float A[16])
 
int IDeterminant4x4 (const int A[16])
 
template<typename T >
void ICross (const T x[4], const T y[4], const T z[4], T xxyxz[4])
 
void IInvert2x2 (const double A[4], double Ai[4])
 
void IInvert2x2 (const float A[4], float Ai[4])
 
void IInvert2x2 (const int A[4], double Ai[4])
 
void IInvert3x3 (const double A[9], double Ai[9])
 
void IInvert3x3 (const float A[9], float Ai[9])
 
void IInvert3x3 (const int A[9], double Ai[9])
 
void IInvert3x3UpperTriangular (const double A[9], double Ai[9])
 
void IInvert3x3UpperTriangular (const float A[9], float Ai[9])
 
void IInvert3x3UpperTriangular (const int A[9], double Ai[9])
 
void ISolve2x2 (const double A[4], const double b[2], double x[2])
 
void ISolve2x2 (const float A[4], const float b[2], float x[2])
 
void ISolve3x3 (const double A[9], const double b[3], double x[3])
 
void ISolve3x3 (const float A[9], const float b[3], float x[3])
 
template<typename T >
void ITranspose (T *A, int n)
 
template<typename T >
void ITranspose (const T *A, T *At, int m, int n)
 
template<typename T >
void ITranspose2x2 (T A[4])
 
template<typename T >
void ITranspose2x2 (const T A[4], T At[4])
 
template<typename T >
void ITranspose3x3 (T A[9])
 
template<typename T >
void ITranspose3x3 (const T A[9], T At[9])
 
template<typename T >
void ITranspose4x4 (T A[16])
 
template<typename T >
void ITranspose4x4 (const T A[16], T At[16])
 
template<typename T >
void IAugmentDiagonal (T *A, int n, const T lambda)
 
template<typename T >
void IMultAx (const T *A, const T *x, T *Ax, int m, int n)
 
template<typename T >
void IMultAtx (const T *A, const T *x, T *Atx, int m, int n)
 
template<typename T >
void IMultAx1x3 (const T A[3], const T x[3], T Ax[1])
 
template<typename T >
void IMultAx2x2 (const T A[4], const T x[2], T Ax[2])
 
template<typename T >
void IMultAx2x3 (const T A[6], const T x[3], T Ax[2])
 
template<typename T >
void IMultAx3x3 (const T A[9], const T x[3], T Ax[3])
 
template<typename T >
void IMultAtx3x3 (const T A[9], const T x[3], T Atx[3])
 
template<typename T >
void IMultAx3x4 (const T A[12], const T x[4], T Ax[3])
 
template<typename T >
void IMultAx4x3 (const T A[12], const T x[3], T Ax[4])
 
template<typename T >
void IMultAtx4x3 (const T A[12], const T x[3], T Atx[4])
 
template<typename T >
void IMultAx4x4 (const T A[16], const T x[4], T Ax[4])
 
template<typename T >
void IMultAB (const T *A, const T *B, T *AB, int m, int n, int o)
 
template<typename T >
void IMultAB3x1And1x3 (const T A[3], const T B[3], T AB[9])
 
template<typename T >
void IMultAB2x2And2x2 (const T A[4], const T B[4], T AB[4])
 
template<typename T >
void IMultAB2x3And3x2 (const T A[6], const T B[6], T AB[4])
 
template<typename T >
void IMultAB2x3And3x3 (const T A[6], const T B[9], T AB[6])
 
template<typename T >
void IMultAB2x3And3x4 (const T A[6], const T B[12], T AB[8])
 
template<typename T >
void IMultAB3x3And3x3 (const T A[9], const T B[9], T AB[9])
 
template<typename T >
void IMultAB4x4And4x4 (const T A[16], const T B[16], T AB[16])
 
template<typename T >
void IMultAB4x1And1x4 (const T A[4], const T B[4], T AB[16])
 
template<typename T >
void IMultAB3x3And3x3WAUpperTriangular (const T A[9], const T B[9], T AB[9])
 
template<typename T >
void IMultAB3x3And3x3WBUpperTriangular (const T A[9], const T B[9], T AB[9])
 
template<typename T >
void IMultAB3x3And3x4 (const T A[9], const T B[12], T AB[12])
 
template<typename T >
void IMultAB3x4And4x3 (const T A[12], const T B[12], T AB[9])
 
template<typename T >
void IMultABt3x3And3x3 (const T A[9], const T B[9], T ABt[9])
 
template<typename T >
void IMultABt2x3And2x3 (const T A[6], const T B[6], T ABt[4])
 
template<typename T >
void IMultABt4x4And3x4 (const T A[16], const T B[12], T ABt[12])
 
template<typename T >
void IMultAtA (const T *A, T *AtA, int m, int n)
 
template<typename T >
void IMultAtA2x2 (const T A[4], T AtA[4])
 
template<typename T >
void IMultAtA2x2 (const T *A, T AtA[4], int n)
 
template<typename T >
void IMultAtAnx2 (const T *A, T *AtA, int n)
 
template<typename T >
void IMultAtA3x3 (const T A[9], T AtA[9])
 
template<typename T >
void IMultAtAnx3 (const T *A, T AtA[9], int n)
 
template<typename T >
void IMultAtA4x4 (const T A[16], T AtA[16])
 
template<typename T >
void IMultAtB2x2And2x2 (const T A[4], const T B[4], T AtB[4])
 
template<typename T >
void IMultAtB3x3And3x3 (const T A[9], const T B[9], T AtB[9])
 
template<typename T >
void IMultAAt2x3 (const T A[6], T AAt[4])
 
template<typename T >
void IMultAAt3x3 (const T A[9], T AAt[9])
 
template<typename T >
void IMultAAt4x1 (const T A[4], T AAt[16])
 
template<typename T >
void IMultABC3x3And3x3And3x3 (const T A[9], const T B[9], const T C[9], T ABC[9])
 
template<typename T >
void IMultAtBC3x3And3x3And3x3 (const T A[9], const T B[9], const T C[9], T AtBC[9])
 
template<typename T >
void IMultAB4x4WABlockDiagonal (const T A1[4], const T A2[4], const T B[16], T AB[16])
 
template<typename T >
void ISwapRows (T *A, int r1, int r2, int m, int n)
 
template<typename T >
void ISwapCols (T *A, int c1, int c2, int m, int n)
 
template<typename T >
void ISwapRowsInterval (T *A, int i1, int i2, int r1, int r2, int m, int n)
 
template<typename T >
void ISwapColsInterval (T *A, int i1, int i2, int c1, int c2, int m, int n)
 
template<typename T >
void IShiftHomogeneous3 (T *A, int n)
 
template<typename T >
void IShiftHomogeneous4 (T *A, int n)
 
double IRandCoreD (int *s)
 
int IRandI (int pool_size, int *s)
 
void IRandomSample (int *sample, int n, int pool_size, int *s)
 
template<typename T >
void IRandomizedShuffle (T *A, int n, int l, int *s)
 
template<typename T >
void IRandomizedShuffle (T *A, T *B, int n, int la, int lb, int *s)
 
template<typename T >
void IRandomizedShuffle1 (T *A, int n, int *s)
 
int IRansacTrials (int sample_size, double confidence, double inlierprob)
 
template<typename T , int l, int lp, int k, int s, void(*)(const T *x, const T *xp, T *model) HypogenFunc, void(*)(const T *model, const T *x, const T *xp, int n, int *nr_liner, int *inliers, T *cost, T error_tol) CostFunc, void(*)(T *x, T *xp, int *inliers, T *model, int n, int nr_liner) RefitFunc>
bool RobustBinaryFitRansac (T *x, T *xp, int n, T *model, int *consensus_size, int *inliers, T error_tol, bool re_est_model_w_inliers=false, bool adaptive_trial_count=false, double confidence=0.99, double inlierprob=0.5, int min_nr_inliers=s, bool random_shuffle_inputs=false)
 
template<typename T >
ILineToPointDistance2d (const T *l, const T *p)
 
template<typename T >
void ILineFit2dTotalLeastSquare (T *x, T *l, int n)
 
template<typename T >
void ILineFit2d (const T *x, const T *xp, T *l)
 
template<typename T >
void IPointOnPlaneProjection (const T *pi, const T *p, T *q)
 
template<typename T >
IPlaneToPointDistance (const T *pi, const T *p)
 
template<typename T >
IPlaneToPointDistance (const T *pi, const T *p, T l2_norm3_pi)
 
template<typename T >
IPlaneToPointDistanceWUnitNorm (const T *pi, const T *p)
 
template<typename T >
IPlaneToPointSignedDistanceWUnitNorm (const T *pi, const T *p)
 
template<typename T >
IPlaneToPointDistanceWNormalizedPlaneNorm (const T *pi, const T *p)
 
template<typename T >
IPlaneToPlaneNormalDeltaDegreeZUp (const T *pi_p, const T *pi_q)
 
template<typename T >
void IPlaneFitTotalLeastSquare (T *X, T *pi, int n)
 
template<typename T >
void IPlaneFitTotalLeastSquare3 (T *X, T *pi)
 
template<typename T >
void IPlaneFitTotalLeastSquare (const T *X, T *pi, int n, T *Xp, T *centroid, T *err_stat)
 
template<typename T >
void IPlaneFitTotalLeastSquare (T *X, int *indices, T *pi, int m, int n)
 
template<typename T >
void IPlaneFitTotalLeastSquare (T *X, int *indices, T *pi, T *centroid, int m, int n)
 
template<typename T >
void IPlaneFitTotalLeastSquareAdv (T *X, int *indices, T *para, int m, int n)
 
template<typename T >
void IPlaneFit (const T *X1, const T *X2, const T *X3, T *pi)
 
template<typename T >
void IPlaneFit (const T *Xs, T *pi)
 
template<typename T >
void IPlaneFitDestroyed (T *Xs, T *pi)
 
template<typename T >
void IPlaneFitAdv (const T *Xs, T *para)
 
template<typename T >
void IEigSymmetric2x2Closed (const T *A, T *EV, T *Q)
 
template<typename T >
void IEigSymmetric3x3Closed (const T *A, T *EV, T *Q)
 
template<typename T >
void IProjectThroughExtrinsic (const T *R, const T *t, const T *X, T *x)
 
template<typename T >
void IProjectThroughIntrinsic (const T *K, const T *X, T *x)
 
template<typename T >
void IProjectThroughKRt (const T *K, const T *R, const T *t, const T *X, T *x)
 
template<typename T >
void IUnprojectThroughIntrinsic (const T *K, const T *x, T *X)
 
template<typename T >
bool IPointInFrontOfCamera (const T *X, const T *cop, const T *prv)
 
template<typename T >
void IBackprojectCanonical (const T *x, const T *K, T depth, T *X)
 
template<typename T >
void IBackprojectThroughKRt (const T *x, const T *K, const T *R, const T *t, T depth, T *X)
 
template<typename T >
bool IBackprojectPlaneIntersectionCanonical (const T *x, const T *K, const T *pi, T *X)
 
void IPlaneEucliToSpher (const GroundPlaneLiDAR &src, GroundPlaneSpherical *dst)
 
void IPlaneSpherToEucli (const GroundPlaneSpherical &src, GroundPlaneLiDAR *dst)
 
template<typename T >
int IAssignPointToVoxel (const T *data, T bound_x_min, T bound_x_max, T bound_y_min, T bound_y_max, T bound_z_min, T bound_z_max, T voxel_width_x_rec, T voxel_width_y_rec, int nr_voxel_x, int nr_voxel_y)
 
template<typename T >
bool IDownsampleVoxelGridXY (const VoxelGridXY< T > &src, VoxelGridXY< T > *dst, unsigned int dsf_dim_x, unsigned int dsf_dim_y)
 
template<typename T >
void IGetPointcloudsDimWBound (const T *threeds, int n, int start_offset, int element_size, T *dim_min_x, T *dim_max_x, T *dim_min_y, T *dim_max_y, T *dim_min_z, T *dim_max_z, T bound_min_x, T bound_max_x, T bound_min_y, T bound_max_y, T bound_min_z, T bound_max_z)
 
bool ReadPoseFile (const std::string &filename, Eigen::Affine3d *pose, int *frame_id, double *time_stamp)
 
bool LoadBrownCameraIntrinsic (const std::string &yaml_file, base::BrownCameraDistortionModel *model)
 
bool LoadOmnidirectionalCameraIntrinsics (const std::string &yaml_file, base::OmnidirectionalCameraDistortionModel *model)
 
bool GetFileList (const std::string &path, const std::string &suffix, std::vector< std::string > *files)
 
template<typename PointT >
void TransformPoint (const PointT &point_in, const Eigen::Affine3d &pose, PointT *point_out)
 
template<typename PointT >
void TransformPointCloud (const base::PointCloud< PointT > &cloud_in, const Eigen::Affine3d &pose, base::PointCloud< PointT > *cloud_out)
 
template<typename PointT >
void TransformPointCloud (const Eigen::Affine3d &pose, base::PointCloud< PointT > *cloud_in_out)
 
template<typename PointCloudT >
void ExtractIndicedCloud (const std::shared_ptr< const PointCloudT > cloud, const std::vector< int > &indices, std::shared_ptr< PointCloudT > trans_cloud)
 
template<typename PointT >
void GetMinMaxIn3DWithRange (const base::AttributePointCloud< PointT > &cloud, const size_t range, Eigen::Matrix< typename PointT::Type, 4, 1 > *min_p, Eigen::Matrix< typename PointT::Type, 4, 1 > *max_p)
 
template<typename PointT >
void GetMinMaxIn3D (const base::AttributePointCloud< PointT > &cloud, const base::PointIndices &indices, Eigen::Matrix< typename PointT::Type, 4, 1 > *min_p, Eigen::Matrix< typename PointT::Type, 4, 1 > *max_p)
 
template<typename PointT >
void GetMinMaxIn3D (const base::AttributePointCloud< PointT > &cloud, Eigen::Matrix< typename PointT::Type, 4, 1 > *min_p, Eigen::Matrix< typename PointT::Type, 4, 1 > *max_p)
 
template<typename T >
Eigen::Matrix< T, 3, 1 > CalculateCentroid (const base::AttributePointCloud< base::Point< T >> &cloud)
 
template<typename PointT >
void DownsamplingCircular (const PointT &center_pt, float radius, float neighbour_dist, typename std::shared_ptr< const base::PointCloud< PointT >> cloud, typename std::shared_ptr< base::PointCloud< PointT >> down_cloud)
 
template<typename PointT >
void DownsamplingCircularOrgAll (const PointT &center_pt, int smp_ratio, float radius, int velodyne_model, typename std::shared_ptr< const base::PointCloud< PointT >> cloud, typename std::shared_ptr< base::PointCloud< PointT >> down_cloud)
 
template<typename PointT >
void DownsamplingCircularOrgPartial (const PointT &center_pt, int org_num, int smp_ratio, float radius, int velodyne_model, const typename std::shared_ptr< const base::PointCloud< PointT >> cloud, typename std::shared_ptr< base::PointCloud< PointT >> down_cloud, std::vector< std::pair< int, int >> *all_org_idx_ptr)
 
template<typename PointT >
void DownsamplingRectangleOrgPartial (int org_num, int smp_ratio, float front_range, float side_range, int velodyne_model, typename std::shared_ptr< const base::PointCloud< PointT >> cloud, typename std::shared_ptr< base::PointCloud< PointT >> down_cloud, std::vector< std::pair< int, int >> *all_org_idx_ptr)
 
template<typename PointT >
void DownsamplingRectangleNeighbour (float front_range, float side_range, double max_nei, int velo_model, typename std::shared_ptr< const base::PointCloud< PointT >> cloud, typename std::shared_ptr< base::PointCloud< PointT >> down_cloud)
 

Variables

const int I_DEFAULT_SEED = 432
 

Function Documentation

◆ Calculate2DXYProjectVector()

template<typename T >
Eigen::Matrix<T, 3, 1> apollo::perception::common::Calculate2DXYProjectVector ( const Eigen::Matrix< T, 3, 1 > &  projected_vector,
const Eigen::Matrix< T, 3, 1 > &  project_vector 
)

◆ CalculateBBoxSizeCenter2DXY()

template<typename PointCloudT >
void apollo::perception::common::CalculateBBoxSizeCenter2DXY ( const PointCloudT &  cloud,
const Eigen::Vector3f &  dir,
Eigen::Vector3f *  size,
Eigen::Vector3d *  center,
float  minimum_edge_length = std::numeric_limits<float>::epsilon() 
)

◆ CalculateCentroid()

template<typename T >
Eigen::Matrix<T, 3, 1> apollo::perception::common::CalculateCentroid ( const base::AttributePointCloud< base::Point< T >> &  cloud)

◆ CalculateCosTheta2DXY()

template<typename T >
T apollo::perception::common::CalculateCosTheta2DXY ( const Eigen::Matrix< T, 3, 1 > &  v1,
const Eigen::Matrix< T, 3, 1 > &  v2 
)

◆ CalculateDistAndDirToBoundary() [1/2]

template<typename PointT >
void apollo::perception::common::CalculateDistAndDirToBoundary ( const Eigen::Matrix< typename PointT::Type, 3, 1 > &  pt,
const base::PointCloud< PointT > &  left_boundary,
const base::PointCloud< PointT > &  right_boundary,
typename PointT::Type *  dist,
Eigen::Matrix< typename PointT::Type, 3, 1 > *  dir 
)

◆ CalculateDistAndDirToBoundary() [2/2]

template<typename PointT >
void apollo::perception::common::CalculateDistAndDirToBoundary ( const Eigen::Matrix< typename PointT::Type, 3, 1 > &  pt,
const apollo::common::EigenVector< base::PointCloud< PointT >> &  left_boundary,
const apollo::common::EigenVector< base::PointCloud< PointT >> &  right_boundary,
typename PointT::Type *  dist,
Eigen::Matrix< typename PointT::Type, 3, 1 > *  dir 
)

◆ CalculateDistAndDirToSegs()

template<typename PointT >
bool apollo::perception::common::CalculateDistAndDirToSegs ( const Eigen::Matrix< typename PointT::Type, 3, 1 > &  pt,
const base::PointCloud< PointT > &  segs,
typename PointT::Type *  dist,
Eigen::Matrix< typename PointT::Type, 3, 1 > *  dir 
)

◆ CalculateEuclidenDist()

template<typename PointT >
PointT::Type apollo::perception::common::CalculateEuclidenDist ( const PointT &  pt1,
const PointT &  pt2 
)
inline

◆ CalculateEuclidenDist2DXY()

template<typename PointT >
PointT::Type apollo::perception::common::CalculateEuclidenDist2DXY ( const PointT &  pt1,
const PointT &  pt2 
)
inline

◆ CalculateIou2DXY()

template<typename Type >
Type apollo::perception::common::CalculateIou2DXY ( const Eigen::Matrix< Type, 3, 1 > &  center0,
const Eigen::Matrix< Type, 3, 1 > &  size0,
const Eigen::Matrix< Type, 3, 1 > &  center1,
const Eigen::Matrix< Type, 3, 1 > &  size1 
)

◆ CalculateIOUBBox()

template<typename Type >
Type apollo::perception::common::CalculateIOUBBox ( const base::BBox2D< Type > &  box1,
const base::BBox2D< Type > &  box2 
)

◆ CalculateMostConsistentBBoxDir2DXY()

template<typename Type >
void apollo::perception::common::CalculateMostConsistentBBoxDir2DXY ( const Eigen::Matrix< Type, 3, 1 > &  prev_dir,
Eigen::Matrix< Type, 3, 1 > *  curr_dir 
)

◆ CalculateRotationMat2DXY()

template<typename T >
Eigen::Matrix<T, 3, 3> apollo::perception::common::CalculateRotationMat2DXY ( const Eigen::Matrix< T, 3, 1 > &  v1,
const Eigen::Matrix< T, 3, 1 > &  v2 
)

◆ CalculateTheta2DXY()

template<typename T >
T apollo::perception::common::CalculateTheta2DXY ( const Eigen::Matrix< T, 3, 1 > &  v1,
const Eigen::Matrix< T, 3, 1 > &  v2 
)

◆ ConnectedComponentAnalysis()

void apollo::perception::common::ConnectedComponentAnalysis ( const std::vector< std::vector< int >> &  graph,
std::vector< std::vector< int >> *  components 
)

◆ ConvertCartesiantoPolarCoordinate()

template<typename PointT >
void apollo::perception::common::ConvertCartesiantoPolarCoordinate ( const PointT &  xyz,
typename PointT::Type *  h_angle_in_degree,
typename PointT::Type *  v_angle_in_degree,
typename PointT::Type *  dist 
)

◆ CrossProduct() [1/2]

template<typename Type >
Type apollo::perception::common::CrossProduct ( const Eigen::Matrix< Type, 2, 1 > &  point1,
const Eigen::Matrix< Type, 2, 1 > &  point2,
const Eigen::Matrix< Type, 2, 1 > &  point3 
)
inline

◆ CrossProduct() [2/2]

template<typename PointT >
PointT::Type apollo::perception::common::CrossProduct ( const PointT &  point1,
const PointT &  point2,
const PointT &  point3 
)
inline

◆ DownsamplingCircular()

template<typename PointT >
void apollo::perception::common::DownsamplingCircular ( const PointT &  center_pt,
float  radius,
float  neighbour_dist,
typename std::shared_ptr< const base::PointCloud< PointT >>  cloud,
typename std::shared_ptr< base::PointCloud< PointT >>  down_cloud 
)

◆ DownsamplingCircularOrgAll()

template<typename PointT >
void apollo::perception::common::DownsamplingCircularOrgAll ( const PointT &  center_pt,
int  smp_ratio,
float  radius,
int  velodyne_model,
typename std::shared_ptr< const base::PointCloud< PointT >>  cloud,
typename std::shared_ptr< base::PointCloud< PointT >>  down_cloud 
)

◆ DownsamplingCircularOrgPartial()

template<typename PointT >
void apollo::perception::common::DownsamplingCircularOrgPartial ( const PointT &  center_pt,
int  org_num,
int  smp_ratio,
float  radius,
int  velodyne_model,
const typename std::shared_ptr< const base::PointCloud< PointT >>  cloud,
typename std::shared_ptr< base::PointCloud< PointT >>  down_cloud,
std::vector< std::pair< int, int >> *  all_org_idx_ptr 
)

◆ DownsamplingRectangleNeighbour()

template<typename PointT >
void apollo::perception::common::DownsamplingRectangleNeighbour ( float  front_range,
float  side_range,
double  max_nei,
int  velo_model,
typename std::shared_ptr< const base::PointCloud< PointT >>  cloud,
typename std::shared_ptr< base::PointCloud< PointT >>  down_cloud 
)

◆ DownsamplingRectangleOrgPartial()

template<typename PointT >
void apollo::perception::common::DownsamplingRectangleOrgPartial ( int  org_num,
int  smp_ratio,
float  front_range,
float  side_range,
int  velodyne_model,
typename std::shared_ptr< const base::PointCloud< PointT >>  cloud,
typename std::shared_ptr< base::PointCloud< PointT >>  down_cloud,
std::vector< std::pair< int, int >> *  all_org_idx_ptr 
)

◆ ExtractIndicedCloud()

template<typename PointCloudT >
void apollo::perception::common::ExtractIndicedCloud ( const std::shared_ptr< const PointCloudT >  cloud,
const std::vector< int > &  indices,
std::shared_ptr< PointCloudT >  trans_cloud 
)

◆ GetFileList()

bool apollo::perception::common::GetFileList ( const std::string &  path,
const std::string &  suffix,
std::vector< std::string > *  files 
)

◆ GetMinMaxIn3D() [1/2]

template<typename PointT >
void apollo::perception::common::GetMinMaxIn3D ( const base::AttributePointCloud< PointT > &  cloud,
const base::PointIndices indices,
Eigen::Matrix< typename PointT::Type, 4, 1 > *  min_p,
Eigen::Matrix< typename PointT::Type, 4, 1 > *  max_p 
)

◆ GetMinMaxIn3D() [2/2]

template<typename PointT >
void apollo::perception::common::GetMinMaxIn3D ( const base::AttributePointCloud< PointT > &  cloud,
Eigen::Matrix< typename PointT::Type, 4, 1 > *  min_p,
Eigen::Matrix< typename PointT::Type, 4, 1 > *  max_p 
)

◆ GetMinMaxIn3DWithRange()

template<typename PointT >
void apollo::perception::common::GetMinMaxIn3DWithRange ( const base::AttributePointCloud< PointT > &  cloud,
const size_t  range,
Eigen::Matrix< typename PointT::Type, 4, 1 > *  min_p,
Eigen::Matrix< typename PointT::Type, 4, 1 > *  max_p 
)

◆ IAbs() [1/3]

float apollo::perception::common::IAbs ( float  a)
inline

◆ IAbs() [2/3]

int apollo::perception::common::IAbs ( int  a)
inline

◆ IAbs() [3/3]

double apollo::perception::common::IAbs ( double  a)
inline

◆ IAbsSum()

template<typename T >
T apollo::perception::common::IAbsSum ( const T *  x,
int  n 
)
inline

◆ IAcos() [1/2]

float apollo::perception::common::IAcos ( float  alpha)
inline

◆ IAcos() [2/2]

double apollo::perception::common::IAcos ( double  alpha)
inline

◆ IAdd() [1/3]

template<typename T >
void apollo::perception::common::IAdd ( T *  x,
int  n,
k 
)
inline

◆ IAdd() [2/3]

template<typename T >
void apollo::perception::common::IAdd ( const T *  x,
const T *  y,
int  n,
T *  z 
)
inline

◆ IAdd() [3/3]

template<typename T >
void apollo::perception::common::IAdd ( const T *  x,
T *  y,
int  n 
)
inline

◆ IAdd1() [1/2]

template<typename T >
void apollo::perception::common::IAdd1 ( const T  x[1],
const T  y[1],
z[1] 
)
inline

◆ IAdd1() [2/2]

template<typename T >
void apollo::perception::common::IAdd1 ( const T  x[1],
y[1] 
)
inline

◆ IAdd10() [1/2]

template<typename T >
void apollo::perception::common::IAdd10 ( const T  x[10],
const T  y[10],
z[10] 
)
inline

◆ IAdd10() [2/2]

template<typename T >
void apollo::perception::common::IAdd10 ( const T  x[10],
y[10] 
)
inline

◆ IAdd11() [1/2]

template<typename T >
void apollo::perception::common::IAdd11 ( const T  x[11],
const T  y[11],
z[11] 
)
inline

◆ IAdd11() [2/2]

template<typename T >
void apollo::perception::common::IAdd11 ( const T  x[11],
y[11] 
)
inline

◆ IAdd12() [1/2]

template<typename T >
void apollo::perception::common::IAdd12 ( const T  x[12],
const T  y[12],
z[12] 
)
inline

◆ IAdd12() [2/2]

template<typename T >
void apollo::perception::common::IAdd12 ( const T  x[12],
y[12] 
)
inline

◆ IAdd13() [1/2]

template<typename T >
void apollo::perception::common::IAdd13 ( const T  x[13],
const T  y[13],
z[13] 
)
inline

◆ IAdd13() [2/2]

template<typename T >
void apollo::perception::common::IAdd13 ( const T  x[13],
y[13] 
)
inline

◆ IAdd14() [1/2]

template<typename T >
void apollo::perception::common::IAdd14 ( const T  x[14],
const T  y[14],
z[14] 
)
inline

◆ IAdd14() [2/2]

template<typename T >
void apollo::perception::common::IAdd14 ( const T  x[14],
y[14] 
)
inline

◆ IAdd15() [1/2]

template<typename T >
void apollo::perception::common::IAdd15 ( const T  x[15],
const T  y[15],
z[15] 
)
inline

◆ IAdd15() [2/2]

template<typename T >
void apollo::perception::common::IAdd15 ( const T  x[15],
y[15] 
)
inline

◆ IAdd16() [1/2]

template<typename T >
void apollo::perception::common::IAdd16 ( const T  x[16],
const T  y[16],
z[16] 
)
inline

◆ IAdd16() [2/2]

template<typename T >
void apollo::perception::common::IAdd16 ( const T  x[16],
y[16] 
)
inline

◆ IAdd2() [1/2]

template<typename T >
void apollo::perception::common::IAdd2 ( const T  x[2],
const T  y[2],
z[2] 
)
inline

◆ IAdd2() [2/2]

template<typename T >
void apollo::perception::common::IAdd2 ( const T  x[2],
y[2] 
)
inline

◆ IAdd20() [1/2]

template<typename T >
void apollo::perception::common::IAdd20 ( const T  x[20],
const T  y[20],
z[20] 
)
inline

◆ IAdd20() [2/2]

template<typename T >
void apollo::perception::common::IAdd20 ( const T  x[20],
y[20] 
)
inline

◆ IAdd3() [1/2]

template<typename T >
void apollo::perception::common::IAdd3 ( const T  x[3],
const T  y[3],
z[3] 
)
inline

◆ IAdd3() [2/2]

template<typename T >
void apollo::perception::common::IAdd3 ( const T  x[3],
y[3] 
)
inline

◆ IAdd4() [1/2]

template<typename T >
void apollo::perception::common::IAdd4 ( const T  x[4],
const T  y[4],
z[4] 
)
inline

◆ IAdd4() [2/2]

template<typename T >
void apollo::perception::common::IAdd4 ( const T  x[4],
y[4] 
)
inline

◆ IAdd5() [1/2]

template<typename T >
void apollo::perception::common::IAdd5 ( const T  x[5],
const T  y[5],
z[5] 
)
inline

◆ IAdd5() [2/2]

template<typename T >
void apollo::perception::common::IAdd5 ( const T  x[5],
y[5] 
)
inline

◆ IAdd6() [1/2]

template<typename T >
void apollo::perception::common::IAdd6 ( const T  x[6],
const T  y[6],
z[6] 
)
inline

◆ IAdd6() [2/2]

template<typename T >
void apollo::perception::common::IAdd6 ( const T  x[6],
y[6] 
)
inline

◆ IAdd7() [1/2]

template<typename T >
void apollo::perception::common::IAdd7 ( const T  x[7],
const T  y[7],
z[7] 
)
inline

◆ IAdd7() [2/2]

template<typename T >
void apollo::perception::common::IAdd7 ( const T  x[7],
y[7] 
)
inline

◆ IAdd8() [1/2]

template<typename T >
void apollo::perception::common::IAdd8 ( const T  x[8],
const T  y[8],
z[8] 
)
inline

◆ IAdd8() [2/2]

template<typename T >
void apollo::perception::common::IAdd8 ( const T  x[8],
y[8] 
)
inline

◆ IAdd9() [1/2]

template<typename T >
void apollo::perception::common::IAdd9 ( const T  x[9],
const T  y[9],
z[9] 
)
inline

◆ IAdd9() [2/2]

template<typename T >
void apollo::perception::common::IAdd9 ( const T  x[9],
y[9] 
)
inline

◆ IAddScaled() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled ( const T *  x,
T *  y,
int  n,
k 
)
inline

◆ IAddScaled() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled ( const T *  x,
const T *  y,
T *  z,
int  n,
k 
)
inline

◆ IAddScaled1() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled1 ( const T  x[1],
y[1],
k 
)
inline

◆ IAddScaled1() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled1 ( const T  x[1],
const T  y[1],
z[1],
k 
)
inline

◆ IAddScaled2() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled2 ( const T  x[2],
y[2],
k 
)
inline

◆ IAddScaled2() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled2 ( const T  x[2],
const T  y[2],
z[2],
k 
)
inline

◆ IAddScaled3() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled3 ( const T  x[3],
y[3],
k 
)
inline

◆ IAddScaled3() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled3 ( const T  x[3],
const T  y[3],
z[3],
k 
)
inline

◆ IAddScaled4() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled4 ( const T  x[4],
y[4],
k 
)
inline

◆ IAddScaled4() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled4 ( const T  x[4],
const T  y[4],
z[4],
k 
)
inline

◆ IAddScaled5() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled5 ( const T  x[5],
y[5],
k 
)
inline

◆ IAddScaled5() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled5 ( const T  x[5],
const T  y[5],
z[5],
k 
)
inline

◆ IAddScaled6() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled6 ( const T  x[6],
y[6],
k 
)
inline

◆ IAddScaled6() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled6 ( const T  x[6],
const T  y[6],
z[6],
k 
)
inline

◆ IAddScaled7() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled7 ( const T  x[7],
y[7],
k 
)
inline

◆ IAddScaled7() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled7 ( const T  x[7],
const T  y[7],
z[7],
k 
)
inline

◆ IAddScaled8() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled8 ( const T  x[8],
y[8],
k 
)
inline

◆ IAddScaled8() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled8 ( const T  x[8],
const T  y[8],
z[8],
k 
)
inline

◆ IAddScaled9() [1/2]

template<typename T >
void apollo::perception::common::IAddScaled9 ( const T  x[9],
y[9],
k 
)
inline

◆ IAddScaled9() [2/2]

template<typename T >
void apollo::perception::common::IAddScaled9 ( const T  x[9],
const T  y[9],
z[9],
k 
)
inline

◆ IAlloc()

template<typename T >
T* apollo::perception::common::IAlloc ( int  memory_size)
inline

◆ IAlloc2()

template<typename T >
T** apollo::perception::common::IAlloc2 ( int  m,
int  n 
)
inline

◆ IAlloc3()

template<class T >
T*** apollo::perception::common::IAlloc3 ( int  l,
int  m,
int  n 
)
inline

◆ IAllocAligned()

template<typename T >
T* apollo::perception::common::IAllocAligned ( int  memory_size,
int  alignment_power = 4 
)
inline

◆ IAsin() [1/2]

float apollo::perception::common::IAsin ( float  alpha)
inline

◆ IAsin() [2/2]

double apollo::perception::common::IAsin ( double  alpha)
inline

◆ IAssignPointToVoxel()

template<typename T >
int apollo::perception::common::IAssignPointToVoxel ( const T *  data,
bound_x_min,
bound_x_max,
bound_y_min,
bound_y_max,
bound_z_min,
bound_z_max,
voxel_width_x_rec,
voxel_width_y_rec,
int  nr_voxel_x,
int  nr_voxel_y 
)
inline

◆ IAtan2() [1/2]

float apollo::perception::common::IAtan2 ( float  y,
float  x 
)
inline

◆ IAtan2() [2/2]

double apollo::perception::common::IAtan2 ( double  y,
double  x 
)
inline

◆ IAugmentDiagonal()

template<typename T >
void apollo::perception::common::IAugmentDiagonal ( T *  A,
int  n,
const T  lambda 
)
inline

◆ IAverage()

template<typename T >
T apollo::perception::common::IAverage ( a,
b 
)
inline

◆ IAxiator()

template<typename T >
void apollo::perception::common::IAxiator ( const T  x[3],
e_x[9] 
)
inline

◆ IBackprojectCanonical()

template<typename T >
void apollo::perception::common::IBackprojectCanonical ( const T *  x,
const T *  K,
depth,
T *  X 
)
inline

◆ IBackprojectPlaneIntersectionCanonical()

template<typename T >
bool apollo::perception::common::IBackprojectPlaneIntersectionCanonical ( const T *  x,
const T *  K,
const T *  pi,
T *  X 
)
inline

◆ IBackprojectThroughKRt()

template<typename T >
void apollo::perception::common::IBackprojectThroughKRt ( const T *  x,
const T *  K,
const T *  R,
const T *  t,
depth,
T *  X 
)
inline

◆ ICbrt() [1/4]

float apollo::perception::common::ICbrt ( float  a)
inline

◆ ICbrt() [2/4]

double apollo::perception::common::ICbrt ( int  a)
inline

◆ ICbrt() [3/4]

double apollo::perception::common::ICbrt ( unsigned int  a)
inline

◆ ICbrt() [4/4]

double apollo::perception::common::ICbrt ( double  a)
inline

◆ ICeil() [1/3]

int apollo::perception::common::ICeil ( int  a)
inline

◆ ICeil() [2/3]

int apollo::perception::common::ICeil ( float  a)
inline

◆ ICeil() [3/3]

int apollo::perception::common::ICeil ( double  a)
inline

◆ ICentroid2() [1/4]

void apollo::perception::common::ICentroid2 ( const double *  a,
int  n,
double  centroid[2] 
)
inline

◆ ICentroid2() [2/4]

void apollo::perception::common::ICentroid2 ( const float *  a,
int  n,
float  centroid[2] 
)
inline

◆ ICentroid2() [3/4]

void apollo::perception::common::ICentroid2 ( const double *  a,
int  n,
double  centroid[2],
double *  distances 
)
inline

◆ ICentroid2() [4/4]

void apollo::perception::common::ICentroid2 ( const float *  a,
int  n,
float  centroid[2],
float *  distances 
)
inline

◆ ICentroid3() [1/4]

void apollo::perception::common::ICentroid3 ( const double *  a,
int  n,
double  centroid[3] 
)
inline

◆ ICentroid3() [2/4]

void apollo::perception::common::ICentroid3 ( const float *  a,
int  n,
float  centroid[3] 
)
inline

◆ ICentroid3() [3/4]

void apollo::perception::common::ICentroid3 ( const double *  a,
int  n,
double  centroid[3],
double *  distances 
)
inline

◆ ICentroid3() [4/4]

void apollo::perception::common::ICentroid3 ( const float *  a,
int  n,
float  centroid[3],
float *  distances 
)
inline

◆ ICopy() [1/4]

template<typename T >
void apollo::perception::common::ICopy ( const T *  src,
T *  dst,
int  n 
)
inline

◆ ICopy() [2/4]

template<typename T >
void apollo::perception::common::ICopy ( const T *const *  src,
T **  dst,
int  m,
int  n 
)
inline

◆ ICopy() [3/4]

template<typename T , typename S >
void apollo::perception::common::ICopy ( const T *  src,
S *  dst,
int  n 
)
inline

◆ ICopy() [4/4]

template<typename T , typename S >
void apollo::perception::common::ICopy ( const T *const *  src,
S **  dst,
int  m,
int  n 
)
inline

◆ ICopy1()

template<typename T >
void apollo::perception::common::ICopy1 ( const T  src[1],
dst[1] 
)
inline

◆ ICopy10()

template<typename T >
void apollo::perception::common::ICopy10 ( const T  src[10],
dst[10] 
)
inline

◆ ICopy11()

template<typename T >
void apollo::perception::common::ICopy11 ( const T  src[11],
dst[11] 
)
inline

◆ ICopy12()

template<typename T >
void apollo::perception::common::ICopy12 ( const T  src[12],
dst[12] 
)
inline

◆ ICopy13()

template<typename T >
void apollo::perception::common::ICopy13 ( const T  src[13],
dst[13] 
)
inline

◆ ICopy14()

template<typename T >
void apollo::perception::common::ICopy14 ( const T  src[14],
dst[14] 
)
inline

◆ ICopy15()

template<typename T >
void apollo::perception::common::ICopy15 ( const T  src[15],
dst[15] 
)
inline

◆ ICopy16()

template<typename T >
void apollo::perception::common::ICopy16 ( const T  src[16],
dst[16] 
)
inline

◆ ICopy2()

template<typename T >
void apollo::perception::common::ICopy2 ( const T  src[2],
dst[2] 
)
inline

◆ ICopy3()

template<typename T >
void apollo::perception::common::ICopy3 ( const T  src[3],
dst[3] 
)
inline

◆ ICopy4()

template<typename T >
void apollo::perception::common::ICopy4 ( const T  src[4],
dst[4] 
)
inline

◆ ICopy5()

template<typename T >
void apollo::perception::common::ICopy5 ( const T  src[5],
dst[5] 
)
inline

◆ ICopy6()

template<typename T >
void apollo::perception::common::ICopy6 ( const T  src[6],
dst[6] 
)
inline

◆ ICopy7()

template<typename T >
void apollo::perception::common::ICopy7 ( const T  src[7],
dst[7] 
)
inline

◆ ICopy8()

template<typename T >
void apollo::perception::common::ICopy8 ( const T  src[8],
dst[8] 
)
inline

◆ ICopy9()

template<typename T >
void apollo::perception::common::ICopy9 ( const T  src[9],
dst[9] 
)
inline

◆ ICos() [1/2]

float apollo::perception::common::ICos ( float  alpha)
inline

◆ ICos() [2/2]

double apollo::perception::common::ICos ( double  alpha)
inline

◆ ICross() [1/2]

template<typename T >
void apollo::perception::common::ICross ( const T  x[3],
const T  y[3],
xxy[3] 
)
inline

◆ ICross() [2/2]

template<typename T >
void apollo::perception::common::ICross ( const T  x[4],
const T  y[4],
const T  z[4],
xxyxz[4] 
)
inline

◆ ICub() [1/6]

float apollo::perception::common::ICub ( float  a)
inline

◆ ICub() [2/6]

int apollo::perception::common::ICub ( int  a)
inline

◆ ICub() [3/6]

unsigned int apollo::perception::common::ICub ( unsigned int  a)
inline

◆ ICub() [4/6]

double apollo::perception::common::ICub ( double  a)
inline

◆ ICub() [5/6]

int apollo::perception::common::ICub ( char  a)
inline

◆ ICub() [6/6]

int apollo::perception::common::ICub ( unsigned char  a)
inline

◆ IDegreeToRadians() [1/2]

float apollo::perception::common::IDegreeToRadians ( float  d)
inline

◆ IDegreeToRadians() [2/2]

double apollo::perception::common::IDegreeToRadians ( double  d)
inline

◆ IDeterminant2x2() [1/3]

double apollo::perception::common::IDeterminant2x2 ( const double  A[4])
inline

◆ IDeterminant2x2() [2/3]

float apollo::perception::common::IDeterminant2x2 ( const float  A[4])
inline

◆ IDeterminant2x2() [3/3]

int apollo::perception::common::IDeterminant2x2 ( const int  A[4])
inline

◆ IDeterminant3x3() [1/3]

double apollo::perception::common::IDeterminant3x3 ( const double  A[9])
inline

◆ IDeterminant3x3() [2/3]

float apollo::perception::common::IDeterminant3x3 ( const float  A[9])
inline

◆ IDeterminant3x3() [3/3]

int apollo::perception::common::IDeterminant3x3 ( const int  A[9])
inline

◆ IDeterminant4x4() [1/3]

double apollo::perception::common::IDeterminant4x4 ( const double  A[16])
inline

◆ IDeterminant4x4() [2/3]

float apollo::perception::common::IDeterminant4x4 ( const float  A[16])
inline

◆ IDeterminant4x4() [3/3]

int apollo::perception::common::IDeterminant4x4 ( const int  A[16])
inline

◆ IDiv() [1/8]

float apollo::perception::common::IDiv ( float  a,
float  b 
)
inline

◆ IDiv() [2/8]

float apollo::perception::common::IDiv ( float  a,
int  b 
)
inline

◆ IDiv() [3/8]

float apollo::perception::common::IDiv ( float  a,
unsigned int  b 
)
inline

◆ IDiv() [4/8]

double apollo::perception::common::IDiv ( int  a,
int  b 
)
inline

◆ IDiv() [5/8]

double apollo::perception::common::IDiv ( unsigned int  a,
unsigned int  b 
)
inline

◆ IDiv() [6/8]

double apollo::perception::common::IDiv ( double  a,
double  b 
)
inline

◆ IDiv() [7/8]

double apollo::perception::common::IDiv ( double  a,
int  b 
)
inline

◆ IDiv() [8/8]

double apollo::perception::common::IDiv ( double  a,
unsigned int  b 
)
inline

◆ IDot()

template<typename T >
T apollo::perception::common::IDot ( const T *  x,
const T *  y,
int  n 
)
inline

◆ IDot1()

template<typename T >
T apollo::perception::common::IDot1 ( const T  x[1],
const T  y[1] 
)
inline

◆ IDot10()

template<typename T >
T apollo::perception::common::IDot10 ( const T  x[10],
const T  y[10] 
)
inline

◆ IDot11()

template<typename T >
T apollo::perception::common::IDot11 ( const T  x[11],
const T  y[11] 
)
inline

◆ IDot12()

template<typename T >
T apollo::perception::common::IDot12 ( const T  x[12],
const T  y[12] 
)
inline

◆ IDot13()

template<typename T >
T apollo::perception::common::IDot13 ( const T  x[13],
const T  y[13] 
)
inline

◆ IDot14()

template<typename T >
T apollo::perception::common::IDot14 ( const T  x[14],
const T  y[14] 
)
inline

◆ IDot15()

template<typename T >
T apollo::perception::common::IDot15 ( const T  x[15],
const T  y[15] 
)
inline

◆ IDot16()

template<typename T >
T apollo::perception::common::IDot16 ( const T  x[16],
const T  y[16] 
)
inline

◆ IDot2()

template<typename T >
T apollo::perception::common::IDot2 ( const T  x[2],
const T  y[2] 
)
inline

◆ IDot3()

template<typename T >
T apollo::perception::common::IDot3 ( const T  x[3],
const T  y[3] 
)
inline

◆ IDot4()

template<typename T >
T apollo::perception::common::IDot4 ( const T  x[4],
const T  y[4] 
)
inline

◆ IDot5()

template<typename T >
T apollo::perception::common::IDot5 ( const T  x[5],
const T  y[5] 
)
inline

◆ IDot6()

template<typename T >
T apollo::perception::common::IDot6 ( const T  x[6],
const T  y[6] 
)
inline

◆ IDot7()

template<typename T >
T apollo::perception::common::IDot7 ( const T  x[7],
const T  y[7] 
)
inline

◆ IDot8()

template<typename T >
T apollo::perception::common::IDot8 ( const T  x[8],
const T  y[8] 
)
inline

◆ IDot9()

template<typename T >
T apollo::perception::common::IDot9 ( const T  x[9],
const T  y[9] 
)
inline

◆ IDownsampleVoxelGridXY()

template<typename T >
bool apollo::perception::common::IDownsampleVoxelGridXY ( const VoxelGridXY< T > &  src,
VoxelGridXY< T > *  dst,
unsigned int  dsf_dim_x,
unsigned int  dsf_dim_y 
)

◆ IEigSymmetric2x2Closed()

template<typename T >
void apollo::perception::common::IEigSymmetric2x2Closed ( const T *  A,
T *  EV,
T *  Q 
)
inline

◆ IEigSymmetric3x3Closed()

template<typename T >
void apollo::perception::common::IEigSymmetric3x3Closed ( const T *  A,
T *  EV,
T *  Q 
)
inline

◆ IExp() [1/4]

float apollo::perception::common::IExp ( float  x)
inline

◆ IExp() [2/4]

double apollo::perception::common::IExp ( int  x)
inline

◆ IExp() [3/4]

double apollo::perception::common::IExp ( unsigned int  x)
inline

◆ IExp() [4/4]

double apollo::perception::common::IExp ( double  x)
inline

◆ IEye()

template<typename T >
void apollo::perception::common::IEye ( T *  A,
int  n 
)
inline

◆ IEye2x2()

template<typename T >
void apollo::perception::common::IEye2x2 ( A[4])
inline

◆ IEye3x3()

template<typename T >
void apollo::perception::common::IEye3x3 ( A[9])
inline

◆ IEye4x4()

template<typename T >
void apollo::perception::common::IEye4x4 ( A[16])
inline

◆ IFill()

template<typename T >
void apollo::perception::common::IFill ( T *  a,
int  n,
val 
)
inline

◆ IFill1()

template<typename T >
void apollo::perception::common::IFill1 ( a[1],
val 
)
inline

◆ IFill10()

template<typename T >
void apollo::perception::common::IFill10 ( a[10],
val 
)
inline

◆ IFill11()

template<typename T >
void apollo::perception::common::IFill11 ( a[11],
val 
)
inline

◆ IFill12()

template<typename T >
void apollo::perception::common::IFill12 ( a[12],
val 
)
inline

◆ IFill13()

template<typename T >
void apollo::perception::common::IFill13 ( a[13],
val 
)
inline

◆ IFill14()

template<typename T >
void apollo::perception::common::IFill14 ( a[14],
val 
)
inline

◆ IFill15()

template<typename T >
void apollo::perception::common::IFill15 ( a[15],
val 
)
inline

◆ IFill16()

template<typename T >
void apollo::perception::common::IFill16 ( a[16],
val 
)
inline

◆ IFill2()

template<typename T >
void apollo::perception::common::IFill2 ( a[2],
val 
)
inline

◆ IFill3()

template<typename T >
void apollo::perception::common::IFill3 ( a[3],
val 
)
inline

◆ IFill4()

template<typename T >
void apollo::perception::common::IFill4 ( a[4],
val 
)
inline

◆ IFill5()

template<typename T >
void apollo::perception::common::IFill5 ( a[5],
val 
)
inline

◆ IFill6()

template<typename T >
void apollo::perception::common::IFill6 ( a[6],
val 
)
inline

◆ IFill7()

template<typename T >
void apollo::perception::common::IFill7 ( a[7],
val 
)
inline

◆ IFill8()

template<typename T >
void apollo::perception::common::IFill8 ( a[8],
val 
)
inline

◆ IFill9()

template<typename T >
void apollo::perception::common::IFill9 ( a[9],
val 
)
inline

◆ IFree()

template<typename T >
void apollo::perception::common::IFree ( T **  mem)
inline

◆ IFree2()

template<typename T >
void apollo::perception::common::IFree2 ( T ***  A)
inline

◆ IFreeAligned()

template<typename T >
void apollo::perception::common::IFreeAligned ( T **  mem)
inline

◆ IGaussian2D() [1/2]

void apollo::perception::common::IGaussian2D ( float *  kernel,
int  n,
const float  sigma 
)
inline

◆ IGaussian2D() [2/2]

void apollo::perception::common::IGaussian2D ( double *  kernel,
int  n,
const double  sigma 
)
inline

◆ IGetPointcloudsDimWBound()

template<typename T >
void apollo::perception::common::IGetPointcloudsDimWBound ( const T *  threeds,
int  n,
int  start_offset,
int  element_size,
T *  dim_min_x,
T *  dim_max_x,
T *  dim_min_y,
T *  dim_max_y,
T *  dim_min_z,
T *  dim_max_z,
bound_min_x,
bound_max_x,
bound_min_y,
bound_max_y,
bound_min_z,
bound_max_z 
)
inline

◆ IHamming()

unsigned int apollo::perception::common::IHamming ( unsigned int  a,
unsigned int  b 
)
inline

◆ IHammingDiff()

unsigned int apollo::perception::common::IHammingDiff ( const unsigned int *  x,
const unsigned int *  y,
int  n 
)
inline

◆ IHammingDiff16()

unsigned int apollo::perception::common::IHammingDiff16 ( const unsigned int  x[16],
const unsigned int  y[16] 
)
inline

◆ IHammingDiff2()

unsigned int apollo::perception::common::IHammingDiff2 ( const unsigned int  x[2],
const unsigned int  y[2] 
)
inline

◆ IHammingDiff4()

unsigned int apollo::perception::common::IHammingDiff4 ( const unsigned int  x[4],
const unsigned int  y[4] 
)
inline

◆ IHammingDiff8()

unsigned int apollo::perception::common::IHammingDiff8 ( const unsigned int  x[8],
const unsigned int  y[8] 
)
inline

◆ IHammingLut()

unsigned int apollo::perception::common::IHammingLut ( unsigned int  a,
unsigned int  b 
)
inline

◆ IHomogeneousUnitize() [1/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize ( T *  x,
int  n 
)
inline

◆ IHomogeneousUnitize() [2/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize ( const T *  x,
T *  y,
int  n 
)
inline

◆ IHomogeneousUnitize2() [1/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize2 ( x[2])
inline

◆ IHomogeneousUnitize2() [2/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize2 ( const T  x[2],
y[2] 
)
inline

◆ IHomogeneousUnitize3() [1/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize3 ( x[3])
inline

◆ IHomogeneousUnitize3() [2/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize3 ( const T  x[3],
y[3] 
)
inline

◆ IHomogeneousUnitize4() [1/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize4 ( x[4])
inline

◆ IHomogeneousUnitize4() [2/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize4 ( const T  x[4],
y[4] 
)
inline

◆ IHomogeneousUnitize9() [1/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize9 ( x[9])
inline

◆ IHomogeneousUnitize9() [2/2]

template<typename T >
void apollo::perception::common::IHomogeneousUnitize9 ( const T  x[9],
y[9] 
)
inline

◆ IHomogenize()

template<typename T >
void apollo::perception::common::IHomogenize ( const T *  x,
T *  y,
int  n 
)
inline

◆ IHomogenize1()

template<typename T >
void apollo::perception::common::IHomogenize1 ( const T  x[1],
y[2] 
)
inline

◆ IHomogenize2()

template<typename T >
void apollo::perception::common::IHomogenize2 ( const T  x[2],
y[3] 
)
inline

◆ IHomogenize3()

template<typename T >
void apollo::perception::common::IHomogenize3 ( const T  x[3],
y[4] 
)
inline

◆ IIndexedShuffle() [1/2]

template<typename T >
void apollo::perception::common::IIndexedShuffle ( T *  a,
int *  indices,
int  n,
int  element_size,
int  nr_indexed_elements,
bool  is_sort_indices = true 
)
inline

◆ IIndexedShuffle() [2/2]

template<typename T >
void apollo::perception::common::IIndexedShuffle ( T *  a,
T *  b,
int *  indices,
int  n,
int  element_size_a,
int  element_size_b,
int  nr_indexed_elements,
bool  is_sort_indices = true 
)
inline

◆ IInfinityNorm()

template<typename T >
T apollo::perception::common::IInfinityNorm ( const T *  A,
int  m,
int  n 
)
inline

◆ IInsertionSort()

template<typename T , bool Compare>
void apollo::perception::common::IInsertionSort ( T *  a,
int  n 
)
inline

◆ IInterval()

template<typename T >
T apollo::perception::common::IInterval ( a,
min_val,
max_val 
)
inline

◆ IIntervalHalfopen()

template<typename T >
T apollo::perception::common::IIntervalHalfopen ( a,
min_val,
max_val 
)
inline

◆ IInvert2x2() [1/3]

void apollo::perception::common::IInvert2x2 ( const double  A[4],
double  Ai[4] 
)
inline

◆ IInvert2x2() [2/3]

void apollo::perception::common::IInvert2x2 ( const float  A[4],
float  Ai[4] 
)
inline

◆ IInvert2x2() [3/3]

void apollo::perception::common::IInvert2x2 ( const int  A[4],
double  Ai[4] 
)
inline

◆ IInvert3x3() [1/3]

void apollo::perception::common::IInvert3x3 ( const double  A[9],
double  Ai[9] 
)
inline

◆ IInvert3x3() [2/3]

void apollo::perception::common::IInvert3x3 ( const float  A[9],
float  Ai[9] 
)
inline

◆ IInvert3x3() [3/3]

void apollo::perception::common::IInvert3x3 ( const int  A[9],
double  Ai[9] 
)
inline

◆ IInvert3x3UpperTriangular() [1/3]

void apollo::perception::common::IInvert3x3UpperTriangular ( const double  A[9],
double  Ai[9] 
)
inline

◆ IInvert3x3UpperTriangular() [2/3]

void apollo::perception::common::IInvert3x3UpperTriangular ( const float  A[9],
float  Ai[9] 
)
inline

◆ IInvert3x3UpperTriangular() [3/3]

void apollo::perception::common::IInvert3x3UpperTriangular ( const int  A[9],
double  Ai[9] 
)
inline

◆ IL2Norm() [1/4]

double apollo::perception::common::IL2Norm ( const unsigned char *  x,
int  n 
)
inline

◆ IL2Norm() [2/4]

double apollo::perception::common::IL2Norm ( const int *  x,
int  n 
)
inline

◆ IL2Norm() [3/4]

float apollo::perception::common::IL2Norm ( const float *  x,
int  n 
)
inline

◆ IL2Norm() [4/4]

double apollo::perception::common::IL2Norm ( const double *  x,
int  n 
)
inline

◆ IL2Norm1()

template<typename T >
T apollo::perception::common::IL2Norm1 ( const T  x[1])
inline

◆ IL2Norm10()

template<typename T >
T apollo::perception::common::IL2Norm10 ( const T  x[10])
inline

◆ IL2Norm11()

template<typename T >
T apollo::perception::common::IL2Norm11 ( const T  x[11])
inline

◆ IL2Norm12()

template<typename T >
T apollo::perception::common::IL2Norm12 ( const T  x[12])
inline

◆ IL2Norm13()

template<typename T >
T apollo::perception::common::IL2Norm13 ( const T  x[13])
inline

◆ IL2Norm14()

template<typename T >
T apollo::perception::common::IL2Norm14 ( const T  x[14])
inline

◆ IL2Norm15()

template<typename T >
T apollo::perception::common::IL2Norm15 ( const T  x[15])
inline

◆ IL2Norm16()

template<typename T >
T apollo::perception::common::IL2Norm16 ( const T  x[16])
inline

◆ IL2Norm2()

template<typename T >
T apollo::perception::common::IL2Norm2 ( const T  x[2])
inline

◆ IL2Norm3()

template<typename T >
T apollo::perception::common::IL2Norm3 ( const T  x[3])
inline

◆ IL2Norm4()

template<typename T >
T apollo::perception::common::IL2Norm4 ( const T  x[4])
inline

◆ IL2Norm5()

template<typename T >
T apollo::perception::common::IL2Norm5 ( const T  x[5])
inline

◆ IL2Norm6()

template<typename T >
T apollo::perception::common::IL2Norm6 ( const T  x[6])
inline

◆ IL2Norm7()

template<typename T >
T apollo::perception::common::IL2Norm7 ( const T  x[7])
inline

◆ IL2Norm8()

template<typename T >
T apollo::perception::common::IL2Norm8 ( const T  x[8])
inline

◆ IL2Norm9()

template<typename T >
T apollo::perception::common::IL2Norm9 ( const T  x[9])
inline

◆ IL2NormAdv() [1/2]

template<typename T >
T apollo::perception::common::IL2NormAdv ( a,
b 
)
inline

◆ IL2NormAdv() [2/2]

template<typename T >
T apollo::perception::common::IL2NormAdv ( const T  x[2])
inline

◆ ILarger()

template<typename T >
bool apollo::perception::common::ILarger ( const T &  a,
const T &  b 
)
inline

◆ ILess()

template<typename T >
bool apollo::perception::common::ILess ( const T &  a,
const T &  b 
)
inline

◆ ILineFit2d()

template<typename T >
void apollo::perception::common::ILineFit2d ( const T *  x,
const T *  xp,
T *  l 
)
inline

◆ ILineFit2dTotalLeastSquare()

template<typename T >
void apollo::perception::common::ILineFit2dTotalLeastSquare ( T *  x,
T *  l,
int  n 
)
inline

◆ ILineToPointDistance2d()

template<typename T >
T apollo::perception::common::ILineToPointDistance2d ( const T *  l,
const T *  p 
)
inline

◆ ILog() [1/4]

float apollo::perception::common::ILog ( float  x)
inline

◆ ILog() [2/4]

double apollo::perception::common::ILog ( int  x)
inline

◆ ILog() [3/4]

double apollo::perception::common::ILog ( unsigned int  x)
inline

◆ ILog() [4/4]

double apollo::perception::common::ILog ( double  x)
inline

◆ IMakeConstReference()

template<typename T >
void apollo::perception::common::IMakeConstReference ( const T *  a,
const T **  p,
int  m,
int  n 
)
inline

◆ IMakeConstReference12x12()

template<typename T >
void apollo::perception::common::IMakeConstReference12x12 ( const T  a[144],
const T *  p[12] 
)
inline

◆ IMakeConstReference2x2()

template<typename T >
void apollo::perception::common::IMakeConstReference2x2 ( const T  a[4],
const T *  p[2] 
)
inline

◆ IMakeConstReference3x3()

template<typename T >
void apollo::perception::common::IMakeConstReference3x3 ( const T  a[9],
const T *  p[3] 
)
inline

◆ IMakeConstReference4x4()

template<typename T >
void apollo::perception::common::IMakeConstReference4x4 ( const T  a[16],
const T *  p[4] 
)
inline

◆ IMakeConstReference4x9()

template<typename T >
void apollo::perception::common::IMakeConstReference4x9 ( const T  a[36],
const T *  p[4] 
)
inline

◆ IMakeConstReference5x9()

template<typename T >
void apollo::perception::common::IMakeConstReference5x9 ( const T  a[45],
const T *  p[5] 
)
inline

◆ IMakeConstReference9x9()

template<typename T >
void apollo::perception::common::IMakeConstReference9x9 ( const T  a[81],
const T *  p[9] 
)
inline

◆ IMakeReference() [1/2]

template<typename T >
void apollo::perception::common::IMakeReference ( T *  a,
T **  p,
int  m,
int  n 
)
inline

◆ IMakeReference() [2/2]

template<typename T >
void apollo::perception::common::IMakeReference ( T *  a,
T ***  p,
int  l,
int  m,
int  n 
)
inline

◆ IMakeReference12x12()

template<typename T >
void apollo::perception::common::IMakeReference12x12 ( a[144],
T *  p[12] 
)
inline

◆ IMakeReference2x2()

template<typename T >
void apollo::perception::common::IMakeReference2x2 ( a[4],
T *  p[2] 
)
inline

◆ IMakeReference3x3()

template<typename T >
void apollo::perception::common::IMakeReference3x3 ( a[9],
T *  p[3] 
)
inline

◆ IMakeReference4x4()

template<typename T >
void apollo::perception::common::IMakeReference4x4 ( a[16],
T *  p[4] 
)
inline

◆ IMakeReference4x9()

template<typename T >
void apollo::perception::common::IMakeReference4x9 ( a[36],
T *  p[4] 
)
inline

◆ IMakeReference5x9()

template<typename T >
void apollo::perception::common::IMakeReference5x9 ( a[45],
T *  p[5] 
)
inline

◆ IMakeReference9x9()

template<typename T >
void apollo::perception::common::IMakeReference9x9 ( a[81],
T *  p[9] 
)
inline

◆ IMax()

template<typename T >
T apollo::perception::common::IMax ( a,
b 
)
inline

◆ IMaxAbsIndex() [1/3]

int apollo::perception::common::IMaxAbsIndex ( const double *  a,
int  n 
)
inline

◆ IMaxAbsIndex() [2/3]

int apollo::perception::common::IMaxAbsIndex ( const float *  a,
int  n 
)
inline

◆ IMaxAbsIndex() [3/3]

int apollo::perception::common::IMaxAbsIndex ( const int *  a,
int  n 
)
inline

◆ IMaxAbsIndexInterval() [1/3]

int apollo::perception::common::IMaxAbsIndexInterval ( const double *  a,
int  i1,
int  i2 
)
inline

◆ IMaxAbsIndexInterval() [2/3]

int apollo::perception::common::IMaxAbsIndexInterval ( const float *  a,
int  i1,
int  i2 
)
inline

◆ IMaxAbsIndexInterval() [3/3]

int apollo::perception::common::IMaxAbsIndexInterval ( const int *  a,
int  i1,
int  i2 
)
inline

◆ IMaxAbsIndexIntervalColumn() [1/3]

int apollo::perception::common::IMaxAbsIndexIntervalColumn ( const double *  a,
int  i1,
int  i2,
int  n 
)
inline

◆ IMaxAbsIndexIntervalColumn() [2/3]

int apollo::perception::common::IMaxAbsIndexIntervalColumn ( const float *  a,
int  i1,
int  i2,
int  n 
)
inline

◆ IMaxAbsIndexIntervalColumn() [3/3]

int apollo::perception::common::IMaxAbsIndexIntervalColumn ( const int *  a,
int  i1,
int  i2,
int  n 
)
inline

◆ IMaxAbsIndexSubdiagonalColumn()

template<typename T >
int apollo::perception::common::IMaxAbsIndexSubdiagonalColumn ( const T *  A,
int  i,
int  n 
)
inline

◆ IMaxDiagonalElement()

template<typename T >
T apollo::perception::common::IMaxDiagonalElement ( const T *  a,
int  n 
)
inline

◆ IMaxElement()

template<typename T >
T apollo::perception::common::IMaxElement ( const T *  a,
int  n 
)
inline

◆ IMaxIndex() [1/3]

int apollo::perception::common::IMaxIndex ( const double *  a,
int  n 
)
inline

◆ IMaxIndex() [2/3]

int apollo::perception::common::IMaxIndex ( const float *  a,
int  n 
)
inline

◆ IMaxIndex() [3/3]

int apollo::perception::common::IMaxIndex ( const int *  a,
int  n 
)
inline

◆ IMean()

template<typename T >
T apollo::perception::common::IMean ( const T *  x,
int  n 
)
inline

◆ IMean10()

template<typename T >
T apollo::perception::common::IMean10 ( const T  x[10])
inline

◆ IMean11()

template<typename T >
T apollo::perception::common::IMean11 ( const T  x[11])
inline

◆ IMean12()

template<typename T >
T apollo::perception::common::IMean12 ( const T  x[12])
inline

◆ IMean13()

template<typename T >
T apollo::perception::common::IMean13 ( const T  x[13])
inline

◆ IMean14()

template<typename T >
T apollo::perception::common::IMean14 ( const T  x[14])
inline

◆ IMean15()

template<typename T >
T apollo::perception::common::IMean15 ( const T  x[15])
inline

◆ IMean16()

template<typename T >
T apollo::perception::common::IMean16 ( const T  x[16])
inline

◆ IMean2()

template<typename T >
T apollo::perception::common::IMean2 ( const T  x[2])
inline

◆ IMean3()

template<typename T >
T apollo::perception::common::IMean3 ( const T  x[3])
inline

◆ IMean4()

template<typename T >
T apollo::perception::common::IMean4 ( const T  x[4])
inline

◆ IMean5()

template<typename T >
T apollo::perception::common::IMean5 ( const T  x[5])
inline

◆ IMean6()

template<typename T >
T apollo::perception::common::IMean6 ( const T  x[6])
inline

◆ IMean7()

template<typename T >
T apollo::perception::common::IMean7 ( const T  x[7])
inline

◆ IMean8()

template<typename T >
T apollo::perception::common::IMean8 ( const T  x[8])
inline

◆ IMean9()

template<typename T >
T apollo::perception::common::IMean9 ( const T  x[9])
inline

◆ IMeanU()

int apollo::perception::common::IMeanU ( const unsigned char *  x,
int  n 
)
inline

◆ IMedian3()

template<typename T >
T apollo::perception::common::IMedian3 ( const T &  a,
const T &  b,
const T &  c 
)
inline

◆ IMin()

template<typename T >
T apollo::perception::common::IMin ( a,
b 
)
inline

◆ IMinAbsIndex() [1/3]

int apollo::perception::common::IMinAbsIndex ( const double *  a,
int  n 
)
inline

◆ IMinAbsIndex() [2/3]

int apollo::perception::common::IMinAbsIndex ( const float *  a,
int  n 
)
inline

◆ IMinAbsIndex() [3/3]

int apollo::perception::common::IMinAbsIndex ( const int *  a,
int  n 
)
inline

◆ IMinAbsIndexInterval() [1/3]

int apollo::perception::common::IMinAbsIndexInterval ( const double *  a,
int  i1,
int  i2 
)
inline

◆ IMinAbsIndexInterval() [2/3]

int apollo::perception::common::IMinAbsIndexInterval ( const float *  a,
int  i1,
int  i2 
)
inline

◆ IMinAbsIndexInterval() [3/3]

int apollo::perception::common::IMinAbsIndexInterval ( const int *  a,
int  i1,
int  i2 
)
inline

◆ IMinAbsIndexIntervalColumn() [1/3]

int apollo::perception::common::IMinAbsIndexIntervalColumn ( const double *  a,
int  i1,
int  i2,
int  n 
)
inline

◆ IMinAbsIndexIntervalColumn() [2/3]

int apollo::perception::common::IMinAbsIndexIntervalColumn ( const float *  a,
int  i1,
int  i2,
int  n 
)
inline

◆ IMinAbsIndexIntervalColumn() [3/3]

int apollo::perception::common::IMinAbsIndexIntervalColumn ( const int *  a,
int  i1,
int  i2,
int  n 
)
inline

◆ IMinElement()

template<typename T >
T apollo::perception::common::IMinElement ( const T *  a,
int  n 
)
inline

◆ IMinMaxElements()

template<typename T >
void apollo::perception::common::IMinMaxElements ( const T *  a,
int  n,
T *  min_val,
T *  max_val 
)
inline

◆ IMove()

template<typename T >
void apollo::perception::common::IMove ( const T &  a,
T *  b 
)
inline

◆ IMultAAt2x3()

template<typename T >
void apollo::perception::common::IMultAAt2x3 ( const T  A[6],
AAt[4] 
)
inline

◆ IMultAAt3x3()

template<typename T >
void apollo::perception::common::IMultAAt3x3 ( const T  A[9],
AAt[9] 
)
inline

◆ IMultAAt4x1()

template<typename T >
void apollo::perception::common::IMultAAt4x1 ( const T  A[4],
AAt[16] 
)
inline

◆ IMultAB()

template<typename T >
void apollo::perception::common::IMultAB ( const T *  A,
const T *  B,
T *  AB,
int  m,
int  n,
int  o 
)
inline

◆ IMultAB2x2And2x2()

template<typename T >
void apollo::perception::common::IMultAB2x2And2x2 ( const T  A[4],
const T  B[4],
AB[4] 
)
inline

◆ IMultAB2x3And3x2()

template<typename T >
void apollo::perception::common::IMultAB2x3And3x2 ( const T  A[6],
const T  B[6],
AB[4] 
)
inline

◆ IMultAB2x3And3x3()

template<typename T >
void apollo::perception::common::IMultAB2x3And3x3 ( const T  A[6],
const T  B[9],
AB[6] 
)
inline

◆ IMultAB2x3And3x4()

template<typename T >
void apollo::perception::common::IMultAB2x3And3x4 ( const T  A[6],
const T  B[12],
AB[8] 
)
inline

◆ IMultAB3x1And1x3()

template<typename T >
void apollo::perception::common::IMultAB3x1And1x3 ( const T  A[3],
const T  B[3],
AB[9] 
)
inline

◆ IMultAB3x3And3x3()

template<typename T >
void apollo::perception::common::IMultAB3x3And3x3 ( const T  A[9],
const T  B[9],
AB[9] 
)
inline

◆ IMultAB3x3And3x3WAUpperTriangular()

template<typename T >
void apollo::perception::common::IMultAB3x3And3x3WAUpperTriangular ( const T  A[9],
const T  B[9],
AB[9] 
)
inline

◆ IMultAB3x3And3x3WBUpperTriangular()

template<typename T >
void apollo::perception::common::IMultAB3x3And3x3WBUpperTriangular ( const T  A[9],
const T  B[9],
AB[9] 
)
inline

◆ IMultAB3x3And3x4()

template<typename T >
void apollo::perception::common::IMultAB3x3And3x4 ( const T  A[9],
const T  B[12],
AB[12] 
)
inline

◆ IMultAB3x4And4x3()

template<typename T >
void apollo::perception::common::IMultAB3x4And4x3 ( const T  A[12],
const T  B[12],
AB[9] 
)
inline

◆ IMultAB4x1And1x4()

template<typename T >
void apollo::perception::common::IMultAB4x1And1x4 ( const T  A[4],
const T  B[4],
AB[16] 
)
inline

◆ IMultAB4x4And4x4()

template<typename T >
void apollo::perception::common::IMultAB4x4And4x4 ( const T  A[16],
const T  B[16],
AB[16] 
)
inline

◆ IMultAB4x4WABlockDiagonal()

template<typename T >
void apollo::perception::common::IMultAB4x4WABlockDiagonal ( const T  A1[4],
const T  A2[4],
const T  B[16],
AB[16] 
)
inline

◆ IMultABC3x3And3x3And3x3()

template<typename T >
void apollo::perception::common::IMultABC3x3And3x3And3x3 ( const T  A[9],
const T  B[9],
const T  C[9],
ABC[9] 
)
inline

◆ IMultABt2x3And2x3()

template<typename T >
void apollo::perception::common::IMultABt2x3And2x3 ( const T  A[6],
const T  B[6],
ABt[4] 
)
inline

◆ IMultABt3x3And3x3()

template<typename T >
void apollo::perception::common::IMultABt3x3And3x3 ( const T  A[9],
const T  B[9],
ABt[9] 
)
inline

◆ IMultABt4x4And3x4()

template<typename T >
void apollo::perception::common::IMultABt4x4And3x4 ( const T  A[16],
const T  B[12],
ABt[12] 
)
inline

◆ IMultAtA()

template<typename T >
void apollo::perception::common::IMultAtA ( const T *  A,
T *  AtA,
int  m,
int  n 
)
inline

◆ IMultAtA2x2() [1/2]

template<typename T >
void apollo::perception::common::IMultAtA2x2 ( const T  A[4],
AtA[4] 
)
inline

◆ IMultAtA2x2() [2/2]

template<typename T >
void apollo::perception::common::IMultAtA2x2 ( const T *  A,
AtA[4],
int  n 
)
inline

◆ IMultAtA3x3()

template<typename T >
void apollo::perception::common::IMultAtA3x3 ( const T  A[9],
AtA[9] 
)
inline

◆ IMultAtA4x4()

template<typename T >
void apollo::perception::common::IMultAtA4x4 ( const T  A[16],
AtA[16] 
)
inline

◆ IMultAtAnx2()

template<typename T >
void apollo::perception::common::IMultAtAnx2 ( const T *  A,
T *  AtA,
int  n 
)
inline

◆ IMultAtAnx3()

template<typename T >
void apollo::perception::common::IMultAtAnx3 ( const T *  A,
AtA[9],
int  n 
)
inline

◆ IMultAtB2x2And2x2()

template<typename T >
void apollo::perception::common::IMultAtB2x2And2x2 ( const T  A[4],
const T  B[4],
AtB[4] 
)
inline

◆ IMultAtB3x3And3x3()

template<typename T >
void apollo::perception::common::IMultAtB3x3And3x3 ( const T  A[9],
const T  B[9],
AtB[9] 
)
inline

◆ IMultAtBC3x3And3x3And3x3()

template<typename T >
void apollo::perception::common::IMultAtBC3x3And3x3And3x3 ( const T  A[9],
const T  B[9],
const T  C[9],
AtBC[9] 
)
inline

◆ IMultAtx()

template<typename T >
void apollo::perception::common::IMultAtx ( const T *  A,
const T *  x,
T *  Atx,
int  m,
int  n 
)
inline

◆ IMultAtx3x3()

template<typename T >
void apollo::perception::common::IMultAtx3x3 ( const T  A[9],
const T  x[3],
Atx[3] 
)
inline

◆ IMultAtx4x3()

template<typename T >
void apollo::perception::common::IMultAtx4x3 ( const T  A[12],
const T  x[3],
Atx[4] 
)
inline

◆ IMultAx()

template<typename T >
void apollo::perception::common::IMultAx ( const T *  A,
const T *  x,
T *  Ax,
int  m,
int  n 
)
inline

◆ IMultAx1x3()

template<typename T >
void apollo::perception::common::IMultAx1x3 ( const T  A[3],
const T  x[3],
Ax[1] 
)
inline

◆ IMultAx2x2()

template<typename T >
void apollo::perception::common::IMultAx2x2 ( const T  A[4],
const T  x[2],
Ax[2] 
)
inline

◆ IMultAx2x3()

template<typename T >
void apollo::perception::common::IMultAx2x3 ( const T  A[6],
const T  x[3],
Ax[2] 
)
inline

◆ IMultAx3x3()

template<typename T >
void apollo::perception::common::IMultAx3x3 ( const T  A[9],
const T  x[3],
Ax[3] 
)
inline

◆ IMultAx3x4()

template<typename T >
void apollo::perception::common::IMultAx3x4 ( const T  A[12],
const T  x[4],
Ax[3] 
)
inline

◆ IMultAx4x3()

template<typename T >
void apollo::perception::common::IMultAx4x3 ( const T  A[12],
const T  x[3],
Ax[4] 
)
inline

◆ IMultAx4x4()

template<typename T >
void apollo::perception::common::IMultAx4x4 ( const T  A[16],
const T  x[4],
Ax[4] 
)
inline

◆ INeg()

template<typename T >
void apollo::perception::common::INeg ( T *  x,
int  n 
)
inline

◆ INeg1() [1/2]

template<typename T >
void apollo::perception::common::INeg1 ( x[1])
inline

◆ INeg1() [2/2]

template<typename T >
void apollo::perception::common::INeg1 ( const T  x[1],
y[1] 
)
inline

◆ INeg10() [1/2]

template<typename T >
void apollo::perception::common::INeg10 ( x[10])
inline

◆ INeg10() [2/2]

template<typename T >
void apollo::perception::common::INeg10 ( const T  x[10],
y[10] 
)
inline

◆ INeg11() [1/2]

template<typename T >
void apollo::perception::common::INeg11 ( x[11])
inline

◆ INeg11() [2/2]

template<typename T >
void apollo::perception::common::INeg11 ( const T  x[11],
y[11] 
)
inline

◆ INeg12() [1/2]

template<typename T >
void apollo::perception::common::INeg12 ( x[12])
inline

◆ INeg12() [2/2]

template<typename T >
void apollo::perception::common::INeg12 ( const T  x[12],
y[12] 
)
inline

◆ INeg13() [1/2]

template<typename T >
void apollo::perception::common::INeg13 ( x[13])
inline

◆ INeg13() [2/2]

template<typename T >
void apollo::perception::common::INeg13 ( const T  x[13],
y[13] 
)
inline

◆ INeg14() [1/2]

template<typename T >
void apollo::perception::common::INeg14 ( x[14])
inline

◆ INeg14() [2/2]

template<typename T >
void apollo::perception::common::INeg14 ( const T  x[14],
y[14] 
)
inline

◆ INeg15() [1/2]

template<typename T >
void apollo::perception::common::INeg15 ( x[15])
inline

◆ INeg15() [2/2]

template<typename T >
void apollo::perception::common::INeg15 ( const T  x[15],
y[15] 
)
inline

◆ INeg16() [1/2]

template<typename T >
void apollo::perception::common::INeg16 ( x[16])
inline

◆ INeg16() [2/2]

template<typename T >
void apollo::perception::common::INeg16 ( const T  x[16],
y[16] 
)
inline

◆ INeg2() [1/2]

template<typename T >
void apollo::perception::common::INeg2 ( x[2])
inline

◆ INeg2() [2/2]

template<typename T >
void apollo::perception::common::INeg2 ( const T  x[2],
y[2] 
)
inline

◆ INeg3() [1/2]

template<typename T >
void apollo::perception::common::INeg3 ( x[3])
inline

◆ INeg3() [2/2]

template<typename T >
void apollo::perception::common::INeg3 ( const T  x[3],
y[3] 
)
inline

◆ INeg4() [1/2]

template<typename T >
void apollo::perception::common::INeg4 ( x[4])
inline

◆ INeg4() [2/2]

template<typename T >
void apollo::perception::common::INeg4 ( const T  x[4],
y[4] 
)
inline

◆ INeg5() [1/2]

template<typename T >
void apollo::perception::common::INeg5 ( x[5])
inline

◆ INeg5() [2/2]

template<typename T >
void apollo::perception::common::INeg5 ( const T  x[5],
y[5] 
)
inline

◆ INeg6() [1/2]

template<typename T >
void apollo::perception::common::INeg6 ( x[6])
inline

◆ INeg6() [2/2]

template<typename T >
void apollo::perception::common::INeg6 ( const T  x[6],
y[6] 
)
inline

◆ INeg7() [1/2]

template<typename T >
void apollo::perception::common::INeg7 ( x[7])
inline

◆ INeg7() [2/2]

template<typename T >
void apollo::perception::common::INeg7 ( const T  x[7],
y[7] 
)
inline

◆ INeg8() [1/2]

template<typename T >
void apollo::perception::common::INeg8 ( x[8])
inline

◆ INeg8() [2/2]

template<typename T >
void apollo::perception::common::INeg8 ( const T  x[8],
y[8] 
)
inline

◆ INeg9() [1/2]

template<typename T >
void apollo::perception::common::INeg9 ( x[9])
inline

◆ INeg9() [2/2]

template<typename T >
void apollo::perception::common::INeg9 ( const T  x[9],
y[9] 
)
inline

◆ INegCol()

template<typename T >
void apollo::perception::common::INegCol ( T *  A,
int  c,
int  m,
int  n 
)
inline

◆ IPlaneEucliToSpher()

void apollo::perception::common::IPlaneEucliToSpher ( const GroundPlaneLiDAR src,
GroundPlaneSpherical dst 
)

◆ IPlaneFit() [1/2]

template<typename T >
void apollo::perception::common::IPlaneFit ( const T *  X1,
const T *  X2,
const T *  X3,
T *  pi 
)
inline

◆ IPlaneFit() [2/2]

template<typename T >
void apollo::perception::common::IPlaneFit ( const T *  Xs,
T *  pi 
)
inline

◆ IPlaneFitAdv()

template<typename T >
void apollo::perception::common::IPlaneFitAdv ( const T *  Xs,
T *  para 
)
inline

◆ IPlaneFitDestroyed()

template<typename T >
void apollo::perception::common::IPlaneFitDestroyed ( T *  Xs,
T *  pi 
)
inline

◆ IPlaneFitTotalLeastSquare() [1/4]

template<typename T >
void apollo::perception::common::IPlaneFitTotalLeastSquare ( T *  X,
T *  pi,
int  n 
)
inline

◆ IPlaneFitTotalLeastSquare() [2/4]

template<typename T >
void apollo::perception::common::IPlaneFitTotalLeastSquare ( const T *  X,
T *  pi,
int  n,
T *  Xp,
T *  centroid,
T *  err_stat 
)
inline

◆ IPlaneFitTotalLeastSquare() [3/4]

template<typename T >
void apollo::perception::common::IPlaneFitTotalLeastSquare ( T *  X,
int *  indices,
T *  pi,
int  m,
int  n 
)
inline

◆ IPlaneFitTotalLeastSquare() [4/4]

template<typename T >
void apollo::perception::common::IPlaneFitTotalLeastSquare ( T *  X,
int *  indices,
T *  pi,
T *  centroid,
int  m,
int  n 
)
inline

◆ IPlaneFitTotalLeastSquare3()

template<typename T >
void apollo::perception::common::IPlaneFitTotalLeastSquare3 ( T *  X,
T *  pi 
)
inline

◆ IPlaneFitTotalLeastSquareAdv()

template<typename T >
void apollo::perception::common::IPlaneFitTotalLeastSquareAdv ( T *  X,
int *  indices,
T *  para,
int  m,
int  n 
)
inline

◆ IPlaneSpherToEucli()

void apollo::perception::common::IPlaneSpherToEucli ( const GroundPlaneSpherical src,
GroundPlaneLiDAR dst 
)

◆ IPlaneToPlaneNormalDeltaDegreeZUp()

template<typename T >
T apollo::perception::common::IPlaneToPlaneNormalDeltaDegreeZUp ( const T *  pi_p,
const T *  pi_q 
)
inline

◆ IPlaneToPointDistance() [1/2]

template<typename T >
T apollo::perception::common::IPlaneToPointDistance ( const T *  pi,
const T *  p 
)
inline

◆ IPlaneToPointDistance() [2/2]

template<typename T >
T apollo::perception::common::IPlaneToPointDistance ( const T *  pi,
const T *  p,
l2_norm3_pi 
)
inline

◆ IPlaneToPointDistanceWNormalizedPlaneNorm()

template<typename T >
T apollo::perception::common::IPlaneToPointDistanceWNormalizedPlaneNorm ( const T *  pi,
const T *  p 
)
inline

◆ IPlaneToPointDistanceWUnitNorm()

template<typename T >
T apollo::perception::common::IPlaneToPointDistanceWUnitNorm ( const T *  pi,
const T *  p 
)
inline

◆ IPlaneToPointSignedDistanceWUnitNorm()

template<typename T >
T apollo::perception::common::IPlaneToPointSignedDistanceWUnitNorm ( const T *  pi,
const T *  p 
)
inline

◆ IPointInFrontOfCamera()

template<typename T >
bool apollo::perception::common::IPointInFrontOfCamera ( const T *  X,
const T *  cop,
const T *  prv 
)
inline

◆ IPointOnPlaneProjection()

template<typename T >
void apollo::perception::common::IPointOnPlaneProjection ( const T *  pi,
const T *  p,
T *  q 
)
inline

◆ IPow() [1/6]

float apollo::perception::common::IPow ( float  a,
float  b 
)
inline

◆ IPow() [2/6]

float apollo::perception::common::IPow ( float  a,
int  b 
)
inline

◆ IPow() [3/6]

double apollo::perception::common::IPow ( int  a,
int  b 
)
inline

◆ IPow() [4/6]

double apollo::perception::common::IPow ( unsigned int  a,
unsigned int  b 
)
inline

◆ IPow() [5/6]

double apollo::perception::common::IPow ( double  a,
double  b 
)
inline

◆ IPow() [6/6]

double apollo::perception::common::IPow ( double  a,
int  b 
)
inline

◆ IProjectThroughExtrinsic()

template<typename T >
void apollo::perception::common::IProjectThroughExtrinsic ( const T *  R,
const T *  t,
const T *  X,
T *  x 
)
inline

◆ IProjectThroughIntrinsic()

template<typename T >
void apollo::perception::common::IProjectThroughIntrinsic ( const T *  K,
const T *  X,
T *  x 
)
inline

◆ IProjectThroughKRt()

template<typename T >
void apollo::perception::common::IProjectThroughKRt ( const T *  K,
const T *  R,
const T *  t,
const T *  X,
T *  x 
)
inline

◆ IRadiansToDegree() [1/2]

float apollo::perception::common::IRadiansToDegree ( float  r)
inline

◆ IRadiansToDegree() [2/2]

double apollo::perception::common::IRadiansToDegree ( double  r)
inline

◆ IRamp()

template<typename T >
void apollo::perception::common::IRamp ( T *  a,
int  n 
)
inline

◆ IRandCoreD()

double apollo::perception::common::IRandCoreD ( int *  s)
inline

◆ IRandI()

int apollo::perception::common::IRandI ( int  pool_size,
int *  s 
)
inline

◆ IRandomizedShuffle() [1/2]

template<typename T >
void apollo::perception::common::IRandomizedShuffle ( T *  A,
int  n,
int  l,
int *  s 
)
inline

◆ IRandomizedShuffle() [2/2]

template<typename T >
void apollo::perception::common::IRandomizedShuffle ( T *  A,
T *  B,
int  n,
int  la,
int  lb,
int *  s 
)
inline

◆ IRandomizedShuffle1()

template<typename T >
void apollo::perception::common::IRandomizedShuffle1 ( T *  A,
int  n,
int *  s 
)
inline

◆ IRandomSample()

void apollo::perception::common::IRandomSample ( int *  sample,
int  n,
int  pool_size,
int *  s 
)
inline

◆ IRansacTrials()

int apollo::perception::common::IRansacTrials ( int  sample_size,
double  confidence,
double  inlierprob 
)
inline

◆ IRec() [1/4]

float apollo::perception::common::IRec ( float  a)
inline

◆ IRec() [2/4]

double apollo::perception::common::IRec ( int  a)
inline

◆ IRec() [3/4]

double apollo::perception::common::IRec ( unsigned int  a)
inline

◆ IRec() [4/4]

double apollo::perception::common::IRec ( double  a)
inline

◆ IRound() [1/3]

int apollo::perception::common::IRound ( int  a)
inline

◆ IRound() [2/3]

int apollo::perception::common::IRound ( float  a)
inline

◆ IRound() [3/3]

int apollo::perception::common::IRound ( double  a)
inline

◆ ISafeUnitize() [1/4]

void apollo::perception::common::ISafeUnitize ( double *  x,
int  n 
)
inline

◆ ISafeUnitize() [2/4]

void apollo::perception::common::ISafeUnitize ( float *  x,
int  n 
)
inline

◆ ISafeUnitize() [3/4]

void apollo::perception::common::ISafeUnitize ( const double *  x,
double *  y,
int  n 
)
inline

◆ ISafeUnitize() [4/4]

void apollo::perception::common::ISafeUnitize ( float *  x,
float *  y,
int  n 
)
inline

◆ IScale() [1/2]

template<typename T >
void apollo::perception::common::IScale ( T *  x,
int  n,
sf 
)
inline

◆ IScale() [2/2]

template<typename T >
void apollo::perception::common::IScale ( const T *  x,
T *  y,
int  n,
sf 
)
inline

◆ IScale1() [1/2]

template<typename T >
void apollo::perception::common::IScale1 ( x[1],
sf 
)
inline

◆ IScale1() [2/2]

template<typename T >
void apollo::perception::common::IScale1 ( const T  x[1],
y[1],
sf 
)
inline

◆ IScale10() [1/2]

template<typename T >
void apollo::perception::common::IScale10 ( x[10],
sf 
)
inline

◆ IScale10() [2/2]

template<typename T >
void apollo::perception::common::IScale10 ( const T  x[10],
y[10],
sf 
)
inline

◆ IScale11() [1/2]

template<typename T >
void apollo::perception::common::IScale11 ( x[11],
sf 
)
inline

◆ IScale11() [2/2]

template<typename T >
void apollo::perception::common::IScale11 ( const T  x[11],
y[11],
sf 
)
inline

◆ IScale12() [1/2]

template<typename T >
void apollo::perception::common::IScale12 ( x[12],
sf 
)
inline

◆ IScale12() [2/2]

template<typename T >
void apollo::perception::common::IScale12 ( const T  x[12],
y[12],
sf 
)
inline

◆ IScale13() [1/2]

template<typename T >
void apollo::perception::common::IScale13 ( x[13],
sf 
)
inline

◆ IScale13() [2/2]

template<typename T >
void apollo::perception::common::IScale13 ( const T  x[13],
y[13],
sf 
)
inline

◆ IScale14() [1/2]

template<typename T >
void apollo::perception::common::IScale14 ( x[14],
sf 
)
inline

◆ IScale14() [2/2]

template<typename T >
void apollo::perception::common::IScale14 ( const T  x[14],
y[14],
sf 
)
inline

◆ IScale15() [1/2]

template<typename T >
void apollo::perception::common::IScale15 ( x[15],
sf 
)
inline

◆ IScale15() [2/2]

template<typename T >
void apollo::perception::common::IScale15 ( const T  x[15],
y[15],
sf 
)
inline

◆ IScale16() [1/2]

template<typename T >
void apollo::perception::common::IScale16 ( x[16],
sf 
)
inline

◆ IScale16() [2/2]

template<typename T >
void apollo::perception::common::IScale16 ( const T  x[16],
y[16],
sf 
)
inline

◆ IScale2() [1/2]

template<typename T >
void apollo::perception::common::IScale2 ( x[2],
sf 
)
inline

◆ IScale2() [2/2]

template<typename T >
void apollo::perception::common::IScale2 ( const T  x[2],
y[2],
sf 
)
inline

◆ IScale3() [1/2]

template<typename T >
void apollo::perception::common::IScale3 ( x[3],
sf 
)
inline

◆ IScale3() [2/2]

template<typename T >
void apollo::perception::common::IScale3 ( const T  x[3],
y[3],
sf 
)
inline

◆ IScale4() [1/2]

template<typename T >
void apollo::perception::common::IScale4 ( x[4],
sf 
)
inline

◆ IScale4() [2/2]

template<typename T >
void apollo::perception::common::IScale4 ( const T  x[4],
y[4],
sf 
)
inline

◆ IScale5() [1/2]

template<typename T >
void apollo::perception::common::IScale5 ( x[5],
sf 
)
inline

◆ IScale5() [2/2]

template<typename T >
void apollo::perception::common::IScale5 ( const T  x[5],
y[5],
sf 
)
inline

◆ IScale6() [1/2]

template<typename T >
void apollo::perception::common::IScale6 ( x[6],
sf 
)
inline

◆ IScale6() [2/2]

template<typename T >
void apollo::perception::common::IScale6 ( const T  x[6],
y[6],
sf 
)
inline

◆ IScale7() [1/2]

template<typename T >
void apollo::perception::common::IScale7 ( x[7],
sf 
)
inline

◆ IScale7() [2/2]

template<typename T >
void apollo::perception::common::IScale7 ( const T  x[7],
y[7],
sf 
)
inline

◆ IScale8() [1/2]

template<typename T >
void apollo::perception::common::IScale8 ( x[8],
sf 
)
inline

◆ IScale8() [2/2]

template<typename T >
void apollo::perception::common::IScale8 ( const T  x[8],
y[8],
sf 
)
inline

◆ IScale9() [1/2]

template<typename T >
void apollo::perception::common::IScale9 ( x[9],
sf 
)
inline

◆ IScale9() [2/2]

template<typename T >
void apollo::perception::common::IScale9 ( const T  x[9],
y[9],
sf 
)
inline

◆ IsCamerasFieldOverlap()

bool apollo::perception::common::IsCamerasFieldOverlap ( const base::PinholeCameraModel from_camera,
const base::PinholeCameraModel to_camera,
const Eigen::Matrix4d &  extrinsic,
Eigen::Vector2d *  up_left,
Eigen::Vector2d *  low_right 
)

◆ ISdv()

template<typename T >
T apollo::perception::common::ISdv ( const T *  x,
mean,
int  n 
)
inline

◆ IShiftHomogeneous3()

template<typename T >
void apollo::perception::common::IShiftHomogeneous3 ( T *  A,
int  n 
)
inline

◆ IShiftHomogeneous4()

template<typename T >
void apollo::perception::common::IShiftHomogeneous4 ( T *  A,
int  n 
)
inline

◆ ISign()

template<typename T >
T apollo::perception::common::ISign ( a)
inline

◆ ISignedUnitize2()

template<typename T >
void apollo::perception::common::ISignedUnitize2 ( x[2])
inline

◆ ISignedUnitize3()

template<typename T >
void apollo::perception::common::ISignedUnitize3 ( x[3])
inline

◆ ISignedUnitize4()

template<typename T >
void apollo::perception::common::ISignedUnitize4 ( x[4])
inline

◆ ISignNeverZero()

template<typename T >
T apollo::perception::common::ISignNeverZero ( a)
inline

◆ ISin() [1/2]

float apollo::perception::common::ISin ( float  alpha)
inline

◆ ISin() [2/2]

double apollo::perception::common::ISin ( double  alpha)
inline

◆ IsObjectBboxInRoi()

bool apollo::perception::common::IsObjectBboxInRoi ( const std::shared_ptr< const apollo::perception::base::HdmapStruct roi,
const std::shared_ptr< const apollo::perception::base::Object obj 
)

◆ IsObjectInRoi()

bool apollo::perception::common::IsObjectInRoi ( const std::shared_ptr< const apollo::perception::base::HdmapStruct roi,
const std::shared_ptr< const apollo::perception::base::Object obj 
)

◆ ISolve2x2() [1/2]

void apollo::perception::common::ISolve2x2 ( const double  A[4],
const double  b[2],
double  x[2] 
)
inline

◆ ISolve2x2() [2/2]

void apollo::perception::common::ISolve2x2 ( const float  A[4],
const float  b[2],
float  x[2] 
)
inline

◆ ISolve3x3() [1/2]

void apollo::perception::common::ISolve3x3 ( const double  A[9],
const double  b[3],
double  x[3] 
)
inline

◆ ISolve3x3() [2/2]

void apollo::perception::common::ISolve3x3 ( const float  A[9],
const float  b[3],
float  x[3] 
)
inline

◆ IsPointInBBox()

template<typename PointT >
bool apollo::perception::common::IsPointInBBox ( const Eigen::Matrix< typename PointT::Type, 3, 1 > &  gnd_c,
const Eigen::Matrix< typename PointT::Type, 3, 1 > &  dir_x,
const Eigen::Matrix< typename PointT::Type, 3, 1 > &  dir_y,
const Eigen::Matrix< typename PointT::Type, 3, 1 > &  dir_z,
const Eigen::Matrix< typename PointT::Type, 3, 1 > &  size,
const PointT &  point 
)

◆ IsPointXYInPolygon2DXY()

template<typename PointT >
bool apollo::perception::common::IsPointXYInPolygon2DXY ( const PointT &  point,
const base::PointCloud< PointT > &  polygon 
)

◆ IsPtInRoi()

bool apollo::perception::common::IsPtInRoi ( const std::shared_ptr< const apollo::perception::base::HdmapStruct roi,
const apollo::perception::base::PointD  pt 
)

◆ ISqr() [1/6]

float apollo::perception::common::ISqr ( float  a)
inline

◆ ISqr() [2/6]

int apollo::perception::common::ISqr ( int  a)
inline

◆ ISqr() [3/6]

unsigned int apollo::perception::common::ISqr ( unsigned int  a)
inline

◆ ISqr() [4/6]

double apollo::perception::common::ISqr ( double  a)
inline

◆ ISqr() [5/6]

int apollo::perception::common::ISqr ( char  a)
inline

◆ ISqr() [6/6]

int apollo::perception::common::ISqr ( unsigned char  a)
inline

◆ ISqrSkewSymmetric3x3()

template<typename T >
void apollo::perception::common::ISqrSkewSymmetric3x3 ( const T  x[3],
e_x2[9] 
)
inline

◆ ISqrt() [1/4]

float apollo::perception::common::ISqrt ( float  a)
inline

◆ ISqrt() [2/4]

double apollo::perception::common::ISqrt ( int  a)
inline

◆ ISqrt() [3/4]

double apollo::perception::common::ISqrt ( unsigned int  a)
inline

◆ ISqrt() [4/4]

double apollo::perception::common::ISqrt ( double  a)
inline

◆ ISquaresum()

template<typename T >
T apollo::perception::common::ISquaresum ( const T *  x,
int  n 
)
inline

◆ ISquaresum1()

template<typename T >
T apollo::perception::common::ISquaresum1 ( const T  x[1])
inline

◆ ISquaresum10()

template<typename T >
T apollo::perception::common::ISquaresum10 ( const T  x[10])
inline

◆ ISquaresum11()

template<typename T >
T apollo::perception::common::ISquaresum11 ( const T  x[11])
inline

◆ ISquaresum12()

template<typename T >
T apollo::perception::common::ISquaresum12 ( const T  x[12])
inline

◆ ISquaresum13()

template<typename T >
T apollo::perception::common::ISquaresum13 ( const T  x[13])
inline

◆ ISquaresum14()

template<typename T >
T apollo::perception::common::ISquaresum14 ( const T  x[14])
inline

◆ ISquaresum15()

template<typename T >
T apollo::perception::common::ISquaresum15 ( const T  x[15])
inline

◆ ISquaresum16()

template<typename T >
T apollo::perception::common::ISquaresum16 ( const T  x[16])
inline

◆ ISquaresum2()

template<typename T >
T apollo::perception::common::ISquaresum2 ( const T  x[2])
inline

◆ ISquaresum3()

template<typename T >
T apollo::perception::common::ISquaresum3 ( const T  x[3])
inline

◆ ISquaresum4()

template<typename T >
T apollo::perception::common::ISquaresum4 ( const T  x[4])
inline

◆ ISquaresum5()

template<typename T >
T apollo::perception::common::ISquaresum5 ( const T  x[5])
inline

◆ ISquaresum6()

template<typename T >
T apollo::perception::common::ISquaresum6 ( const T  x[6])
inline

◆ ISquaresum7()

template<typename T >
T apollo::perception::common::ISquaresum7 ( const T  x[7])
inline

◆ ISquaresum8()

template<typename T >
T apollo::perception::common::ISquaresum8 ( const T  x[8])
inline

◆ ISquaresum9()

template<typename T >
T apollo::perception::common::ISquaresum9 ( const T  x[9])
inline

◆ ISquaresumDiffU() [1/2]

int apollo::perception::common::ISquaresumDiffU ( const unsigned char *  x,
const unsigned char *  y,
int  n 
)
inline

◆ ISquaresumDiffU() [2/2]

template<typename T >
T apollo::perception::common::ISquaresumDiffU ( const T *  x,
const T *  y,
int  n 
)
inline

◆ ISquaresumDiffU1()

template<typename T >
T apollo::perception::common::ISquaresumDiffU1 ( const T  x[1],
const T  y[1] 
)
inline

◆ ISquaresumDiffU10()

template<typename T >
T apollo::perception::common::ISquaresumDiffU10 ( const T  x[10],
const T  y[10] 
)
inline

◆ ISquaresumDiffU11()

template<typename T >
T apollo::perception::common::ISquaresumDiffU11 ( const T  x[11],
const T  y[11] 
)
inline

◆ ISquaresumDiffU12()

template<typename T >
T apollo::perception::common::ISquaresumDiffU12 ( const T  x[12],
const T  y[12] 
)
inline

◆ ISquaresumDiffU13()

template<typename T >
T apollo::perception::common::ISquaresumDiffU13 ( const T  x[13],
const T  y[13] 
)
inline

◆ ISquaresumDiffU14()

template<typename T >
T apollo::perception::common::ISquaresumDiffU14 ( const T  x[14],
const T  y[14] 
)
inline

◆ ISquaresumDiffU15()

template<typename T >
T apollo::perception::common::ISquaresumDiffU15 ( const T  x[15],
const T  y[15] 
)
inline

◆ ISquaresumDiffU16()

template<typename T >
T apollo::perception::common::ISquaresumDiffU16 ( const T  x[16],
const T  y[16] 
)
inline

◆ ISquaresumDiffU2()

template<typename T >
T apollo::perception::common::ISquaresumDiffU2 ( const T  x[2],
const T  y[2] 
)
inline

◆ ISquaresumDiffU3()

template<typename T >
T apollo::perception::common::ISquaresumDiffU3 ( const T  x[3],
const T  y[3] 
)
inline

◆ ISquaresumDiffU4()

template<typename T >
T apollo::perception::common::ISquaresumDiffU4 ( const T  x[4],
const T  y[4] 
)
inline

◆ ISquaresumDiffU5()

template<typename T >
T apollo::perception::common::ISquaresumDiffU5 ( const T  x[5],
const T  y[5] 
)
inline

◆ ISquaresumDiffU6()

template<typename T >
T apollo::perception::common::ISquaresumDiffU6 ( const T  x[6],
const T  y[6] 
)
inline

◆ ISquaresumDiffU7()

template<typename T >
T apollo::perception::common::ISquaresumDiffU7 ( const T  x[7],
const T  y[7] 
)
inline

◆ ISquaresumDiffU8()

template<typename T >
T apollo::perception::common::ISquaresumDiffU8 ( const T  x[8],
const T  y[8] 
)
inline

◆ ISquaresumDiffU9()

template<typename T >
T apollo::perception::common::ISquaresumDiffU9 ( const T  x[9],
const T  y[9] 
)
inline

◆ ISquaresumU()

int apollo::perception::common::ISquaresumU ( const unsigned char *  x,
int  n 
)
inline

◆ ISub() [1/3]

template<typename T >
void apollo::perception::common::ISub ( T *  x,
int  n,
k 
)
inline

◆ ISub() [2/3]

template<typename T >
void apollo::perception::common::ISub ( const T *  x,
const T *  y,
int  n,
T *  z 
)
inline

◆ ISub() [3/3]

template<typename T >
void apollo::perception::common::ISub ( const T *  x,
T *  y,
int  n 
)
inline

◆ ISub1() [1/2]

template<typename T >
void apollo::perception::common::ISub1 ( const T  x[1],
const T  y[1],
z[1] 
)
inline

◆ ISub1() [2/2]

template<typename T >
void apollo::perception::common::ISub1 ( const T  x[1],
y[1] 
)
inline

◆ ISub10() [1/2]

template<typename T >
void apollo::perception::common::ISub10 ( const T  x[10],
const T  y[10],
z[10] 
)
inline

◆ ISub10() [2/2]

template<typename T >
void apollo::perception::common::ISub10 ( const T  x[10],
y[10] 
)
inline

◆ ISub11() [1/2]

template<typename T >
void apollo::perception::common::ISub11 ( const T  x[11],
const T  y[11],
z[11] 
)
inline

◆ ISub11() [2/2]

template<typename T >
void apollo::perception::common::ISub11 ( const T  x[11],
y[11] 
)
inline

◆ ISub12() [1/2]

template<typename T >
void apollo::perception::common::ISub12 ( const T  x[12],
const T  y[12],
z[12] 
)
inline

◆ ISub12() [2/2]

template<typename T >
void apollo::perception::common::ISub12 ( const T  x[12],
y[12] 
)
inline

◆ ISub13() [1/2]

template<typename T >
void apollo::perception::common::ISub13 ( const T  x[13],
const T  y[13],
z[13] 
)
inline

◆ ISub13() [2/2]

template<typename T >
void apollo::perception::common::ISub13 ( const T  x[13],
y[13] 
)
inline

◆ ISub14() [1/2]

template<typename T >
void apollo::perception::common::ISub14 ( const T  x[14],
const T  y[14],
z[14] 
)
inline

◆ ISub14() [2/2]

template<typename T >
void apollo::perception::common::ISub14 ( const T  x[14],
y[14] 
)
inline

◆ ISub15() [1/2]

template<typename T >
void apollo::perception::common::ISub15 ( const T  x[15],
const T  y[15],
z[15] 
)
inline

◆ ISub15() [2/2]

template<typename T >
void apollo::perception::common::ISub15 ( const T  x[15],
y[15] 
)
inline

◆ ISub16() [1/2]

template<typename T >
void apollo::perception::common::ISub16 ( const T  x[16],
const T  y[16],
z[16] 
)
inline

◆ ISub16() [2/2]

template<typename T >
void apollo::perception::common::ISub16 ( const T  x[16],
y[16] 
)
inline

◆ ISub2() [1/2]

template<typename T >
void apollo::perception::common::ISub2 ( const T  x[2],
const T  y[2],
z[2] 
)
inline

◆ ISub2() [2/2]

template<typename T >
void apollo::perception::common::ISub2 ( const T  x[2],
y[2] 
)
inline

◆ ISub3() [1/2]

template<typename T >
void apollo::perception::common::ISub3 ( const T  x[3],
const T  y[3],
z[3] 
)
inline

◆ ISub3() [2/2]

template<typename T >
void apollo::perception::common::ISub3 ( const T  x[3],
y[3] 
)
inline

◆ ISub4() [1/2]

template<typename T >
void apollo::perception::common::ISub4 ( const T  x[4],
const T  y[4],
z[4] 
)
inline

◆ ISub4() [2/2]

template<typename T >
void apollo::perception::common::ISub4 ( const T  x[4],
y[4] 
)
inline

◆ ISub5() [1/2]

template<typename T >
void apollo::perception::common::ISub5 ( const T  x[5],
const T  y[5],
z[5] 
)
inline

◆ ISub5() [2/2]

template<typename T >
void apollo::perception::common::ISub5 ( const T  x[5],
y[5] 
)
inline

◆ ISub6() [1/2]

template<typename T >
void apollo::perception::common::ISub6 ( const T  x[6],
const T  y[6],
z[6] 
)
inline

◆ ISub6() [2/2]

template<typename T >
void apollo::perception::common::ISub6 ( const T  x[6],
y[6] 
)
inline

◆ ISub7() [1/2]

template<typename T >
void apollo::perception::common::ISub7 ( const T  x[7],
const T  y[7],
z[7] 
)
inline

◆ ISub7() [2/2]

template<typename T >
void apollo::perception::common::ISub7 ( const T  x[7],
y[7] 
)
inline

◆ ISub8() [1/2]

template<typename T >
void apollo::perception::common::ISub8 ( const T  x[8],
const T  y[8],
z[8] 
)
inline

◆ ISub8() [2/2]

template<typename T >
void apollo::perception::common::ISub8 ( const T  x[8],
y[8] 
)
inline

◆ ISub9() [1/2]

template<typename T >
void apollo::perception::common::ISub9 ( const T  x[9],
const T  y[9],
z[9] 
)
inline

◆ ISub9() [2/2]

template<typename T >
void apollo::perception::common::ISub9 ( const T  x[9],
y[9] 
)
inline

◆ ISubdeterminants2x4() [1/3]

void apollo::perception::common::ISubdeterminants2x4 ( const double  x[4],
const double  y[4],
double  sd[6] 
)
inline

◆ ISubdeterminants2x4() [2/3]

void apollo::perception::common::ISubdeterminants2x4 ( const float  x[4],
const float  y[4],
float  sd[6] 
)
inline

◆ ISubdeterminants2x4() [3/3]

void apollo::perception::common::ISubdeterminants2x4 ( const int  x[4],
const int  y[4],
int  sd[6] 
)
inline

◆ ISubdeterminants3x4() [1/3]

void apollo::perception::common::ISubdeterminants3x4 ( const double  x[4],
const double  y[4],
const double  z[4],
double  sd[4] 
)
inline

◆ ISubdeterminants3x4() [2/3]

void apollo::perception::common::ISubdeterminants3x4 ( const float  x[4],
const float  y[4],
const float  z[4],
float  sd[4] 
)
inline

◆ ISubdeterminants3x4() [3/3]

void apollo::perception::common::ISubdeterminants3x4 ( const int  x[4],
const int  y[4],
const int  z[4],
int  sd[4] 
)
inline

◆ ISubScaled()

template<typename T >
void apollo::perception::common::ISubScaled ( const T *  x,
T *  y,
int  n,
k 
)
inline

◆ ISubScaled1()

template<typename T >
void apollo::perception::common::ISubScaled1 ( const T  x[1],
y[1],
k 
)
inline

◆ ISubScaled2()

template<typename T >
void apollo::perception::common::ISubScaled2 ( const T  x[2],
y[2],
k 
)
inline

◆ ISubScaled3()

template<typename T >
void apollo::perception::common::ISubScaled3 ( const T  x[3],
y[3],
k 
)
inline

◆ ISubScaled4()

template<typename T >
void apollo::perception::common::ISubScaled4 ( const T  x[4],
y[4],
k 
)
inline

◆ ISubScaled5()

template<typename T >
void apollo::perception::common::ISubScaled5 ( const T  x[5],
y[5],
k 
)
inline

◆ ISubScaled6()

template<typename T >
void apollo::perception::common::ISubScaled6 ( const T  x[6],
y[6],
k 
)
inline

◆ ISubScaled7()

template<typename T >
void apollo::perception::common::ISubScaled7 ( const T  x[7],
y[7],
k 
)
inline

◆ ISubScaled8()

template<typename T >
void apollo::perception::common::ISubScaled8 ( const T  x[8],
y[8],
k 
)
inline

◆ ISubScaled9()

template<typename T >
void apollo::perception::common::ISubScaled9 ( const T  x[9],
y[9],
k 
)
inline

◆ ISum()

template<typename T >
T apollo::perception::common::ISum ( const T *  x,
int  n 
)
inline

◆ ISum1()

template<typename T >
T apollo::perception::common::ISum1 ( const T  x[1])
inline

◆ ISum10()

template<typename T >
T apollo::perception::common::ISum10 ( const T  x[10])
inline

◆ ISum11()

template<typename T >
T apollo::perception::common::ISum11 ( const T  x[11])
inline

◆ ISum12()

template<typename T >
T apollo::perception::common::ISum12 ( const T  x[12])
inline

◆ ISum13()

template<typename T >
T apollo::perception::common::ISum13 ( const T  x[13])
inline

◆ ISum14()

template<typename T >
T apollo::perception::common::ISum14 ( const T  x[14])
inline

◆ ISum15()

template<typename T >
T apollo::perception::common::ISum15 ( const T  x[15])
inline

◆ ISum16()

template<typename T >
T apollo::perception::common::ISum16 ( const T  x[16])
inline

◆ ISum2()

template<typename T >
T apollo::perception::common::ISum2 ( const T  x[2])
inline

◆ ISum3()

template<typename T >
T apollo::perception::common::ISum3 ( const T  x[3])
inline

◆ ISum4()

template<typename T >
T apollo::perception::common::ISum4 ( const T  x[4])
inline

◆ ISum5()

template<typename T >
T apollo::perception::common::ISum5 ( const T  x[5])
inline

◆ ISum6()

template<typename T >
T apollo::perception::common::ISum6 ( const T  x[6])
inline

◆ ISum7()

template<typename T >
T apollo::perception::common::ISum7 ( const T  x[7])
inline

◆ ISum8()

template<typename T >
T apollo::perception::common::ISum8 ( const T  x[8])
inline

◆ ISum9()

template<typename T >
T apollo::perception::common::ISum9 ( const T  x[9])
inline

◆ ISumU()

int apollo::perception::common::ISumU ( const unsigned char *  x,
int  n 
)
inline

◆ ISwap() [1/2]

template<typename T >
void apollo::perception::common::ISwap ( T &  a,
T &  b 
)
inline

◆ ISwap() [2/2]

template<typename T >
void apollo::perception::common::ISwap ( T *  a,
T *  b,
int  n 
)
inline

◆ ISwap2()

template<typename T >
void apollo::perception::common::ISwap2 ( T *  a,
T *  b 
)
inline

◆ ISwap3()

template<typename T >
void apollo::perception::common::ISwap3 ( T *  a,
T *  b 
)
inline

◆ ISwap4()

template<typename T >
void apollo::perception::common::ISwap4 ( T *  a,
T *  b 
)
inline

◆ ISwapCols()

template<typename T >
void apollo::perception::common::ISwapCols ( T *  A,
int  c1,
int  c2,
int  m,
int  n 
)
inline

◆ ISwapColsInterval()

template<typename T >
void apollo::perception::common::ISwapColsInterval ( T *  A,
int  i1,
int  i2,
int  c1,
int  c2,
int  m,
int  n 
)
inline

◆ ISwapRows()

template<typename T >
void apollo::perception::common::ISwapRows ( T *  A,
int  r1,
int  r2,
int  m,
int  n 
)
inline

◆ ISwapRowsInterval()

template<typename T >
void apollo::perception::common::ISwapRowsInterval ( T *  A,
int  i1,
int  i2,
int  r1,
int  r2,
int  m,
int  n 
)
inline

◆ ITan() [1/2]

float apollo::perception::common::ITan ( float  alpha)
inline

◆ ITan() [2/2]

double apollo::perception::common::ITan ( double  alpha)
inline

◆ ITrace2x2() [1/2]

double apollo::perception::common::ITrace2x2 ( const double  A[4])
inline

◆ ITrace2x2() [2/2]

float apollo::perception::common::ITrace2x2 ( const float  A[4])
inline

◆ ITrace3x3() [1/2]

double apollo::perception::common::ITrace3x3 ( const double  A[9])
inline

◆ ITrace3x3() [2/2]

float apollo::perception::common::ITrace3x3 ( const float  A[9])
inline

◆ ITranspose() [1/2]

template<typename T >
void apollo::perception::common::ITranspose ( T *  A,
int  n 
)
inline

◆ ITranspose() [2/2]

template<typename T >
void apollo::perception::common::ITranspose ( const T *  A,
T *  At,
int  m,
int  n 
)
inline

◆ ITranspose2x2() [1/2]

template<typename T >
void apollo::perception::common::ITranspose2x2 ( A[4])
inline

◆ ITranspose2x2() [2/2]

template<typename T >
void apollo::perception::common::ITranspose2x2 ( const T  A[4],
At[4] 
)
inline

◆ ITranspose3x3() [1/2]

template<typename T >
void apollo::perception::common::ITranspose3x3 ( A[9])
inline

◆ ITranspose3x3() [2/2]

template<typename T >
void apollo::perception::common::ITranspose3x3 ( const T  A[9],
At[9] 
)
inline

◆ ITranspose4x4() [1/2]

template<typename T >
void apollo::perception::common::ITranspose4x4 ( A[16])
inline

◆ ITranspose4x4() [2/2]

template<typename T >
void apollo::perception::common::ITranspose4x4 ( const T  A[16],
At[16] 
)
inline

◆ IUnitize() [1/4]

void apollo::perception::common::IUnitize ( double *  x,
int  n 
)
inline

◆ IUnitize() [2/4]

void apollo::perception::common::IUnitize ( float *  x,
int  n 
)
inline

◆ IUnitize() [3/4]

void apollo::perception::common::IUnitize ( const double *  x,
double *  y,
int  n 
)
inline

◆ IUnitize() [4/4]

void apollo::perception::common::IUnitize ( const float *  x,
float *  y,
int  n 
)
inline

◆ IUnitize10() [1/2]

template<typename T >
void apollo::perception::common::IUnitize10 ( x[10])
inline

◆ IUnitize10() [2/2]

template<typename T >
void apollo::perception::common::IUnitize10 ( const T  x[10],
y[10] 
)
inline

◆ IUnitize11() [1/2]

template<typename T >
void apollo::perception::common::IUnitize11 ( x[11])
inline

◆ IUnitize11() [2/2]

template<typename T >
void apollo::perception::common::IUnitize11 ( const T  x[11],
y[11] 
)
inline

◆ IUnitize12() [1/2]

template<typename T >
void apollo::perception::common::IUnitize12 ( x[12])
inline

◆ IUnitize12() [2/2]

template<typename T >
void apollo::perception::common::IUnitize12 ( const T  x[12],
y[12] 
)
inline

◆ IUnitize13() [1/2]

template<typename T >
void apollo::perception::common::IUnitize13 ( x[13])
inline

◆ IUnitize13() [2/2]

template<typename T >
void apollo::perception::common::IUnitize13 ( const T  x[13],
y[13] 
)
inline

◆ IUnitize14() [1/2]

template<typename T >
void apollo::perception::common::IUnitize14 ( x[14])
inline

◆ IUnitize14() [2/2]

template<typename T >
void apollo::perception::common::IUnitize14 ( const T  x[14],
y[14] 
)
inline

◆ IUnitize15() [1/2]

template<typename T >
void apollo::perception::common::IUnitize15 ( x[15])
inline

◆ IUnitize15() [2/2]

template<typename T >
void apollo::perception::common::IUnitize15 ( const T  x[15],
y[15] 
)
inline

◆ IUnitize16() [1/2]

template<typename T >
void apollo::perception::common::IUnitize16 ( x[16])
inline

◆ IUnitize16() [2/2]

template<typename T >
void apollo::perception::common::IUnitize16 ( const T  x[16],
y[16] 
)
inline

◆ IUnitize2() [1/2]

template<typename T >
void apollo::perception::common::IUnitize2 ( x[2])
inline

◆ IUnitize2() [2/2]

template<typename T >
void apollo::perception::common::IUnitize2 ( const T  x[2],
y[2] 
)
inline

◆ IUnitize3() [1/2]

template<typename T >
void apollo::perception::common::IUnitize3 ( x[3])
inline

◆ IUnitize3() [2/2]

template<typename T >
void apollo::perception::common::IUnitize3 ( const T  x[3],
y[3] 
)
inline

◆ IUnitize4() [1/2]

template<typename T >
void apollo::perception::common::IUnitize4 ( x[4])
inline

◆ IUnitize4() [2/2]

template<typename T >
void apollo::perception::common::IUnitize4 ( const T  x[4],
y[4] 
)
inline

◆ IUnitize5() [1/2]

template<typename T >
void apollo::perception::common::IUnitize5 ( x[5])
inline

◆ IUnitize5() [2/2]

template<typename T >
void apollo::perception::common::IUnitize5 ( const T  x[5],
y[5] 
)
inline

◆ IUnitize6() [1/2]

template<typename T >
void apollo::perception::common::IUnitize6 ( x[6])
inline

◆ IUnitize6() [2/2]

template<typename T >
void apollo::perception::common::IUnitize6 ( const T  x[6],
y[6] 
)
inline

◆ IUnitize7() [1/2]

template<typename T >
void apollo::perception::common::IUnitize7 ( x[7])
inline

◆ IUnitize7() [2/2]

template<typename T >
void apollo::perception::common::IUnitize7 ( const T  x[7],
y[7] 
)
inline

◆ IUnitize8() [1/2]

template<typename T >
void apollo::perception::common::IUnitize8 ( x[8])
inline

◆ IUnitize8() [2/2]

template<typename T >
void apollo::perception::common::IUnitize8 ( const T  x[8],
y[8] 
)
inline

◆ IUnitize9() [1/2]

template<typename T >
void apollo::perception::common::IUnitize9 ( x[9])
inline

◆ IUnitize9() [2/2]

template<typename T >
void apollo::perception::common::IUnitize9 ( const T  x[9],
y[9] 
)
inline

◆ IUnprojectThroughIntrinsic()

template<typename T >
void apollo::perception::common::IUnprojectThroughIntrinsic ( const T *  K,
const T *  x,
T *  X 
)
inline

◆ IUpperTriangular2x2()

template<typename T >
void apollo::perception::common::IUpperTriangular2x2 ( a0,
a1,
a3,
A[4] 
)
inline

◆ IUpperTriangular3x3()

template<typename T >
void apollo::perception::common::IUpperTriangular3x3 ( a0,
a1,
a2,
a4,
a5,
a8,
A[9] 
)
inline

◆ IVerifyAlignment()

template<typename T >
int apollo::perception::common::IVerifyAlignment ( const T *  mem,
int  alignment_power = 4 
)
inline

◆ IWithin1D()

template<typename T >
bool apollo::perception::common::IWithin1D ( const T  x,
const T  start,
const T  length 
)
inline

◆ IWithin2D() [1/2]

template<typename T >
bool apollo::perception::common::IWithin2D ( const T  p[2],
const T  x_upper_left,
const T  y_upper_left,
const T  width,
const T  height 
)
inline

◆ IWithin2D() [2/2]

template<typename T >
bool apollo::perception::common::IWithin2D ( const T  x,
const T  y,
const T  x_upper_left,
const T  y_upper_left,
const T  width,
const T  height 
)
inline

◆ IZero()

template<typename T >
void apollo::perception::common::IZero ( T *  a,
int  n 
)
inline

◆ IZero1()

template<typename T >
void apollo::perception::common::IZero1 ( a[1])
inline

◆ IZero10()

template<typename T >
void apollo::perception::common::IZero10 ( a[10])
inline

◆ IZero11()

template<typename T >
void apollo::perception::common::IZero11 ( a[11])
inline

◆ IZero12()

template<typename T >
void apollo::perception::common::IZero12 ( a[12])
inline

◆ IZero13()

template<typename T >
void apollo::perception::common::IZero13 ( a[13])
inline

◆ IZero14()

template<typename T >
void apollo::perception::common::IZero14 ( a[14])
inline

◆ IZero15()

template<typename T >
void apollo::perception::common::IZero15 ( a[15])
inline

◆ IZero16()

template<typename T >
void apollo::perception::common::IZero16 ( a[16])
inline

◆ IZero2()

template<typename T >
void apollo::perception::common::IZero2 ( a[2])
inline

◆ IZero3()

template<typename T >
void apollo::perception::common::IZero3 ( a[3])
inline

◆ IZero4()

template<typename T >
void apollo::perception::common::IZero4 ( a[4])
inline

◆ IZero5()

template<typename T >
void apollo::perception::common::IZero5 ( a[5])
inline

◆ IZero6()

template<typename T >
void apollo::perception::common::IZero6 ( a[6])
inline

◆ IZero7()

template<typename T >
void apollo::perception::common::IZero7 ( a[7])
inline

◆ IZero8()

template<typename T >
void apollo::perception::common::IZero8 ( a[8])
inline

◆ IZero9()

template<typename T >
void apollo::perception::common::IZero9 ( a[9])
inline

◆ LoadBrownCameraIntrinsic()

bool apollo::perception::common::LoadBrownCameraIntrinsic ( const std::string &  yaml_file,
base::BrownCameraDistortionModel model 
)

◆ LoadOmnidirectionalCameraIntrinsics()

bool apollo::perception::common::LoadOmnidirectionalCameraIntrinsics ( const std::string &  yaml_file,
base::OmnidirectionalCameraDistortionModel model 
)

◆ ObjectInRoiCheck()

bool apollo::perception::common::ObjectInRoiCheck ( const std::shared_ptr< const apollo::perception::base::HdmapStruct roi,
const std::vector< std::shared_ptr< apollo::perception::base::Object >> &  objs,
std::vector< std::shared_ptr< apollo::perception::base::Object >> *  valid_objs 
)

◆ PointCamera1ToCamera2()

bool apollo::perception::common::PointCamera1ToCamera2 ( const Eigen::Vector2d &  point,
const Eigen::Matrix3d &  camera1_intrinsic_inverse,
const Eigen::Matrix3d &  camera2_intrinsic,
const Eigen::Matrix3d &  trans_camera1_to_camera2,
Eigen::Vector2d *  point_out 
)

◆ ReadPoseFile()

bool apollo::perception::common::ReadPoseFile ( const std::string &  filename,
Eigen::Affine3d *  pose,
int *  frame_id,
double *  time_stamp 
)

◆ RobustBinaryFitRansac()

template<typename T , int l, int lp, int k, int s, void(*)(const T *x, const T *xp, T *model) HypogenFunc, void(*)(const T *model, const T *x, const T *xp, int n, int *nr_liner, int *inliers, T *cost, T error_tol) CostFunc, void(*)(T *x, T *xp, int *inliers, T *model, int n, int nr_liner) RefitFunc>
bool apollo::perception::common::RobustBinaryFitRansac ( T *  x,
T *  xp,
int  n,
T *  model,
int *  consensus_size,
int *  inliers,
error_tol,
bool  re_est_model_w_inliers = false,
bool  adaptive_trial_count = false,
double  confidence = 0.99,
double  inlierprob = 0.5,
int  min_nr_inliers = s,
bool  random_shuffle_inputs = false 
)

◆ TransformPoint()

template<typename PointT >
void apollo::perception::common::TransformPoint ( const PointT &  point_in,
const Eigen::Affine3d &  pose,
PointT *  point_out 
)

◆ TransformPointCloud() [1/2]

template<typename PointT >
void apollo::perception::common::TransformPointCloud ( const base::PointCloud< PointT > &  cloud_in,
const Eigen::Affine3d &  pose,
base::PointCloud< PointT > *  cloud_out 
)

◆ TransformPointCloud() [2/2]

template<typename PointT >
void apollo::perception::common::TransformPointCloud ( const Eigen::Affine3d &  pose,
base::PointCloud< PointT > *  cloud_in_out 
)

Variable Documentation

◆ I_DEFAULT_SEED

const int apollo::perception::common::I_DEFAULT_SEED = 432