Apollo 10.0
自动驾驶开放平台
apollo::perception::algorithm 命名空间参考

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
 

类型定义

using HdmapStructConstPtr = std::shared_ptr< const apollo::perception::base::HdmapStruct >
 
using ObjectConstPtr = std::shared_ptr< const apollo::perception::base::Object >
 
using ObjectPtr = std::shared_ptr< apollo::perception::base::Object >
 

函数

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)
 
template<typename Type >
void CalculateCornersFromCenter (Type center_x, Type center_y, Type center_z, Type size_x, Type size_y, Type size_z, Type theta, Eigen::Matrix< Type, 8, 1 > *corners)
 
template<typename T >
bool IsLineSegments2DIntersect (const Eigen::Matrix< T, 2, 1 > &p1, const Eigen::Matrix< T, 2, 1 > &q1, const Eigen::Matrix< T, 2, 1 > &p2, const Eigen::Matrix< T, 2, 1 > &q2)
 
bool IsPtInRoi (const HdmapStructConstPtr roi, const PointD pt)
 
bool IsObjectInRoi (const HdmapStructConstPtr roi, const ObjectConstPtr obj)
 
bool IsObjectBboxInRoi (const HdmapStructConstPtr roi, const ObjectConstPtr obj)
 
bool ObjectInRoiCheck (const HdmapStructConstPtr roi, const std::vector< ObjectPtr > &objects, std::vector< ObjectPtr > *valid_objects)
 
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)
 
float calculate_two_angles (const GroundPlaneLiDAR &p1, const GroundPlaneLiDAR &p2)
 
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 >
int AssignPointToVoxel (T xx, T yy, T zz, 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 T >
Eigen::Matrix< T, 3, 1 > CalculateRadarCentroid (const base::AttributeRadarPointCloud< base::RadarPoint< 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)
 

变量

const int I_DEFAULT_SEED = 432
 

类型定义说明

◆ HdmapStructConstPtr

在文件 roi_filter.cc30 行定义.

◆ ObjectConstPtr

在文件 roi_filter.cc33 行定义.

◆ ObjectPtr

在文件 roi_filter.cc34 行定义.

函数说明

◆ AssignPointToVoxel()

template<typename T >
int apollo::perception::algorithm::AssignPointToVoxel ( xx,
yy,
zz,
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

在文件 i_struct_s.h186 行定义.

190 {
191 int i, j, k;
192 T x = xx;
193 T y = yy;
194 T z = zz;
195
196 // points that are outside the defined BBOX are ignored
197 if (x < bound_x_min || x > bound_x_max || y < bound_y_min ||
198 y > bound_y_max || z < bound_z_min || z > bound_z_max) {
199 return (-1);
200 }
201
202 // compute the x, y voxel indices
203 k = IMin(nr_voxel_x - 1,
204 static_cast<int>((x - bound_x_min) * voxel_width_x_rec));
205 j = IMin(nr_voxel_y - 1,
206 static_cast<int>((y - bound_y_min) * voxel_width_y_rec));
207 i = (nr_voxel_x * j) + k;
208 return (i);
209}

◆ Calculate2DXYProjectVector()

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

在文件 basic.h135 行定义.

137 {
138 if (projected_vector.head(2).norm() < std::numeric_limits<T>::epsilon() ||
139 project_vector.head(2).norm() < std::numeric_limits<T>::epsilon()) {
140 return Eigen::Matrix<T, 3, 1>::Zero(3, 1);
141 }
142 Eigen::Matrix<T, 3, 1> project_dir = project_vector;
143 project_dir(2) = 0.0;
144 project_dir.normalize();
145
146 const T projected_vector_project_dir_inner_product =
147 projected_vector(0) * project_dir(0) +
148 projected_vector(1) * project_dir(1);
149 const T projected_vector_project_dir_angle_cos =
150 projected_vector_project_dir_inner_product /
151 (projected_vector.head(2).norm() * project_dir.head(2).norm());
152 const T projected_vector_norm_on_project_dir =
153 projected_vector.head(2).norm() * projected_vector_project_dir_angle_cos;
154 return project_dir * projected_vector_norm_on_project_dir;
155}

◆ calculate_two_angles()

float apollo::perception::algorithm::calculate_two_angles ( const GroundPlaneLiDAR p1,
const GroundPlaneLiDAR p2 
)
inline

在文件 i_ground.cc876 行定义.

877 {
878 float numerator = IDot3(p1.params, p2.params);
879 float denominator = IL2Norm(p1.params, 3) * IL2Norm(p2.params, 3);
880 return IAcos(numerator * IRec(denominator));
881}
double IL2Norm(const unsigned char *x, int n)
Definition i_blas.h:2791
float IAcos(float alpha)
Definition i_basic.h:239
T IDot3(const T x[3], const T y[3])
Definition i_blas.h:2260

◆ CalculateBBoxSizeCenter2DXY()

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

在文件 common.h112 行定义.

115 {
116 // NOTE: direction should not be (0, 0, 1)
117 Eigen::Matrix3d projection;
118 Eigen::Vector3d dird(dir[0], dir[1], 0.0);
119 dird.normalize();
120 projection << dird[0], dird[1], 0.0, -dird[1], dird[0], 0.0, 0.0, 0.0, 1.0;
121 constexpr double kDoubleMax = std::numeric_limits<double>::max();
122 Eigen::Vector3d min_pt(kDoubleMax, kDoubleMax, kDoubleMax);
123 Eigen::Vector3d max_pt(-kDoubleMax, -kDoubleMax, -kDoubleMax);
124 Eigen::Vector3d loc_pt(0.0, 0.0, 0.0);
125 for (size_t i = 0; i < cloud.size(); i++) {
126 loc_pt = projection * Eigen::Vector3d(cloud[i].x, cloud[i].y, cloud[i].z);
127
128 min_pt(0) = std::min(min_pt(0), loc_pt(0));
129 min_pt(1) = std::min(min_pt(1), loc_pt(1));
130 min_pt(2) = std::min(min_pt(2), loc_pt(2));
131
132 max_pt(0) = std::max(max_pt(0), loc_pt(0));
133 max_pt(1) = std::max(max_pt(1), loc_pt(1));
134 max_pt(2) = std::max(max_pt(2), loc_pt(2));
135 }
136 (*size) = (max_pt - min_pt).cast<float>();
137 Eigen::Vector3d coeff = (max_pt + min_pt) * 0.5;
138 coeff(2) = min_pt(2);
139 *center = projection.transpose() * coeff;
140
141 constexpr float kFloatEpsilon = std::numeric_limits<float>::epsilon();
142 float minimum_size = std::max(minimum_edge_length, kFloatEpsilon);
143
144 (*size)(0) = (*size)(0) <= minimum_size ? minimum_size : (*size)(0);
145 (*size)(1) = (*size)(1) <= minimum_size ? minimum_size : (*size)(1);
146 (*size)(2) = (*size)(2) <= minimum_size ? minimum_size : (*size)(2);
147}
constexpr float kFloatEpsilon
Definition lane_object.h:32

◆ CalculateCentroid()

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

在文件 common.h134 行定义.

135 {
136 size_t point_num = cloud.size();
137 Eigen::Matrix<T, 3, 1> centroid(0.0, 0.0, 0.0);
138 for (const auto &pt : cloud.points()) {
139 centroid[0] += pt.x;
140 centroid[1] += pt.y;
141 centroid[2] += pt.z;
142 }
143 if (point_num > 0) {
144 centroid[0] /= static_cast<T>(point_num);
145 centroid[1] /= static_cast<T>(point_num);
146 centroid[2] /= static_cast<T>(point_num);
147 }
148 return centroid;
149}

◆ CalculateCornersFromCenter()

template<typename Type >
void apollo::perception::algorithm::CalculateCornersFromCenter ( Type  center_x,
Type  center_y,
Type  center_z,
Type  size_x,
Type  size_y,
Type  size_z,
Type  theta,
Eigen::Matrix< Type, 8, 1 > *  corners 
)

在文件 common.h361 行定义.

363 {
364 Type cos_theta = cos(theta);
365 Type sin_theta = sin(theta);
366 Type hx = size_x * 0.5;
367 Type hy = size_y * 0.5;
368
369 Type left_up_x = (-hx) * cos_theta + (-hy) * sin_theta + center_x;
370 Type left_up_y = (-hx) * (-sin_theta) + (-hy) * cos_theta + center_y;
371 Type right_up_x = (-hx) * cos_theta + hy * sin_theta + center_x;
372 Type right_up_y = (-hx) * (-sin_theta) + hy * cos_theta + center_y;
373 Type right_down_x = hx * cos_theta + hy * sin_theta + center_x;
374 Type right_down_y = hx * (-sin_theta) + hy * cos_theta + center_y;
375 Type left_down_x = hx * cos_theta + (-hy) * sin_theta + center_x;
376 Type left_down_y = hx * (-sin_theta) + (-hy) * cos_theta + center_y;
377
378 (*corners)(0) = left_up_x;
379 (*corners)(1) = left_up_y;
380 (*corners)(2) = right_up_x;
381 (*corners)(3) = right_up_y;
382 (*corners)(4) = right_down_x;
383 (*corners)(5) = right_down_y;
384 (*corners)(6) = left_down_x;
385 (*corners)(7) = left_down_y;
386}

◆ CalculateCosTheta2DXY()

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

在文件 basic.h77 行定义.

78 {
79 T v1_len = static_cast<T>(sqrt((v1.head(2).cwiseProduct(v1.head(2))).sum()));
80 T v2_len = static_cast<T>(sqrt((v2.head(2).cwiseProduct(v2.head(2))).sum()));
81 if (v1_len < std::numeric_limits<T>::epsilon() ||
82 v2_len < std::numeric_limits<T>::epsilon()) {
83 return 0.0;
84 }
85 T cos_theta = (v1.head(2).cwiseProduct(v2.head(2))).sum() / (v1_len * v2_len);
86 return cos_theta;
87}

◆ CalculateDistAndDirToBoundary() [1/2]

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 common.h314 行定义.

319 {
320 using Type = typename PointT::Type;
321 Type dist_to_left = std::numeric_limits<Type>::max();
322 Eigen::Matrix<Type, 3, 1> direction_left;
323 Type dist_to_right = std::numeric_limits<Type>::max();
324 Eigen::Matrix<Type, 3, 1> direction_right;
325
326 for (size_t i = 0; i < left_boundary.size(); i++) {
327 Type dist_temp = std::numeric_limits<Type>::max();
328 Eigen::Matrix<Type, 3, 1> dir_temp;
329 if (CalculateDistAndDirToSegs(pt, left_boundary[i], &dist_temp,
330 &dir_temp)) {
331 if (dist_to_left > dist_temp) {
332 dist_to_left = dist_temp;
333 direction_left = dir_temp;
334 }
335 }
336 }
337
338 for (size_t i = 0; i < right_boundary.size(); i++) {
339 Type dist_temp = std::numeric_limits<Type>::max();
340 Eigen::Matrix<Type, 3, 1> dir_temp;
341 if (CalculateDistAndDirToSegs(pt, right_boundary[i], &dist_temp,
342 &dir_temp)) {
343 if (dist_to_right > dist_temp) {
344 dist_to_right = dist_temp;
345 direction_right = dir_temp;
346 }
347 }
348 }
349 if (dist_to_left < dist_to_right) {
350 (*dist) = dist_to_left;
351 (*dir) = direction_left;
352 } else {
353 (*dist) = dist_to_right;
354 (*dir) = direction_right;
355 }
356}
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)
Definition common.h:219

◆ CalculateDistAndDirToBoundary() [2/2]

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 common.h285 行定义.

289 {
290 using Type = typename PointT::Type;
291 Type dist_to_left = std::numeric_limits<Type>::max();
292 Eigen::Matrix<Type, 3, 1> direction_left;
293 Type dist_to_right = std::numeric_limits<Type>::max();
294 Eigen::Matrix<Type, 3, 1> direction_right;
295
296 CalculateDistAndDirToSegs(pt, left_boundary, &dist_to_left, &direction_left);
297
298 CalculateDistAndDirToSegs(pt, right_boundary, &dist_to_right,
299 &direction_right);
300
301 if (dist_to_left < dist_to_right) {
302 (*dist) = dist_to_left;
303 (*dir) = direction_left;
304 } else {
305 (*dist) = dist_to_right;
306 (*dir) = direction_right;
307 }
308}

◆ CalculateDistAndDirToSegs()

template<typename PointT >
bool apollo::perception::algorithm::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 
)

在文件 common.h219 行定义.

222 {
223 if (segs.size() < 2) {
224 return false;
225 }
226
227 using Type = typename PointT::Type;
228 Eigen::Matrix<Type, 3, 1> seg_point(segs[0].x, segs[0].y, 0);
229 Type min_dist = (pt - seg_point).head(2).norm();
230
231 Eigen::Matrix<Type, 3, 1> end_point_pre;
232 Eigen::Matrix<Type, 3, 1> end_point_cur;
233 Eigen::Matrix<Type, 3, 1> line_segment_dir;
234 Eigen::Matrix<Type, 3, 1> line_segment_dir_pre;
235 Eigen::Matrix<Type, 3, 1> end_point_to_pt_vec;
236
237 line_segment_dir_pre << 0, 0, 0;
238
239 Type line_segment_len = 0;
240 Type projected_len = 0;
241 Type point_to_line_dist = 0;
242 Type point_to_end_point_dist = 0;
243
244 for (size_t i = 1; i < segs.size(); ++i) {
245 end_point_pre << segs[i - 1].x, segs[i - 1].y, 0;
246 end_point_cur << segs[i].x, segs[i].y, 0;
247 line_segment_dir = end_point_pre - end_point_cur;
248 end_point_to_pt_vec = pt - end_point_cur;
249 end_point_to_pt_vec(2) = 0;
250 line_segment_len = line_segment_dir.head(2).norm();
251 line_segment_dir = line_segment_dir / line_segment_len;
252 if (i == 1) {
253 *dir = line_segment_dir;
254 }
255 projected_len = end_point_to_pt_vec.dot(line_segment_dir);
256 // case 1. pt is in the range of current line segment, compute
257 // the point to line distance
258 if (projected_len >= 0 && projected_len <= line_segment_len) {
259 point_to_line_dist = end_point_to_pt_vec.cross(line_segment_dir).norm();
260 if (min_dist > point_to_line_dist) {
261 min_dist = point_to_line_dist;
262 *dir = line_segment_dir;
263 }
264 } else {
265 // case 2. pt is out of range of current line segment, compute
266 // the point to end point distance
267 point_to_end_point_dist = end_point_to_pt_vec.head(2).norm();
268 if (min_dist > point_to_end_point_dist) {
269 min_dist = point_to_end_point_dist;
270 *dir = line_segment_dir + line_segment_dir_pre;
271 dir->normalize();
272 }
273 }
274 line_segment_dir_pre = line_segment_dir;
275 }
276 *dist = min_dist;
277
278 return true;
279}

◆ CalculateEuclidenDist()

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

在文件 basic.h55 行定义.

56 {
57 typename PointT::Type dist = (pt1.x - pt2.x) * (pt1.x - pt2.x);
58 dist += (pt1.y - pt2.y) * (pt1.y - pt2.y);
59 dist += (pt1.z - pt2.z) * (pt1.z - pt2.z);
60 return static_cast<typename PointT::Type>(sqrt(dist));
61}

◆ CalculateEuclidenDist2DXY()

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

在文件 basic.h66 行定义.

67 {
68 typename PointT::Type dist = (pt1.x - pt2.x) * (pt1.x - pt2.x);
69 dist += (pt1.y - pt2.y) * (pt1.y - pt2.y);
70 return static_cast<typename PointT::Type>(sqrt(dist));
71}

◆ CalculateIou2DXY()

template<typename Type >
Type apollo::perception::algorithm::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 
)

在文件 common.h174 行定义.

177 {
178 Type min_x_bbox_0 = center0(0) - size0(0) * static_cast<Type>(0.5);
179 Type min_x_bbox_1 = center1(0) - size1(0) * static_cast<Type>(0.5);
180 Type max_x_bbox_0 = center0(0) + size0(0) * static_cast<Type>(0.5);
181 Type max_x_bbox_1 = center1(0) + size1(0) * static_cast<Type>(0.5);
182 Type start_x = std::max(min_x_bbox_0, min_x_bbox_1);
183 Type end_x = std::min(max_x_bbox_0, max_x_bbox_1);
184 Type length_x = end_x - start_x;
185 if (length_x <= 0) {
186 return 0;
187 }
188 Type min_y_bbox_0 = center0(1) - size0(1) * static_cast<Type>(0.5);
189 Type min_y_bbox_1 = center1(1) - size1(1) * static_cast<Type>(0.5);
190 Type max_y_bbox_0 = center0(1) + size0(1) * static_cast<Type>(0.5);
191 Type max_y_bbox_1 = center1(1) + size1(1) * static_cast<Type>(0.5);
192 Type start_y = std::max(min_y_bbox_0, min_y_bbox_1);
193 Type end_y = std::min(max_y_bbox_0, max_y_bbox_1);
194 Type length_y = end_y - start_y;
195 if (length_y <= 0) {
196 return 0;
197 }
198 Type intersection_area = length_x * length_y;
199 Type bbox_0_area = size0(0) * size0(1);
200 Type bbox_1_area = size1(0) * size1(1);
201 Type iou =
202 intersection_area / (bbox_0_area + bbox_1_area - intersection_area);
203 return iou;
204}

◆ CalculateIOUBBox()

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

在文件 common.h206 行定义.

207 {
208 base::Rect<Type> rect1(box1);
209 base::Rect<Type> rect2(box2);
210 base::Rect<Type> intersection = rect1 & rect2;
211 base::Rect<Type> unionsection = rect1 | rect2;
212 return intersection.Area() / unionsection.Area();
213}

◆ CalculateMostConsistentBBoxDir2DXY()

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

在文件 common.h151 行定义.

153 {
154 Type dot_val_00 = prev_dir(0) * (*curr_dir)(0) + prev_dir(1) * (*curr_dir)(1);
155 Type dot_val_01 = prev_dir(0) * (*curr_dir)(1) - prev_dir(1) * (*curr_dir)(0);
156 if (fabs(dot_val_00) >= fabs(dot_val_01)) {
157 if (dot_val_00 < 0) {
158 (*curr_dir) = -(*curr_dir);
159 }
160 } else {
161 if (dot_val_01 < 0) {
162 (*curr_dir) =
163 Eigen::Matrix<Type, 3, 1>((*curr_dir)(1), -(*curr_dir)(0), 0);
164 } else {
165 (*curr_dir) =
166 Eigen::Matrix<Type, 3, 1>(-(*curr_dir)(1), (*curr_dir)(0), 0);
167 }
168 }
169}

◆ CalculateRadarCentroid()

template<typename T >
Eigen::Matrix< T, 3, 1 > apollo::perception::algorithm::CalculateRadarCentroid ( const base::AttributeRadarPointCloud< base::RadarPoint< T > > &  cloud)

在文件 common.h152 行定义.

153 {
154 size_t point_num = cloud.size();
155 Eigen::Matrix<T, 3, 1> centroid(0.0, 0.0, 0.0);
156 for (const auto &pt : cloud.points()) {
157 centroid[0] += pt.x;
158 centroid[1] += pt.y;
159 centroid[2] += pt.z;
160 }
161 if (point_num > 0) {
162 centroid[0] /= static_cast<T>(point_num);
163 centroid[1] /= static_cast<T>(point_num);
164 centroid[2] /= static_cast<T>(point_num);
165 }
166 return centroid;
167}

◆ CalculateRotationMat2DXY()

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

在文件 basic.h114 行定义.

115 {
116 T v1_len = static_cast<T>(sqrt((v1.head(2).cwiseProduct(v1.head(2))).sum()));
117 T v2_len = static_cast<T>(sqrt((v2.head(2).cwiseProduct(v2.head(2))).sum()));
118 if (v1_len < std::numeric_limits<T>::epsilon() ||
119 v2_len < std::numeric_limits<T>::epsilon()) {
120 return Eigen::Matrix<T, 3, 3>::Zero(3, 3);
121 }
122
123 const T cos_theta =
124 (v1.head(2).cwiseProduct(v2.head(2))).sum() / (v1_len * v2_len);
125 const T sin_theta = (v1(0) * v2(1) - v1(1) * v2(0)) / (v1_len * v2_len);
126
127 Eigen::Matrix<T, 3, 3> rot_mat;
128 rot_mat << cos_theta, sin_theta, 0, -sin_theta, cos_theta, 0, 0, 0, 1;
129 return rot_mat;
130}

◆ CalculateTheta2DXY()

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

在文件 basic.h92 行定义.

93 {
94 T v1_len = static_cast<T>(sqrt((v1.head(2).cwiseProduct(v1.head(2))).sum()));
95 T v2_len = static_cast<T>(sqrt((v2.head(2).cwiseProduct(v2.head(2))).sum()));
96 if (v1_len < std::numeric_limits<T>::epsilon() ||
97 v2_len < std::numeric_limits<T>::epsilon()) {
98 return 0.0;
99 }
100 const T cos_theta =
101 (v1.head(2).cwiseProduct(v2.head(2))).sum() / (v1_len * v2_len);
102 const T sin_theta = (v1(0) * v2(1) - v1(1) * v2(0)) / (v1_len * v2_len);
103 T theta = std::acos(cos_theta);
104 if (sin_theta < 0.0) {
105 theta = -theta;
106 }
107 return theta;
108}

◆ ConnectedComponentAnalysis()

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

在文件 connected_component_analysis.cc22 行定义.

23 {
24 if (components == nullptr) {
25 AERROR << "components is not available";
26 return;
27 }
28 int num_item = static_cast<int>(graph.size());
29 std::vector<int> visited;
30 visited.resize(num_item, 0);
31 std::queue<int> que;
32 std::vector<int> component;
33 component.reserve(num_item);
34 components->clear();
35
36 for (int index = 0; index < num_item; ++index) {
37 if (visited[index]) {
38 continue;
39 }
40 component.push_back(index);
41 que.push(index);
42 visited[index] = 1;
43 while (!que.empty()) {
44 int current_id = que.front();
45 que.pop();
46 for (size_t sub_index = 0; sub_index < graph[current_id].size();
47 ++sub_index) {
48 int neighbor_id = graph[current_id][sub_index];
49 if (visited[neighbor_id] == 0) {
50 component.push_back(neighbor_id);
51 que.push(neighbor_id);
52 visited[neighbor_id] = 1;
53 }
54 }
55 }
56 components->push_back(component);
57 component.clear();
58 }
59}
#define AERROR
Definition log.h:44

◆ ConvertCartesiantoPolarCoordinate()

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

在文件 basic.h160 行定义.

163 {
164 using T = typename PointT::Type;
165 const T radian_to_degree = 180.0 / M_PI;
166 const T x = xyz.x;
167 const T y = xyz.y;
168 const T z = xyz.z;
169
170 (*dist) = static_cast<T>(sqrt(x * x + y * y + z * z));
171 T dist_xy = static_cast<T>(sqrt(x * x + y * y));
172
173 (*h_angle_in_degree) = std::acos(x / dist_xy) * radian_to_degree;
174 if (y < 0.0) {
175 (*h_angle_in_degree) = static_cast<T>(360.0) - (*h_angle_in_degree);
176 }
177
178 (*v_angle_in_degree) = std::acos(dist_xy / (*dist)) * radian_to_degree;
179 if (z < 0.0) {
180 (*v_angle_in_degree) = -(*v_angle_in_degree);
181 }
182}

◆ CrossProduct() [1/2]

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

在文件 basic.h33 行定义.

35 {
36 return (point2.x() - point1.x()) * (point3.y() - point1.y()) -
37 (point3.x() - point1.x()) * (point2.y() - point1.y());
38}

◆ CrossProduct() [2/2]

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

在文件 basic.h45 行定义.

47 {
48 return (point2.x - point1.x) * (point3.y - point1.y) -
49 (point3.x - point1.x) * (point2.y - point1.y);
50}

◆ DownsamplingCircular()

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 downsampling.h36 行定义.

39 {
40 for (size_t c = 0; c < cloud->width(); ++c) {
41 for (size_t r = 0; r < cloud->height(); ++r) {
42 PointT tmp_pt;
43 if (cloud->height() > 1) {
44 const PointT* tmp_pt_ptr = cloud->at(c, r);
45 if (tmp_pt_ptr == nullptr) {
46 continue;
47 }
48 tmp_pt = *(tmp_pt_ptr);
49 } else {
50 tmp_pt = cloud->at(c);
51 }
52 if (CalculateEuclidenDist<PointT>(tmp_pt, center_pt) < radius) {
53 if (down_cloud->size() == 0) {
54 down_cloud->push_back(tmp_pt);
55 } else {
56 if (CalculateEuclidenDist<PointT>(
57 tmp_pt, down_cloud->at(down_cloud->size() - 1)) >=
58 neighbour_dist) {
59 down_cloud->push_back(tmp_pt);
60 }
61 }
62 }
63 }
64 }
65}

◆ DownsamplingCircularOrgAll()

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 downsampling.h72 行定义.

75 {
76 int smp_step = smp_ratio * velodyne_model;
77 down_cloud->resize(cloud->size() / smp_ratio + 1);
78 size_t ii = 0;
79 for (size_t ori_ii = 0; ori_ii < cloud->size(); ori_ii += smp_step) {
80 for (size_t jj = ori_ii;
81 jj < cloud->size() && static_cast<int>(jj - ori_ii) < velodyne_model;
82 ++jj) {
83 const PointT& p = cloud->at(jj);
84 if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
85 continue;
86 }
87 float r = CalculateEuclidenDist2DXY<PointT>(center_pt, p);
88 if (r > radius) {
89 continue;
90 }
91 down_cloud->at(jj).x = cloud->at(jj).x;
92 down_cloud->at(jj).y = cloud->at(jj).y;
93 down_cloud->at(jj).z = cloud->at(jj).z;
94 ++ii;
95 }
96 }
97 down_cloud->resize(ii);
98}

◆ DownsamplingCircularOrgPartial()

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 downsampling.h104 行定义.

109 {
110 int smp_height = static_cast<int>(cloud->height()) / smp_ratio;
111 int smp_width = org_num;
112 if (smp_width < 1 || smp_width >= velodyne_model) {
113 AERROR << "org_num error!";
114 return;
115 }
116 size_t ii = 0;
117 down_cloud->resize(smp_height * smp_width);
118 all_org_idx_ptr->resize(smp_height * smp_width);
119 for (int hh = 0; hh < smp_height; ++hh) {
120 for (int ww = 0; ww < smp_width; ++ww) {
121 int ori_hh = hh * smp_ratio;
122 const PointT* p_ptr = cloud->at(ww, ori_hh);
123 if (p_ptr == nullptr) {
124 continue;
125 }
126 const PointT& p = *(p_ptr);
127 if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
128 continue;
129 }
130 float r = CalculateEuclidenDist2DXY<PointT>(center_pt, p);
131 if (r > radius) {
132 continue;
133 } else {
134 down_cloud->at(ii) = p;
135 all_org_idx_ptr->at(ii).first = hh;
136 all_org_idx_ptr->at(ii).second = ww;
137 ++ii;
138 }
139 }
140 }
141 down_cloud->resize(ii);
142 all_org_idx_ptr->resize(ii);
143}

◆ DownsamplingRectangleNeighbour()

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 downsampling.h191 行定义.

194 {
195 if (static_cast<int>(cloud->width()) != velo_model) {
196 AERROR << "cloud->width (" << cloud->width() << ") does not match "
197 << "velo_model (" << velo_model << ")";
198 return;
199 }
200 down_cloud->resize(cloud->size());
201 size_t pt_num = 0;
202 for (size_t ww = 0; ww < cloud->width(); ++ww) {
203 PointT nei_pt;
204 nei_pt.x = 0;
205 nei_pt.y = 0;
206 nei_pt.z = 0;
207 for (size_t hh = 0; hh < cloud->height(); ++hh) {
208 const PointT* p_ptr = cloud->at(ww, hh);
209 if (p_ptr == nullptr) {
210 continue;
211 }
212 const PointT& p = *(p_ptr);
213 if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
214 continue;
215 }
216 if (fabs(p.x) > front_range || fabs(p.y) > side_range) {
217 continue;
218 }
219 if (fabs(p.x - nei_pt.x) > max_nei || fabs(p.y - nei_pt.y) > max_nei) {
220 nei_pt = p;
221 down_cloud->at(pt_num++) = p;
222 }
223 }
224 }
225 down_cloud->resize(pt_num);
226}

◆ DownsamplingRectangleOrgPartial()

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 downsampling.h148 行定义.

153 {
154 int smp_height = static_cast<int>(cloud->height()) / smp_ratio;
155 int smp_width = org_num;
156 if (smp_width < 1 || smp_width >= velodyne_model) {
157 AERROR << "org_num error!";
158 return;
159 }
160 size_t ii = 0;
161 down_cloud->resize(smp_height * smp_width);
162 all_org_idx_ptr->resize(smp_height * smp_width);
163 for (int hh = 0; hh < smp_height; ++hh) {
164 for (int ww = 0; ww < smp_width; ++ww) {
165 int ori_hh = hh * smp_ratio;
166 const PointT* p_ptr = cloud->at(ww, ori_hh);
167 if (p_ptr == nullptr) {
168 continue;
169 }
170 const PointT& p = *(p_ptr);
171 if (std::isnan(p.x) || std::isnan((p.y) || std::isnan(p.z))) {
172 continue;
173 }
174 if (fabs(p.x) > front_range || fabs(p.y) > side_range) {
175 continue;
176 } else {
177 down_cloud->at(ii) = p;
178 all_org_idx_ptr->at(ii).first = hh;
179 all_org_idx_ptr->at(ii).second = ww;
180 ++ii;
181 }
182 }
183 }
184 down_cloud->resize(ii);
185 all_org_idx_ptr->resize(ii);
186}

◆ ExtractIndicedCloud()

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

在文件 common.h70 行定义.

72 {
73 if (trans_cloud->size() != indices.size()) {
74 trans_cloud->resize(indices.size());
75 }
76 for (size_t i = 0; i < indices.size(); ++i) {
77 const auto &p = cloud->at(indices[i]);
78 auto &tp = trans_cloud->at(i);
79 tp.x = p.x;
80 tp.y = p.y;
81 tp.z = p.z;
82 tp.intensity = p.intensity;
83 }
84}

◆ GetFileList()

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

在文件 io_util.cc163 行定义.

164 {
165 if (!PathExists(path)) {
166 AINFO << path << " not exist.";
167 return false;
168 }
169
170 boost::filesystem::recursive_directory_iterator itr(path);
171 while (itr != boost::filesystem::recursive_directory_iterator()) {
172 try {
173 if (absl::EndsWith(itr->path().string(), suffix)) {
174 files->push_back(itr->path().string());
175 }
176 ++itr;
177 } catch (const std::exception &ex) {
178 AWARN << "Caught execption: " << ex.what();
179 continue;
180 }
181 }
182 return true;
183}
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43

◆ GetMinMaxIn3D() [1/2]

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 common.h115 行定义.

118 {
119 GetMinMaxIn3DWithRange<PointT>(cloud, indices.indices.size(), min_p, max_p);
120}

◆ GetMinMaxIn3D() [2/2]

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

在文件 common.h125 行定义.

127 {
128 GetMinMaxIn3DWithRange<PointT>(cloud, cloud.size(), min_p, max_p);
129}

◆ GetMinMaxIn3DWithRange()

template<typename PointT >
void apollo::perception::algorithm::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 
)

在文件 common.h89 行定义.

92 {
93 using T = typename PointT::Type;
94 (*min_p)[0] = (*min_p)[1] = (*min_p)[2] = std::numeric_limits<T>::max();
95 (*max_p)[0] = (*max_p)[1] = (*max_p)[2] = -std::numeric_limits<T>::max();
96 (*min_p)[3] = 0.0;
97 (*max_p)[3] = 0.0;
98 for (size_t i = 0; i < range; ++i) {
99 const auto &pt = cloud.at(i);
100 if (std::isnan(pt.x) || std::isnan(pt.y) || std::isnan(pt.z)) {
101 continue;
102 }
103 (*min_p)[0] = std::min((*min_p)[0], static_cast<T>(pt.x));
104 (*max_p)[0] = std::max((*max_p)[0], static_cast<T>(pt.x));
105 (*min_p)[1] = std::min((*min_p)[1], static_cast<T>(pt.y));
106 (*max_p)[1] = std::max((*max_p)[1], static_cast<T>(pt.y));
107 (*min_p)[2] = std::min((*min_p)[2], static_cast<T>(pt.z));
108 (*max_p)[2] = std::max((*max_p)[2], static_cast<T>(pt.z));
109 }
110}
const PointT * at(size_t col, size_t row) const
Definition point_cloud.h:63

◆ IAbs() [1/3]

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

在文件 i_basic.h31 行定义.

31{ return a < 0.0 ? -a : a; }

◆ IAbs() [2/3]

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

在文件 i_basic.h29 行定义.

29{ return a < 0.f ? -a : a; }

◆ IAbs() [3/3]

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

在文件 i_basic.h30 行定义.

30{ return a < 0 ? -a : a; }

◆ IAbsSum()

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

在文件 i_blas.h2423 行定义.

2423 {
2424 T acc = static_cast<T>(0.0);
2425 for (int i = 0; i < n; ++i) {
2426 acc += IAbs(x[i]);
2427 }
2428 return acc;
2429}

◆ IAcos() [1/2]

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

在文件 i_basic.h248 行定义.

248 {
249 if (alpha >= 1.0) {
250 return 0.0;
251 }
252 if (alpha < -1.0) {
253 return Constant<double>::PI();
254 }
255 return acos(alpha);
256}

◆ IAcos() [2/2]

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

在文件 i_basic.h239 行定义.

239 {
240 if (alpha >= 1.f) {
241 return 0.f;
242 }
243 if (alpha < -1.f) {
244 return Constant<float>::PI();
245 }
246 return acosf(alpha);
247}

◆ IAdd() [1/3]

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

在文件 i_blas.h793 行定义.

793 {
794 for (int i = 0; i < n; i++) {
795 z[i] = x[i] + y[i];
796 }
797}

◆ IAdd() [2/3]

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

在文件 i_blas.h1008 行定义.

1008 {
1009 for (int i = 0; i < n; i++) {
1010 y[i] += x[i];
1011 }
1012}

◆ IAdd() [3/3]

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

在文件 i_blas.h786 行定义.

786 {
787 for (int i = 0; i < n; i++) {
788 x[i] += k;
789 }
790}

◆ IAdd1() [1/2]

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

在文件 i_blas.h799 行定义.

799 {
800 z[0] = x[0] + y[0];
801}

◆ IAdd1() [2/2]

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

在文件 i_blas.h1014 行定义.

1014 {
1015 y[0] += x[0];
1016}

◆ IAdd10() [1/2]

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

在文件 i_blas.h871 行定义.

871 {
872 z[0] = x[0] + y[0];
873 z[1] = x[1] + y[1];
874 z[2] = x[2] + y[2];
875 z[3] = x[3] + y[3];
876 z[4] = x[4] + y[4];
877 z[5] = x[5] + y[5];
878 z[6] = x[6] + y[6];
879 z[7] = x[7] + y[7];
880 z[8] = x[8] + y[8];
881 z[9] = x[9] + y[9];
882}

◆ IAdd10() [2/2]

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

在文件 i_blas.h1086 行定义.

1086 {
1087 y[0] += x[0];
1088 y[1] += x[1];
1089 y[2] += x[2];
1090 y[3] += x[3];
1091 y[4] += x[4];
1092 y[5] += x[5];
1093 y[6] += x[6];
1094 y[7] += x[7];
1095 y[8] += x[8];
1096 y[9] += x[9];
1097}

◆ IAdd11() [1/2]

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

在文件 i_blas.h884 行定义.

884 {
885 z[0] = x[0] + y[0];
886 z[1] = x[1] + y[1];
887 z[2] = x[2] + y[2];
888 z[3] = x[3] + y[3];
889 z[4] = x[4] + y[4];
890 z[5] = x[5] + y[5];
891 z[6] = x[6] + y[6];
892 z[7] = x[7] + y[7];
893 z[8] = x[8] + y[8];
894 z[9] = x[9] + y[9];
895 z[10] = x[10] + y[10];
896}

◆ IAdd11() [2/2]

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

在文件 i_blas.h1099 行定义.

1099 {
1100 y[0] += x[0];
1101 y[1] += x[1];
1102 y[2] += x[2];
1103 y[3] += x[3];
1104 y[4] += x[4];
1105 y[5] += x[5];
1106 y[6] += x[6];
1107 y[7] += x[7];
1108 y[8] += x[8];
1109 y[9] += x[9];
1110 y[10] += x[10];
1111}

◆ IAdd12() [1/2]

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

在文件 i_blas.h898 行定义.

898 {
899 z[0] = x[0] + y[0];
900 z[1] = x[1] + y[1];
901 z[2] = x[2] + y[2];
902 z[3] = x[3] + y[3];
903 z[4] = x[4] + y[4];
904 z[5] = x[5] + y[5];
905 z[6] = x[6] + y[6];
906 z[7] = x[7] + y[7];
907 z[8] = x[8] + y[8];
908 z[9] = x[9] + y[9];
909 z[10] = x[10] + y[10];
910 z[11] = x[11] + y[11];
911}

◆ IAdd12() [2/2]

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

在文件 i_blas.h1113 行定义.

1113 {
1114 y[0] += x[0];
1115 y[1] += x[1];
1116 y[2] += x[2];
1117 y[3] += x[3];
1118 y[4] += x[4];
1119 y[5] += x[5];
1120 y[6] += x[6];
1121 y[7] += x[7];
1122 y[8] += x[8];
1123 y[9] += x[9];
1124 y[10] += x[10];
1125 y[11] += x[11];
1126}

◆ IAdd13() [1/2]

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

在文件 i_blas.h913 行定义.

913 {
914 z[0] = x[0] + y[0];
915 z[1] = x[1] + y[1];
916 z[2] = x[2] + y[2];
917 z[3] = x[3] + y[3];
918 z[4] = x[4] + y[4];
919 z[5] = x[5] + y[5];
920 z[6] = x[6] + y[6];
921 z[7] = x[7] + y[7];
922 z[8] = x[8] + y[8];
923 z[9] = x[9] + y[9];
924 z[10] = x[10] + y[10];
925 z[11] = x[11] + y[11];
926 z[12] = x[12] + y[12];
927}

◆ IAdd13() [2/2]

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

在文件 i_blas.h1128 行定义.

1128 {
1129 y[0] += x[0];
1130 y[1] += x[1];
1131 y[2] += x[2];
1132 y[3] += x[3];
1133 y[4] += x[4];
1134 y[5] += x[5];
1135 y[6] += x[6];
1136 y[7] += x[7];
1137 y[8] += x[8];
1138 y[9] += x[9];
1139 y[10] += x[10];
1140 y[11] += x[11];
1141 y[12] += x[12];
1142}

◆ IAdd14() [1/2]

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

在文件 i_blas.h929 行定义.

929 {
930 z[0] = x[0] + y[0];
931 z[1] = x[1] + y[1];
932 z[2] = x[2] + y[2];
933 z[3] = x[3] + y[3];
934 z[4] = x[4] + y[4];
935 z[5] = x[5] + y[5];
936 z[6] = x[6] + y[6];
937 z[7] = x[7] + y[7];
938 z[8] = x[8] + y[8];
939 z[9] = x[9] + y[9];
940 z[10] = x[10] + y[10];
941 z[11] = x[11] + y[11];
942 z[12] = x[12] + y[12];
943 z[13] = x[13] + y[13];
944}

◆ IAdd14() [2/2]

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

在文件 i_blas.h1144 行定义.

1144 {
1145 y[0] += x[0];
1146 y[1] += x[1];
1147 y[2] += x[2];
1148 y[3] += x[3];
1149 y[4] += x[4];
1150 y[5] += x[5];
1151 y[6] += x[6];
1152 y[7] += x[7];
1153 y[8] += x[8];
1154 y[9] += x[9];
1155 y[10] += x[10];
1156 y[11] += x[11];
1157 y[12] += x[12];
1158 y[13] += x[13];
1159}

◆ IAdd15() [1/2]

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

在文件 i_blas.h946 行定义.

946 {
947 z[0] = x[0] + y[0];
948 z[1] = x[1] + y[1];
949 z[2] = x[2] + y[2];
950 z[3] = x[3] + y[3];
951 z[4] = x[4] + y[4];
952 z[5] = x[5] + y[5];
953 z[6] = x[6] + y[6];
954 z[7] = x[7] + y[7];
955 z[8] = x[8] + y[8];
956 z[9] = x[9] + y[9];
957 z[10] = x[10] + y[10];
958 z[11] = x[11] + y[11];
959 z[12] = x[12] + y[12];
960 z[13] = x[13] + y[13];
961 z[14] = x[14] + y[14];
962}

◆ IAdd15() [2/2]

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

在文件 i_blas.h1161 行定义.

1161 {
1162 y[0] += x[0];
1163 y[1] += x[1];
1164 y[2] += x[2];
1165 y[3] += x[3];
1166 y[4] += x[4];
1167 y[5] += x[5];
1168 y[6] += x[6];
1169 y[7] += x[7];
1170 y[8] += x[8];
1171 y[9] += x[9];
1172 y[10] += x[10];
1173 y[11] += x[11];
1174 y[12] += x[12];
1175 y[13] += x[13];
1176 y[14] += x[14];
1177}

◆ IAdd16() [1/2]

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

在文件 i_blas.h964 行定义.

964 {
965 z[0] = x[0] + y[0];
966 z[1] = x[1] + y[1];
967 z[2] = x[2] + y[2];
968 z[3] = x[3] + y[3];
969 z[4] = x[4] + y[4];
970 z[5] = x[5] + y[5];
971 z[6] = x[6] + y[6];
972 z[7] = x[7] + y[7];
973 z[8] = x[8] + y[8];
974 z[9] = x[9] + y[9];
975 z[10] = x[10] + y[10];
976 z[11] = x[11] + y[11];
977 z[12] = x[12] + y[12];
978 z[13] = x[13] + y[13];
979 z[14] = x[14] + y[14];
980 z[15] = x[15] + y[15];
981}

◆ IAdd16() [2/2]

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

在文件 i_blas.h1179 行定义.

1179 {
1180 y[0] += x[0];
1181 y[1] += x[1];
1182 y[2] += x[2];
1183 y[3] += x[3];
1184 y[4] += x[4];
1185 y[5] += x[5];
1186 y[6] += x[6];
1187 y[7] += x[7];
1188 y[8] += x[8];
1189 y[9] += x[9];
1190 y[10] += x[10];
1191 y[11] += x[11];
1192 y[12] += x[12];
1193 y[13] += x[13];
1194 y[14] += x[14];
1195 y[15] += x[15];
1196}

◆ IAdd2() [1/2]

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

在文件 i_blas.h803 行定义.

803 {
804 z[0] = x[0] + y[0];
805 z[1] = x[1] + y[1];
806}

◆ IAdd2() [2/2]

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

在文件 i_blas.h1018 行定义.

1018 {
1019 y[0] += x[0];
1020 y[1] += x[1];
1021}

◆ IAdd20() [1/2]

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

在文件 i_blas.h983 行定义.

983 {
984 z[0] = x[0] + y[0];
985 z[1] = x[1] + y[1];
986 z[2] = x[2] + y[2];
987 z[3] = x[3] + y[3];
988 z[4] = x[4] + y[4];
989 z[5] = x[5] + y[5];
990 z[6] = x[6] + y[6];
991 z[7] = x[7] + y[7];
992 z[8] = x[8] + y[8];
993 z[9] = x[9] + y[9];
994 z[10] = x[10] + y[10];
995 z[11] = x[11] + y[11];
996 z[12] = x[12] + y[12];
997 z[13] = x[13] + y[13];
998 z[14] = x[14] + y[14];
999 z[15] = x[15] + y[15];
1000 z[16] = x[16] + y[16];
1001 z[17] = x[17] + y[17];
1002 z[18] = x[18] + y[18];
1003 z[19] = x[19] + y[19];
1004}

◆ IAdd20() [2/2]

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

在文件 i_blas.h1198 行定义.

1198 {
1199 y[0] += x[0];
1200 y[1] += x[1];
1201 y[2] += x[2];
1202 y[3] += x[3];
1203 y[4] += x[4];
1204 y[5] += x[5];
1205 y[6] += x[6];
1206 y[7] += x[7];
1207 y[8] += x[8];
1208 y[9] += x[9];
1209 y[10] += x[10];
1210 y[11] += x[11];
1211 y[12] += x[12];
1212 y[13] += x[13];
1213 y[14] += x[14];
1214 y[15] += x[15];
1215 y[16] += x[16];
1216 y[17] += x[17];
1217 y[18] += x[18];
1218 y[19] += x[19];
1219}

◆ IAdd3() [1/2]

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

在文件 i_blas.h808 行定义.

808 {
809 z[0] = x[0] + y[0];
810 z[1] = x[1] + y[1];
811 z[2] = x[2] + y[2];
812}

◆ IAdd3() [2/2]

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

在文件 i_blas.h1023 行定义.

1023 {
1024 y[0] += x[0];
1025 y[1] += x[1];
1026 y[2] += x[2];
1027}

◆ IAdd4() [1/2]

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

在文件 i_blas.h814 行定义.

814 {
815 z[0] = x[0] + y[0];
816 z[1] = x[1] + y[1];
817 z[2] = x[2] + y[2];
818 z[3] = x[3] + y[3];
819}

◆ IAdd4() [2/2]

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

在文件 i_blas.h1029 行定义.

1029 {
1030 y[0] += x[0];
1031 y[1] += x[1];
1032 y[2] += x[2];
1033 y[3] += x[3];
1034}

◆ IAdd5() [1/2]

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

在文件 i_blas.h821 行定义.

821 {
822 z[0] = x[0] + y[0];
823 z[1] = x[1] + y[1];
824 z[2] = x[2] + y[2];
825 z[3] = x[3] + y[3];
826 z[4] = x[4] + y[4];
827}

◆ IAdd5() [2/2]

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

在文件 i_blas.h1036 行定义.

1036 {
1037 y[0] += x[0];
1038 y[1] += x[1];
1039 y[2] += x[2];
1040 y[3] += x[3];
1041 y[4] += x[4];
1042}

◆ IAdd6() [1/2]

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

在文件 i_blas.h829 行定义.

829 {
830 z[0] = x[0] + y[0];
831 z[1] = x[1] + y[1];
832 z[2] = x[2] + y[2];
833 z[3] = x[3] + y[3];
834 z[4] = x[4] + y[4];
835 z[5] = x[5] + y[5];
836}

◆ IAdd6() [2/2]

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

在文件 i_blas.h1044 行定义.

1044 {
1045 y[0] += x[0];
1046 y[1] += x[1];
1047 y[2] += x[2];
1048 y[3] += x[3];
1049 y[4] += x[4];
1050 y[5] += x[5];
1051}

◆ IAdd7() [1/2]

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

在文件 i_blas.h838 行定义.

838 {
839 z[0] = x[0] + y[0];
840 z[1] = x[1] + y[1];
841 z[2] = x[2] + y[2];
842 z[3] = x[3] + y[3];
843 z[4] = x[4] + y[4];
844 z[5] = x[5] + y[5];
845 z[6] = x[6] + y[6];
846}

◆ IAdd7() [2/2]

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

在文件 i_blas.h1053 行定义.

1053 {
1054 y[0] += x[0];
1055 y[1] += x[1];
1056 y[2] += x[2];
1057 y[3] += x[3];
1058 y[4] += x[4];
1059 y[5] += x[5];
1060 y[6] += x[6];
1061}

◆ IAdd8() [1/2]

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

在文件 i_blas.h848 行定义.

848 {
849 z[0] = x[0] + y[0];
850 z[1] = x[1] + y[1];
851 z[2] = x[2] + y[2];
852 z[3] = x[3] + y[3];
853 z[4] = x[4] + y[4];
854 z[5] = x[5] + y[5];
855 z[6] = x[6] + y[6];
856 z[7] = x[7] + y[7];
857}

◆ IAdd8() [2/2]

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

在文件 i_blas.h1063 行定义.

1063 {
1064 y[0] += x[0];
1065 y[1] += x[1];
1066 y[2] += x[2];
1067 y[3] += x[3];
1068 y[4] += x[4];
1069 y[5] += x[5];
1070 y[6] += x[6];
1071 y[7] += x[7];
1072}

◆ IAdd9() [1/2]

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

在文件 i_blas.h859 行定义.

859 {
860 z[0] = x[0] + y[0];
861 z[1] = x[1] + y[1];
862 z[2] = x[2] + y[2];
863 z[3] = x[3] + y[3];
864 z[4] = x[4] + y[4];
865 z[5] = x[5] + y[5];
866 z[6] = x[6] + y[6];
867 z[7] = x[7] + y[7];
868 z[8] = x[8] + y[8];
869}

◆ IAdd9() [2/2]

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

在文件 i_blas.h1074 行定义.

1074 {
1075 y[0] += x[0];
1076 y[1] += x[1];
1077 y[2] += x[2];
1078 y[3] += x[3];
1079 y[4] += x[4];
1080 y[5] += x[5];
1081 y[6] += x[6];
1082 y[7] += x[7];
1083 y[8] += x[8];
1084}

◆ IAddScaled() [1/2]

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

在文件 i_blas.h1303 行定义.

1303 {
1304 for (int i = 0; i < n; i++) {
1305 z[i] = x[i] + y[i] * k;
1306 }
1307}

◆ IAddScaled() [2/2]

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

在文件 i_blas.h1223 行定义.

1223 {
1224 for (int i = 0; i < n; i++) {
1225 y[i] += (x[i] * k);
1226 }
1227}

◆ IAddScaled1() [1/2]

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

在文件 i_blas.h1309 行定义.

1309 {
1310 z[0] = x[0] + y[0] * k;
1311}

◆ IAddScaled1() [2/2]

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

在文件 i_blas.h1229 行定义.

1229 {
1230 y[0] += x[0] * k;
1231}

◆ IAddScaled2() [1/2]

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

在文件 i_blas.h1313 行定义.

1313 {
1314 z[0] = x[0] + y[0] * k;
1315 z[1] = x[1] + y[1] * k;
1316}

◆ IAddScaled2() [2/2]

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

在文件 i_blas.h1233 行定义.

1233 {
1234 y[0] += x[0] * k;
1235 y[1] += x[1] * k;
1236}

◆ IAddScaled3() [1/2]

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

在文件 i_blas.h1318 行定义.

1318 {
1319 z[0] = x[0] + y[0] * k;
1320 z[1] = x[1] + y[1] * k;
1321 z[2] = x[2] + y[2] * k;
1322}

◆ IAddScaled3() [2/2]

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

在文件 i_blas.h1238 行定义.

1238 {
1239 y[0] += x[0] * k;
1240 y[1] += x[1] * k;
1241 y[2] += x[2] * k;
1242}

◆ IAddScaled4() [1/2]

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

在文件 i_blas.h1324 行定义.

1324 {
1325 z[0] = x[0] + y[0] * k;
1326 z[1] = x[1] + y[1] * k;
1327 z[2] = x[2] + y[2] * k;
1328 z[3] = x[3] + y[3] * k;
1329}

◆ IAddScaled4() [2/2]

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

在文件 i_blas.h1244 行定义.

1244 {
1245 y[0] += x[0] * k;
1246 y[1] += x[1] * k;
1247 y[2] += x[2] * k;
1248 y[3] += x[3] * k;
1249}

◆ IAddScaled5() [1/2]

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

在文件 i_blas.h1331 行定义.

1331 {
1332 z[0] = x[0] + y[0] * k;
1333 z[1] = x[1] + y[1] * k;
1334 z[2] = x[2] + y[2] * k;
1335 z[3] = x[3] + y[3] * k;
1336 z[4] = x[4] + y[4] * k;
1337}

◆ IAddScaled5() [2/2]

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

在文件 i_blas.h1251 行定义.

1251 {
1252 y[0] += x[0] * k;
1253 y[1] += x[1] * k;
1254 y[2] += x[2] * k;
1255 y[3] += x[3] * k;
1256 y[4] += x[4] * k;
1257}

◆ IAddScaled6() [1/2]

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

在文件 i_blas.h1339 行定义.

1339 {
1340 z[0] = x[0] + y[0] * k;
1341 z[1] = x[1] + y[1] * k;
1342 z[2] = x[2] + y[2] * k;
1343 z[3] = x[3] + y[3] * k;
1344 z[4] = x[4] + y[4] * k;
1345 z[5] = x[5] + y[5] * k;
1346}

◆ IAddScaled6() [2/2]

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

在文件 i_blas.h1259 行定义.

1259 {
1260 y[0] += x[0] * k;
1261 y[1] += x[1] * k;
1262 y[2] += x[2] * k;
1263 y[3] += x[3] * k;
1264 y[4] += x[4] * k;
1265 y[5] += x[5] * k;
1266}

◆ IAddScaled7() [1/2]

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

在文件 i_blas.h1348 行定义.

1348 {
1349 z[0] = x[0] + y[0] * k;
1350 z[1] = x[1] + y[1] * k;
1351 z[2] = x[2] + y[2] * k;
1352 z[3] = x[3] + y[3] * k;
1353 z[4] = x[4] + y[4] * k;
1354 z[5] = x[5] + y[5] * k;
1355 z[6] = x[6] + y[6] * k;
1356}

◆ IAddScaled7() [2/2]

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

在文件 i_blas.h1268 行定义.

1268 {
1269 y[0] += x[0] * k;
1270 y[1] += x[1] * k;
1271 y[2] += x[2] * k;
1272 y[3] += x[3] * k;
1273 y[4] += x[4] * k;
1274 y[5] += x[5] * k;
1275 y[6] += x[6] * k;
1276}

◆ IAddScaled8() [1/2]

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

在文件 i_blas.h1358 行定义.

1358 {
1359 z[0] = x[0] + y[0] * k;
1360 z[1] = x[1] + y[1] * k;
1361 z[2] = x[2] + y[2] * k;
1362 z[3] = x[3] + y[3] * k;
1363 z[4] = x[4] + y[4] * k;
1364 z[5] = x[5] + y[5] * k;
1365 z[6] = x[6] + y[6] * k;
1366 z[7] = x[7] + y[7] * k;
1367}

◆ IAddScaled8() [2/2]

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

在文件 i_blas.h1278 行定义.

1278 {
1279 y[0] += x[0] * k;
1280 y[1] += x[1] * k;
1281 y[2] += x[2] * k;
1282 y[3] += x[3] * k;
1283 y[4] += x[4] * k;
1284 y[5] += x[5] * k;
1285 y[6] += x[6] * k;
1286 y[7] += x[7] * k;
1287}

◆ IAddScaled9() [1/2]

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

在文件 i_blas.h1369 行定义.

1369 {
1370 z[0] = x[0] + y[0] * k;
1371 z[1] = x[1] + y[1] * k;
1372 z[2] = x[2] + y[2] * k;
1373 z[3] = x[3] + y[3] * k;
1374 z[4] = x[4] + y[4] * k;
1375 z[5] = x[5] + y[5] * k;
1376 z[6] = x[6] + y[6] * k;
1377 z[7] = x[7] + y[7] * k;
1378 z[8] = x[8] + y[8] * k;
1379}

◆ IAddScaled9() [2/2]

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

在文件 i_blas.h1289 行定义.

1289 {
1290 y[0] += x[0] * k;
1291 y[1] += x[1] * k;
1292 y[2] += x[2] * k;
1293 y[3] += x[3] * k;
1294 y[4] += x[4] * k;
1295 y[5] += x[5] * k;
1296 y[6] += x[6] * k;
1297 y[7] += x[7] * k;
1298 y[8] += x[8] * k;
1299}

◆ IAlloc()

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

在文件 i_alloc.h39 行定义.

39 {
40 T *mem = nullptr;
41 if (!memory_size) {
42 return mem;
43 }
44 mem = new (std::nothrow) T[memory_size];
45 if (mem == nullptr) {
46 return nullptr;
47 }
48 return mem;
49}

◆ IAlloc2()

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

在文件 i_alloc.h61 行定义.

61 {
62 T *mem = nullptr;
63 T **head = nullptr;
64 mem = new (std::nothrow) T[m * n];
65 if (mem == nullptr) {
66 return nullptr;
67 }
68 head = new (std::nothrow) T *[m];
69 if (head == nullptr) {
70 delete[] mem;
71 return nullptr;
72 }
73 IMakeReference<T>(mem, head, m, n);
74 return head;
75}

◆ IAlloc3()

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

在文件 i_alloc.h89 行定义.

89 {
90 T *mem = nullptr;
91 T ***head = nullptr;
92 int i, j;
93 mem = new (std::nothrow) T[l * m * n];
94 if (mem == nullptr) {
95 return nullptr;
96 }
97 head = new (std::nothrow) T **[l];
98 if (head == nullptr) {
99 delete[] mem;
100 return nullptr;
101 }
102 for (i = 0; i < l; i++) {
103 head[i] = new (std::nothrow) T *[m];
104 if (head[i] == nullptr) {
105 for (j = 0; j < i; j++) {
106 delete[] head[j];
107 }
108 delete[] head;
109 delete[] mem;
110 return nullptr;
111 }
112 }
113 IMakeReference(mem, head, l, m, n);
114 return head;
115}
void IMakeReference(T *a, T **p, int m, int n)
Definition i_basic.h:357

◆ IAllocAligned()

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

在文件 i_alloc.h119 行定义.

119 {
120 if (memory_size <= 0) {
121 return (reinterpret_cast<T *>(NULL));
122 }
123 int actual_alignment_power = (alignment_power >= 0) ? alignment_power : 0;
124 std::size_t memory_size_in_byte =
125 static_cast<size_t>(memory_size) * sizeof(T);
126 std::size_t mask = static_cast<size_t>((1 << actual_alignment_power) - 1);
127 std::size_t pointer_size_in_byte = sizeof(char *);
128 char *mem_begin = new (
129 std::nothrow) char[memory_size_in_byte + mask + pointer_size_in_byte];
130 if (!mem_begin) {
131 return (reinterpret_cast<T *>(NULL));
132 }
133 char *mem_actual = reinterpret_cast<char *>(
134 (reinterpret_cast<size_t>(mem_begin) + mask + pointer_size_in_byte) &
135 (~mask));
136 (reinterpret_cast<char **>(mem_actual))[-1] = mem_begin;
137 return (reinterpret_cast<T *>(mem_actual));
138}

◆ IAsin() [1/2]

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

在文件 i_basic.h230 行定义.

230 {
231 if (alpha >= 1.0) {
233 }
234 if (alpha < -1.0) {
235 return -Constant<double>::HALF_PI();
236 }
237 return asin(alpha);
238}

◆ IAsin() [2/2]

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

在文件 i_basic.h221 行定义.

221 {
222 if (alpha >= 1.f) {
224 }
225 if (alpha < -1.f) {
226 return -Constant<float>::HALF_PI();
227 }
228 return asinf(alpha);
229}

◆ IAssignPointToVoxel()

template<typename T >
int apollo::perception::algorithm::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

在文件 i_struct_s.h160 行定义.

164 {
165 int i, j, k;
166 T x = data[0];
167 T y = data[1];
168 T z = data[2];
169
170 // points that are outside the defined BBOX are ignored
171 if (x < bound_x_min || x > bound_x_max || y < bound_y_min ||
172 y > bound_y_max || z < bound_z_min || z > bound_z_max) {
173 return (-1);
174 }
175
176 // compute the x, y voxel indices
177 k = IMin(nr_voxel_x - 1,
178 static_cast<int>((x - bound_x_min) * voxel_width_x_rec));
179 j = IMin(nr_voxel_y - 1,
180 static_cast<int>((y - bound_y_min) * voxel_width_y_rec));
181 i = (nr_voxel_x * j) + k;
182 return (i);
183}

◆ IAtan2() [1/2]

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

在文件 i_basic.h258 行定义.

258{ return atan2(y, x); }

◆ IAtan2() [2/2]

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

在文件 i_basic.h257 行定义.

257{ return atan2f(y, x); }

◆ IAugmentDiagonal()

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

在文件 i_blas.h4299 行定义.

4299 {
4300 T *Ai;
4301 int i, ni = 0;
4302 for (i = 0; i < n; ++i, ni += n) {
4303 Ai = A + ni;
4304 Ai[i] += lambda;
4305 }
4306}

◆ IAverage()

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

在文件 i_basic.h167 行定义.

167 {
168 return (a + b) / 2;
169}

◆ IAxiator()

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

在文件 i_blas.h3727 行定义.

3727 {
3728 e_x[0] = static_cast<T>(0.0);
3729 e_x[1] = -x[2];
3730 e_x[2] = x[1];
3731 e_x[3] = x[2];
3732 e_x[4] = static_cast<T>(0.0);
3733 e_x[5] = -x[0];
3734 e_x[6] = -x[1];
3735 e_x[7] = x[0];
3736 e_x[8] = static_cast<T>(0.0);
3737}

◆ IBackprojectCanonical()

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

在文件 i_util.h164 行定义.

164 {
165 X[0] = (x[0] - K[2]) * depth * IRec(K[0]);
166 X[1] = (x[1] - K[5]) * depth * IRec(K[4]);
167 X[2] = depth;
168}

◆ IBackprojectPlaneIntersectionCanonical()

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

在文件 i_util.h197 行定义.

198 {
199 IZero3(X);
200 T umcx = IDiv(x[0] - K[2], K[0]);
201 T vmcy = IDiv(x[1] - K[5], K[4]);
202 T sf = pi[0] * umcx + pi[1] * vmcy + pi[2];
203 if (sf == static_cast<T>(0.0)) {
204 return false;
205 }
206 T Z = -pi[3] / sf;
207 X[0] = Z * umcx;
208 X[1] = Z * vmcy;
209 X[2] = Z;
210 return Z > static_cast<T>(0.0);
211}
float IDiv(float a, float b)
Definition i_basic.h:35

◆ IBackprojectThroughKRt()

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

在文件 i_util.h173 行定义.

174 {
175 // K^-1*[u,v,1]':
176 T u = (x[0] - K[2]) * IRec(K[0]);
177 T v = (x[1] - K[5]) * IRec(K[4]);
178 // R^-1*K^-1*[u,v,1]':
179 T ru = R[0] * u + R[3] * v + R[6];
180 T rv = R[1] * u + R[4] * v + R[7];
181 T rw = R[2] * u + R[5] * v + R[8];
182 // R^-1*t:
183 T tu = R[0] * t[0] + R[3] * t[1] + R[6] * t[2];
184 T tv = R[1] * t[0] + R[4] * t[1] + R[7] * t[2];
185 T tw = R[2] * t[0] + R[5] * t[1] + R[8] * t[2];
186 T w = IDiv(depth + tw, rw); // scale factor
187 X[0] = ru * w - tu;
188 X[1] = rv * w - tv;
189 X[2] = depth;
190}

◆ ICbrt() [1/4]

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

在文件 i_basic.h97 行定义.

97 {
98 return (a >= 0.0) ? pow(a, 1.0 / 3) : -pow(-a, 1.0 / 3);
99}

◆ ICbrt() [2/4]

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

在文件 i_basic.h87 行定义.

87 {
88 return (a >= 0.f) ? powf(a, 1.f / 3) : -powf(-a, 1.f / 3);
89}

◆ ICbrt() [3/4]

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

在文件 i_basic.h90 行定义.

90 {
91 return (a >= 0) ? pow(static_cast<double>(a), 1.0 / 3)
92 : -pow(-static_cast<double>(a), 1.0 / 3);
93}

◆ ICbrt() [4/4]

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

在文件 i_basic.h94 行定义.

94 {
95 return pow(static_cast<double>(a), 1.0 / 3);
96}

◆ ICeil() [1/3]

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

在文件 i_basic.h211 行定义.

211{ return static_cast<int>(ceil(a)); }

◆ ICeil() [2/3]

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

在文件 i_basic.h210 行定义.

210{ return static_cast<int>(ceilf(a)); }

◆ ICeil() [3/3]

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

在文件 i_basic.h209 行定义.

209{ return (a); }

◆ ICentroid2() [1/4]

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

在文件 i_blas.h3144 行定义.

3144 {
3145 int length = 2 * n;
3146 IFill2(centroid, 0.0);
3147 for (int i = 0; i < length; i += 2) {
3148 IAdd2(a + i, centroid);
3149 }
3150 IScale2(centroid, IRec(n));
3151}
void IFill2(T a[2], T val)
Definition i_blas.h:252
void IAdd2(const T x[2], const T y[2], T z[2])
Definition i_blas.h:803

◆ ICentroid2() [2/4]

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

在文件 i_blas.h3191 行定义.

3192 {
3193 int length = 2 * n;
3194 int i, j;
3195 IFill2(centroid, 0.0);
3196 for (i = 0; i < length; i += 2) {
3197 IAdd2(a + i, centroid);
3198 }
3199 IScale2(centroid, IRec(n));
3200 for (i = 0, j = 0; i < n; ++i, j += 2) {
3201 distances[i] = ISqrt(ISquaresumDiffU2(a + j, centroid));
3202 }
3203}

◆ ICentroid2() [3/4]

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

在文件 i_blas.h3152 行定义.

3152 {
3153 int length = 2 * n;
3154 IFill2(centroid, 0.f);
3155 for (int i = 0; i < length; i += 2) {
3156 IAdd2(a + i, centroid);
3157 }
3158 IScale2(centroid, static_cast<float>(IRec(n)));
3159}

◆ ICentroid2() [4/4]

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

在文件 i_blas.h3204 行定义.

3205 {
3206 int length = 2 * n;
3207 int i, j;
3208 IFill2(centroid, 0.f);
3209 for (i = 0; i < length; i += 2) {
3210 IAdd2(a + i, centroid);
3211 }
3212 IScale2(centroid, static_cast<float>(IRec(n)));
3213 for (i = 0, j = 0; i < n; ++i, j += 2) {
3214 distances[i] = ISqrt(ISquaresumDiffU2(a + j, centroid));
3215 }
3216}

◆ ICentroid3() [1/4]

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

在文件 i_blas.h3127 行定义.

3127 {
3128 int length = 3 * n;
3129 IFill3(centroid, 0.0);
3130 for (int i = 0; i < length; i += 3) {
3131 IAdd3(a + i, centroid);
3132 }
3133 IScale3(centroid, IRec(n));
3134}
void IFill3(T a[3], T val)
Definition i_blas.h:256
void IAdd3(const T x[3], const T y[3], T z[3])
Definition i_blas.h:808

◆ ICentroid3() [2/4]

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

在文件 i_blas.h3163 行定义.

3164 {
3165 int length = 3 * n;
3166 int i, j;
3167 IFill3(centroid, 0.0);
3168 for (i = 0; i < length; i += 3) {
3169 IAdd3(a + i, centroid);
3170 }
3171 IScale3(centroid, IRec(n));
3172 for (i = 0, j = 0; i < n; ++i, j += 3) {
3173 distances[i] = ISqrt(ISquaresumDiffU3(a + j, centroid));
3174 }
3175}

◆ ICentroid3() [3/4]

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

在文件 i_blas.h3135 行定义.

3135 {
3136 int length = 3 * n;
3137 IFill3(centroid, 0.f);
3138 for (int i = 0; i < length; i += 3) {
3139 IAdd3(a + i, centroid);
3140 }
3141 IScale3(centroid, static_cast<float>(IRec(n)));
3142}

◆ ICentroid3() [4/4]

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

在文件 i_blas.h3176 行定义.

3177 {
3178 int length = 3 * n;
3179 int i, j;
3180 IFill3(centroid, 0.f);
3181 for (i = 0; i < length; i += 3) {
3182 IAdd3(a + i, centroid);
3183 }
3184 IScale3(centroid, static_cast<float>(IRec(n)));
3185 for (i = 0, j = 0; i < n; ++i, j += 3) {
3186 distances[i] = ISqrt(ISquaresumDiffU3(a + j, centroid));
3187 }
3188}

◆ ICopy() [1/4]

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

在文件 i_blas.h233 行定义.

233 {
234 int i;
235 for (i = 0; i < m; i++) {
236 ICopy<T, S>(src[i], dst[i], n);
237 }
238}

◆ ICopy() [2/4]

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

在文件 i_blas.h216 行定义.

216 {
217 int i;
218 for (i = 0; i < m; i++) {
219 ICopy<T>(src[i], dst[i], n);
220 }
221}

◆ ICopy() [3/4]

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

在文件 i_blas.h225 行定义.

225 {
226 int i;
227 for (i = 0; i < n; ++i) {
228 dst[i] = (S)(src[i]);
229 }
230}

◆ ICopy() [4/4]

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

在文件 i_blas.h27 行定义.

27 {
28 memcpy(dst, src, n * sizeof(T));
29}

◆ ICopy1()

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

在文件 i_blas.h31 行定义.

31 {
32 dst[0] = src[0];
33}

◆ ICopy10()

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

在文件 i_blas.h103 行定义.

103 {
104 dst[0] = src[0];
105 dst[1] = src[1];
106 dst[2] = src[2];
107 dst[3] = src[3];
108 dst[4] = src[4];
109 dst[5] = src[5];
110 dst[6] = src[6];
111 dst[7] = src[7];
112 dst[8] = src[8];
113 dst[9] = src[9];
114}

◆ ICopy11()

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

在文件 i_blas.h116 行定义.

116 {
117 dst[0] = src[0];
118 dst[1] = src[1];
119 dst[2] = src[2];
120 dst[3] = src[3];
121 dst[4] = src[4];
122 dst[5] = src[5];
123 dst[6] = src[6];
124 dst[7] = src[7];
125 dst[8] = src[8];
126 dst[9] = src[9];
127 dst[10] = src[10];
128}

◆ ICopy12()

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

在文件 i_blas.h130 行定义.

130 {
131 dst[0] = src[0];
132 dst[1] = src[1];
133 dst[2] = src[2];
134 dst[3] = src[3];
135 dst[4] = src[4];
136 dst[5] = src[5];
137 dst[6] = src[6];
138 dst[7] = src[7];
139 dst[8] = src[8];
140 dst[9] = src[9];
141 dst[10] = src[10];
142 dst[11] = src[11];
143}

◆ ICopy13()

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

在文件 i_blas.h145 行定义.

145 {
146 dst[0] = src[0];
147 dst[1] = src[1];
148 dst[2] = src[2];
149 dst[3] = src[3];
150 dst[4] = src[4];
151 dst[5] = src[5];
152 dst[6] = src[6];
153 dst[7] = src[7];
154 dst[8] = src[8];
155 dst[9] = src[9];
156 dst[10] = src[10];
157 dst[11] = src[11];
158 dst[12] = src[12];
159}

◆ ICopy14()

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

在文件 i_blas.h161 行定义.

161 {
162 dst[0] = src[0];
163 dst[1] = src[1];
164 dst[2] = src[2];
165 dst[3] = src[3];
166 dst[4] = src[4];
167 dst[5] = src[5];
168 dst[6] = src[6];
169 dst[7] = src[7];
170 dst[8] = src[8];
171 dst[9] = src[9];
172 dst[10] = src[10];
173 dst[11] = src[11];
174 dst[12] = src[12];
175 dst[13] = src[13];
176}

◆ ICopy15()

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

在文件 i_blas.h178 行定义.

178 {
179 dst[0] = src[0];
180 dst[1] = src[1];
181 dst[2] = src[2];
182 dst[3] = src[3];
183 dst[4] = src[4];
184 dst[5] = src[5];
185 dst[6] = src[6];
186 dst[7] = src[7];
187 dst[8] = src[8];
188 dst[9] = src[9];
189 dst[10] = src[10];
190 dst[11] = src[11];
191 dst[12] = src[12];
192 dst[13] = src[13];
193 dst[14] = src[14];
194}

◆ ICopy16()

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

在文件 i_blas.h196 行定义.

196 {
197 dst[0] = src[0];
198 dst[1] = src[1];
199 dst[2] = src[2];
200 dst[3] = src[3];
201 dst[4] = src[4];
202 dst[5] = src[5];
203 dst[6] = src[6];
204 dst[7] = src[7];
205 dst[8] = src[8];
206 dst[9] = src[9];
207 dst[10] = src[10];
208 dst[11] = src[11];
209 dst[12] = src[12];
210 dst[13] = src[13];
211 dst[14] = src[14];
212 dst[15] = src[15];
213}

◆ ICopy2()

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

在文件 i_blas.h35 行定义.

35 {
36 dst[0] = src[0];
37 dst[1] = src[1];
38}

◆ ICopy3()

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

在文件 i_blas.h40 行定义.

40 {
41 dst[0] = src[0];
42 dst[1] = src[1];
43 dst[2] = src[2];
44}

◆ ICopy4()

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

在文件 i_blas.h46 行定义.

46 {
47 dst[0] = src[0];
48 dst[1] = src[1];
49 dst[2] = src[2];
50 dst[3] = src[3];
51}

◆ ICopy5()

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

在文件 i_blas.h53 行定义.

53 {
54 dst[0] = src[0];
55 dst[1] = src[1];
56 dst[2] = src[2];
57 dst[3] = src[3];
58 dst[4] = src[4];
59}

◆ ICopy6()

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

在文件 i_blas.h61 行定义.

61 {
62 dst[0] = src[0];
63 dst[1] = src[1];
64 dst[2] = src[2];
65 dst[3] = src[3];
66 dst[4] = src[4];
67 dst[5] = src[5];
68}

◆ ICopy7()

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

在文件 i_blas.h70 行定义.

70 {
71 dst[0] = src[0];
72 dst[1] = src[1];
73 dst[2] = src[2];
74 dst[3] = src[3];
75 dst[4] = src[4];
76 dst[5] = src[5];
77 dst[6] = src[6];
78}

◆ ICopy8()

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

在文件 i_blas.h80 行定义.

80 {
81 dst[0] = src[0];
82 dst[1] = src[1];
83 dst[2] = src[2];
84 dst[3] = src[3];
85 dst[4] = src[4];
86 dst[5] = src[5];
87 dst[6] = src[6];
88 dst[7] = src[7];
89}

◆ ICopy9()

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

在文件 i_blas.h91 行定义.

91 {
92 dst[0] = src[0];
93 dst[1] = src[1];
94 dst[2] = src[2];
95 dst[3] = src[3];
96 dst[4] = src[4];
97 dst[5] = src[5];
98 dst[6] = src[6];
99 dst[7] = src[7];
100 dst[8] = src[8];
101}

◆ ICos() [1/2]

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

在文件 i_basic.h217 行定义.

217{ return cos(alpha); }

◆ ICos() [2/2]

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

在文件 i_basic.h216 行定义.

216{ return cosf(alpha); }

◆ ICross() [1/2]

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

在文件 i_blas.h3718 行定义.

3718 {
3719 xxy[0] = x[1] * y[2] - x[2] * y[1];
3720 xxy[1] = x[2] * y[0] - x[0] * y[2];
3721 xxy[2] = x[0] * y[1] - x[1] * y[0];
3722}

◆ ICross() [2/2]

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

在文件 i_blas.h3919 行定义.

3919 {
3920 ISubdeterminants3x4(x, y, z, xxyxz);
3921 xxyxz[0] = -xxyxz[0];
3922 xxyxz[2] = -xxyxz[2];
3923}
void ISubdeterminants3x4(const double x[4], const double y[4], const double z[4], double sd[4])
Definition i_blas.h:3869

◆ ICub() [1/6]

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

在文件 i_basic.h118 行定义.

118 {
119 return (static_cast<int>(a) * static_cast<int>(a) * static_cast<int>(a));
120}

◆ ICub() [2/6]

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

在文件 i_basic.h117 行定义.

117{ return (a * a * a); }

◆ ICub() [3/6]

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

在文件 i_basic.h114 行定义.

114{ return (a * a * a); }

◆ ICub() [4/6]

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

在文件 i_basic.h115 行定义.

115{ return (a * a * a); }

◆ ICub() [5/6]

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

在文件 i_basic.h121 行定义.

121 {
122 return (static_cast<int>(a) * static_cast<int>(a) * static_cast<int>(a));
123}

◆ ICub() [6/6]

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

在文件 i_basic.h116 行定义.

116{ return (a * a * a); }

◆ IDegreeToRadians() [1/2]

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

在文件 i_basic.h269 行定义.

269 {
271}

◆ IDegreeToRadians() [2/2]

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

在文件 i_basic.h266 行定义.

266 {
268}

◆ IDeterminant2x2() [1/3]

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

在文件 i_blas.h3811 行定义.

3811 {
3812 return (A[0] * A[3] - A[1] * A[2]);
3813}

◆ IDeterminant2x2() [2/3]

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

在文件 i_blas.h3814 行定义.

3814 {
3815 return (A[0] * A[3] - A[1] * A[2]);
3816}

◆ IDeterminant2x2() [3/3]

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

在文件 i_blas.h3817 行定义.

3817 {
3818 return (A[0] * A[3] - A[1] * A[2]);
3819}

◆ IDeterminant3x3() [1/3]

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

在文件 i_blas.h3822 行定义.

3822 {
3823 double r0_x_r1[3];
3824 ICross(A, A + 3, r0_x_r1);
3825 return (IDot3(r0_x_r1, A + 6));
3826}
void ICross(const T x[3], const T y[3], T xxy[3])
Definition i_blas.h:3718

◆ IDeterminant3x3() [2/3]

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

在文件 i_blas.h3827 行定义.

3827 {
3828 float r0_x_r1[3];
3829 ICross(A, A + 3, r0_x_r1);
3830 return (IDot3(r0_x_r1, A + 6));
3831}

◆ IDeterminant3x3() [3/3]

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

在文件 i_blas.h3832 行定义.

3832 {
3833 int r0_x_r1[3];
3834 ICross(A, A + 3, r0_x_r1);
3835 return (IDot3(r0_x_r1, A + 6));
3836}

◆ IDeterminant4x4() [1/3]

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

在文件 i_blas.h3898 行定义.

3898 {
3899 double sd[4];
3900 ISubdeterminants3x4(A, A + 4, A + 8, sd);
3901 return -(A[12] * sd[0]) + (A[13] * sd[1]) - (A[14] * sd[2]) + (A[15] * sd[3]);
3902}

◆ IDeterminant4x4() [2/3]

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

在文件 i_blas.h3903 行定义.

3903 {
3904 float sd[4];
3905 ISubdeterminants3x4(A, A + 4, A + 8, sd);
3906 return -(A[12] * sd[0]) + (A[13] * sd[1]) - (A[14] * sd[2]) + (A[15] * sd[3]);
3907}

◆ IDeterminant4x4() [3/3]

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

在文件 i_blas.h3908 行定义.

3908 {
3909 int sd[4];
3910 ISubdeterminants3x4(A, A + 4, A + 8, sd);
3911 return -(A[12] * sd[0]) + (A[13] * sd[1]) - (A[14] * sd[2]) + (A[15] * sd[3]);
3912}

◆ IDiv() [1/8]

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

在文件 i_basic.h56 行定义.

56{ return ((b != 0.0) ? (a / b) : 1.0); }

◆ IDiv() [2/8]

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

在文件 i_basic.h57 行定义.

57{ return ((b != 0) ? (a / b) : 1.0); }

◆ IDiv() [3/8]

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

在文件 i_basic.h58 行定义.

58 {
59 double result = 1.0;
60 if (b != 0) {
61 result = a / b;
62 }
63 return result;
64}

◆ IDiv() [4/8]

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

在文件 i_basic.h35 行定义.

35{ return ((b != 0.f) ? (a / b) : 1.0f); }

◆ IDiv() [5/8]

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

在文件 i_basic.h36 行定义.

36 {
37 return ((b != 0) ? (a / static_cast<float>(b)) : 1.0f);
38}

◆ IDiv() [6/8]

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

在文件 i_basic.h39 行定义.

39 {
40 float result = 1.0f;
41 if (b != 0) {
42 result = a / static_cast<float>(b);
43 }
44 return result;
45}

◆ IDiv() [7/8]

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

在文件 i_basic.h46 行定义.

46 {
47 return ((b != 0) ? (static_cast<double>(a) / b) : 1.0);
48}

◆ IDiv() [8/8]

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

在文件 i_basic.h49 行定义.

49 {
50 double result = 1.0;
51 if (b != 0) {
52 result = static_cast<double>(a) / b;
53 }
54 return result;
55}

◆ IDot()

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

在文件 i_blas.h2244 行定义.

2244 {
2245 T acc = static_cast<T>(0.0);
2246 for (int i = 0; i < n; ++i) {
2247 acc += x[i] * y[i];
2248 }
2249 return acc;
2250}

◆ IDot1()

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

在文件 i_blas.h2252 行定义.

2252 {
2253 return (x[0] * y[0]);
2254}

◆ IDot10()

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

在文件 i_blas.h2292 行定义.

2292 {
2293 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2294 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9]);
2295}

◆ IDot11()

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

在文件 i_blas.h2297 行定义.

2297 {
2298 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2299 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9] +
2300 x[10] * y[10]);
2301}

◆ IDot12()

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

在文件 i_blas.h2303 行定义.

2303 {
2304 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2305 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9] +
2306 x[10] * y[10] + x[11] * y[11]);
2307}

◆ IDot13()

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

在文件 i_blas.h2309 行定义.

2309 {
2310 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2311 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9] +
2312 x[10] * y[10] + x[11] * y[11] + x[12] * y[12]);
2313}

◆ IDot14()

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

在文件 i_blas.h2315 行定义.

2315 {
2316 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2317 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9] +
2318 x[10] * y[10] + x[11] * y[11] + x[12] * y[12] + x[13] * y[13]);
2319}

◆ IDot15()

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

在文件 i_blas.h2321 行定义.

2321 {
2322 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2323 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9] +
2324 x[10] * y[10] + x[11] * y[11] + x[12] * y[12] + x[13] * y[13] +
2325 x[14] * y[14]);
2326}

◆ IDot16()

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

在文件 i_blas.h2328 行定义.

2328 {
2329 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2330 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8] + x[9] * y[9] +
2331 x[10] * y[10] + x[11] * y[11] + x[12] * y[12] + x[13] * y[13] +
2332 x[14] * y[14] + x[15] * y[15]);
2333}

◆ IDot2()

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

在文件 i_blas.h2256 行定义.

2256 {
2257 return (x[0] * y[0] + x[1] * y[1]);
2258}

◆ IDot3()

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

在文件 i_blas.h2260 行定义.

2260 {
2261 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2]);
2262}

◆ IDot4()

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

在文件 i_blas.h2264 行定义.

2264 {
2265 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3]);
2266}

◆ IDot5()

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

在文件 i_blas.h2268 行定义.

2268 {
2269 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4]);
2270}

◆ IDot6()

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

在文件 i_blas.h2272 行定义.

2272 {
2273 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2274 x[5] * y[5]);
2275}

◆ IDot7()

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

在文件 i_blas.h2277 行定义.

2277 {
2278 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2279 x[5] * y[5] + x[6] * y[6]);
2280}

◆ IDot8()

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

在文件 i_blas.h2282 行定义.

2282 {
2283 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2284 x[5] * y[5] + x[6] * y[6] + x[7] * y[7]);
2285}

◆ IDot9()

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

在文件 i_blas.h2287 行定义.

2287 {
2288 return (x[0] * y[0] + x[1] * y[1] + x[2] * y[2] + x[3] * y[3] + x[4] * y[4] +
2289 x[5] * y[5] + x[6] * y[6] + x[7] * y[7] + x[8] * y[8]);
2290}

◆ IDownsampleVoxelGridXY()

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

在文件 i_struct_s.h1064 行定义.

1065 {
1066 if (!src.Initialized()) {
1067 return (false);
1068 } else if (dsf_dim_x == 0 && dsf_dim_y == 0) {
1069 *dst = src;
1070 return (true);
1071 } else {
1072 if (&src == dst) {
1073 return (false); // not allowed to downsample a voxel grid from itself
1074 }
1075 }
1076
1077 dst->CleanUp(); // perform CleanUp first
1078
1079 // # of voxels of the src voxel grid
1080 unsigned int nr_voxel_x_src = src.NrVoxelX();
1081 unsigned int nr_voxel_y_src = src.NrVoxelY();
1082 unsigned int nr_voxel_z_src = src.NrVoxelZ();
1083
1084 assert(nr_voxel_z_src == 1);
1085
1086 // scale factors
1087 unsigned int sf_x = (unsigned int)IPow((unsigned int)2, dsf_dim_x);
1088 unsigned int sf_y = (unsigned int)IPow((unsigned int)2, dsf_dim_y);
1089
1090 // compute the # of voxels for the new scale
1091 unsigned int nr_voxel_x_dst = nr_voxel_x_src / sf_x;
1092 unsigned int nr_voxel_y_dst = nr_voxel_y_src / sf_y;
1093 unsigned int nr_voxel_z_dst = nr_voxel_z_src;
1094
1095 if (!nr_voxel_x_dst || !nr_voxel_y_dst || !nr_voxel_z_dst) {
1096 return (false); // do not continue
1097 }
1098
1099 unsigned int nr_res_voxel_x_dst = (nr_voxel_x_src % sf_x);
1100 unsigned int nr_res_voxel_y_dst = (nr_voxel_y_src % sf_y);
1101
1102 T voxel_width_x_src = 0;
1103 T voxel_width_y_src = 0;
1104 T voxel_width_z_src = 0;
1105 T dim_min_x_src = 0;
1106 T dim_max_x_src = 0;
1107 T dim_min_y_src = 0;
1108 T dim_max_y_src = 0;
1109 T dim_min_z_src = 0;
1110 T dim_max_z_src = 0;
1111
1112 // the dimension of the voxels in the src voxel grid
1113 src.GetVoxelDimension(&voxel_width_x_src, &voxel_width_y_src,
1114 &voxel_width_z_src);
1115
1116 src.GetGridDimension(&dim_min_x_src, &dim_max_x_src, &dim_min_y_src,
1117 &dim_max_y_src, &dim_min_z_src, &dim_max_z_src);
1118
1119 // new voxel dimensions after downsampling the 3D grid
1120 T voxel_width_x_dst = (sf_x * voxel_width_x_src);
1121 T voxel_width_y_dst = (sf_y * voxel_width_y_src);
1122 T voxel_width_z_dst = voxel_width_z_src;
1123
1124 // new grid dimensions after downsampling the 3D grid
1125 T dim_x_dst[2], dim_y_dst[2], dim_z_dst[2];
1126
1127 dim_x_dst[0] = dim_min_x_src;
1128 dim_y_dst[0] = dim_min_y_src;
1129 dim_z_dst[0] = dim_min_z_src;
1130
1131 dim_x_dst[1] = (0 == nr_res_voxel_x_dst)
1132 ? dim_max_x_src
1133 : (voxel_width_x_dst * nr_voxel_x_dst + dim_x_dst[0]);
1134 dim_y_dst[1] = (0 == nr_res_voxel_y_dst)
1135 ? dim_max_y_src
1136 : (voxel_width_y_dst * nr_voxel_y_dst + dim_y_dst[0]);
1137 dim_z_dst[1] = dim_max_z_src;
1138
1139 // Set dst
1140 dst->SetNrPoints(src.NrPoints());
1142 dst->SetVoxelDimension(voxel_width_x_dst, voxel_width_y_dst,
1143 voxel_width_z_dst);
1144 dst->SetGridDimension(dim_x_dst[0], dim_x_dst[1], dim_y_dst[0], dim_y_dst[1],
1145 dim_z_dst[0], dim_z_dst[1]);
1146 dst->SetNrVoxel(nr_voxel_x_dst, nr_voxel_y_dst, nr_voxel_z_dst);
1147 dst->SetPointCloudsData(src.const_data());
1148
1149 unsigned int i, j, r, c, rs, cs, rspi, n = 0;
1150
1151 T vy, vz = dim_z_dst[0];
1152 std::vector<T> vxs(nr_voxel_x_dst);
1153
1154 vxs[0] = dim_x_dst[0];
1155
1156 for (i = 1; i < nr_voxel_x_dst; i++) {
1157 vxs[i] = vxs[i - 1] + voxel_width_x_dst;
1158 }
1159
1160 std::vector<Voxel<T>> voxels(nr_voxel_y_dst * nr_voxel_x_dst);
1161
1162 for (r = 0; r < nr_voxel_y_dst; r++) {
1163 rs = (r * sf_y);
1164 vy = dim_y_dst[0] + (r * voxel_width_y_dst);
1165
1166 for (c = 0; c < nr_voxel_x_dst; c++) {
1167 cs = (c * sf_x);
1168 voxels[n].init(vxs[c], vy, vz, voxel_width_x_dst, voxel_width_y_dst,
1169 voxel_width_z_dst, static_cast<int>(c),
1170 static_cast<int>(r), static_cast<int>(0));
1171 // collect samples from its lower scale:
1172 for (i = 0; i < sf_y; ++i) {
1173 rspi = rs + i;
1174 for (j = 0; j < sf_x; ++j) {
1175 IPushBackVectors(src(rspi, cs + j).indices_, &voxels[n].indices_);
1176 }
1177 }
1178 // increase voxel index by 1
1179 n++;
1180 }
1181 }
1182 dst->SetVoxels(voxels);
1183 dst->SetInitialized(true);
1184 return (true);
1185}
void SetGridDimension(T dim_min_x, T dim_max_x, T dim_min_y, T dim_max_y, T dim_min_z, T dim_max_z)
Definition i_struct_s.h:392
bool GetVoxelDimension(T *voxel_width_x, T *voxel_width_y, T *voxel_width_z) const
Definition i_struct_s.h:402
void SetVoxelDimension(T voxel_width_x, T voxel_width_y, T voxel_width_z)
Definition i_struct_s.h:414
void SetNrPointElement(unsigned int nr_point_element)
Definition i_struct_s.h:422
void SetNrPoints(unsigned int nr_points)
Definition i_struct_s.h:420
bool GetGridDimension(T *dim_min_x, T *dim_max_x, T *dim_min_y, T *dim_max_y, T *dim_min_z, T *dim_max_z) const
Definition i_struct_s.h:376
void SetVoxels(const std::vector< Voxel< T > > &voxels)
Definition i_struct_s.h:372
void SetNrVoxel(unsigned int nr_voxel_x, unsigned int nr_voxel_y, unsigned int nr_voxel_z)
Definition i_struct_s.h:426
float IPow(float a, float b)
Definition i_basic.h:142

◆ IEigSymmetric2x2Closed()

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

在文件 i_util.h29 行定义.

29 {
30 if (A == nullptr) {
31 return;
32 }
33 Eigen::Matrix<T, 2, 2> a;
34 a << A[0], A[1], A[2], A[3];
35 Eigen::SelfAdjointEigenSolver<Eigen::Matrix<T, 2, 2>> es(a);
36 if (es.info() != Eigen::Success) {
37 return;
38 }
39
40 Eigen::Matrix<T, 2, 1> D = es.eigenvalues();
41 Eigen::Matrix<T, 2, 2> V = es.eigenvectors();
42 if (fabs(D(0, 0)) < fabs(D(1, 0))) {
43 std::swap(D(0, 0), D(1, 0));
44 std::swap(V(0, 0), V(0, 1));
45 std::swap(V(1, 0), V(1, 1));
46 }
47 EV[0] = D(0, 0);
48 EV[1] = D(1, 0);
49 Q[0] = V(0, 0);
50 Q[1] = V(0, 1);
51 Q[2] = V(1, 0);
52 Q[3] = V(1, 1);
53}

◆ IEigSymmetric3x3Closed()

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

在文件 i_util.h56 行定义.

56 {
57 if (A == nullptr) {
58 return;
59 }
60 Eigen::Matrix<T, 3, 3> a;
61 a << A[0], A[1], A[2], A[3], A[4], A[5], A[6], A[7], A[8];
62 Eigen::SelfAdjointEigenSolver<Eigen::Matrix<T, 3, 3>> es(a);
63 if (es.info() != Eigen::Success) {
64 return;
65 }
66 Eigen::Matrix<T, 3, 1> D = es.eigenvalues();
67 Eigen::Matrix<T, 3, 3> V = es.eigenvectors();
68 if (fabs(D(1, 0)) < fabs(D(2, 0))) {
69 std::swap(D(1, 0), D(2, 0));
70 for (int i = 0; i < 3; ++i) {
71 std::swap(V(i, 1), V(i, 2));
72 }
73 }
74 if (fabs(D(0, 0)) < fabs(D(1, 0))) {
75 std::swap(D(0, 0), D(1, 0));
76 for (int i = 0; i < 3; ++i) {
77 std::swap(V(i, 0), V(i, 1));
78 }
79 }
80 if (fabs(D(1, 0)) < fabs(D(2, 0))) {
81 std::swap(D(1, 0), D(2, 0));
82 for (int i = 0; i < 3; ++i) {
83 std::swap(V(i, 1), V(i, 2));
84 }
85 }
86
87 EV[0] = D(0, 0);
88 EV[1] = D(1, 0);
89 EV[2] = D(2, 0);
90 Q[0] = V(0, 0);
91 Q[1] = V(0, 1);
92 Q[2] = V(0, 2);
93 Q[3] = V(1, 0);
94 Q[4] = V(1, 1);
95 Q[5] = V(1, 2);
96 Q[6] = V(2, 0);
97 Q[7] = V(2, 1);
98 Q[8] = V(2, 2);
99}

◆ IExp() [1/4]

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

在文件 i_basic.h139 行定义.

139{ return exp(x); }

◆ IExp() [2/4]

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

在文件 i_basic.h136 行定义.

136{ return (expf(x)); }

◆ IExp() [3/4]

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

在文件 i_basic.h137 行定义.

137{ return exp(static_cast<double>(x)); }

◆ IExp() [4/4]

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

在文件 i_basic.h138 行定义.

138{ return exp(static_cast<double>(x)); }

◆ IEye()

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

在文件 i_blas.h3756 行定义.

3756 {
3757 int in = 0;
3758 IZero(A, n * n);
3759 for (int i = 0; i < n; ++i, in += n) {
3760 A[in + i] = static_cast<T>(1.0);
3761 }
3762}
void IZero(T *a, int n)
Definition i_blas.h:320

◆ IEye2x2()

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

在文件 i_blas.h3764 行定义.

3764 {
3765 A[0] = A[3] = static_cast<T>(1.0);
3766 A[1] = A[2] = static_cast<T>(0.0);
3767}

◆ IEye3x3()

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

在文件 i_blas.h3769 行定义.

3769 {
3770 A[0] = A[4] = A[8] = static_cast<T>(1.0);
3771 A[1] = A[2] = A[3] = A[5] = A[6] = A[7] = static_cast<T>(0.0);
3772}

◆ IEye4x4()

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

在文件 i_blas.h3774 行定义.

3774 {
3775 A[0] = A[5] = A[10] = A[15] = static_cast<T>(1.0);
3776 A[1] = A[2] = A[3] = A[4] = A[6] = A[7] = A[8] = A[9] = A[11] = A[12] =
3777 A[13] = A[14] = static_cast<T>(0.0);
3778}

◆ IFill()

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

在文件 i_blas.h242 行定义.

242 {
243 for (int i = 0; i < n; i++) {
244 a[i] = val;
245 }
246}

◆ IFill1()

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

在文件 i_blas.h248 行定义.

248 {
249 a[0] = val;
250}

◆ IFill10()

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

在文件 i_blas.h284 行定义.

284 {
285 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = val;
286}

◆ IFill11()

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

在文件 i_blas.h288 行定义.

288 {
289 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
290 val;
291}

◆ IFill12()

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

在文件 i_blas.h293 行定义.

293 {
294 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
295 a[11] = val;
296}

◆ IFill13()

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

在文件 i_blas.h298 行定义.

298 {
299 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
300 a[11] = a[12] = val;
301}

◆ IFill14()

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

在文件 i_blas.h303 行定义.

303 {
304 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
305 a[11] = a[12] = a[13] = val;
306}

◆ IFill15()

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

在文件 i_blas.h308 行定义.

308 {
309 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
310 a[11] = a[12] = a[13] = a[14] = val;
311}

◆ IFill16()

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

在文件 i_blas.h313 行定义.

313 {
314 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
315 a[11] = a[12] = a[13] = a[14] = a[15] = val;
316}

◆ IFill2()

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

在文件 i_blas.h252 行定义.

252 {
253 a[0] = a[1] = val;
254}

◆ IFill3()

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

在文件 i_blas.h256 行定义.

256 {
257 a[0] = a[1] = a[2] = val;
258}

◆ IFill4()

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

在文件 i_blas.h260 行定义.

260 {
261 a[0] = a[1] = a[2] = a[3] = val;
262}

◆ IFill5()

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

在文件 i_blas.h264 行定义.

264 {
265 a[0] = a[1] = a[2] = a[3] = a[4] = val;
266}

◆ IFill6()

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

在文件 i_blas.h268 行定义.

268 {
269 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = val;
270}

◆ IFill7()

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

在文件 i_blas.h272 行定义.

272 {
273 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = val;
274}

◆ IFill8()

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

在文件 i_blas.h276 行定义.

276 {
277 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = val;
278}

◆ IFill9()

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

在文件 i_blas.h280 行定义.

280 {
281 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = val;
282}

◆ IFree()

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

在文件 i_alloc.h52 行定义.

52 {
53 if (mem != nullptr && *mem != nullptr) {
54 delete[] * mem;
55 *mem = nullptr;
56 }
57}

◆ IFree2()

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

在文件 i_alloc.h79 行定义.

79 {
80 if (A != nullptr && *A != nullptr) {
81 delete[](*A)[0];
82 delete[] * A;
83 *A = nullptr;
84 }
85}

◆ IFreeAligned()

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

在文件 i_alloc.h142 行定义.

142 {
143 if (mem != nullptr && *mem != nullptr) {
144 delete[](reinterpret_cast<char **>(*mem))[-1];
145 *mem = nullptr;
146 }
147}

◆ IGaussian2D() [1/2]

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

在文件 i_basic.h538 行定义.

538 {
539 int r, c, i = 0;
540 const double cen = (static_cast<double>(n - 1)) / 2;
541 const double nf =
542 IDiv(0.5, (sigma * sigma)); // normalization factor = 1/(2sigma*sigma)
543 double dr, drsqr, dc, dcsqr, v, ksum = 0.0;
544 // pre-compute filter
545 for (r = 0; r < n; ++r) {
546 dr = static_cast<double>(r) - cen;
547 drsqr = ISqr(dr);
548 for (c = 0; c < n; ++c) {
549 dc = static_cast<double>(c) - cen;
550 dcsqr = ISqr(dc);
551 v = IExp(-(drsqr + dcsqr) * nf);
552 ksum += v;
553 kernel[i++] = v;
554 }
555 }
556 // normalize the kernel
557 v = IDiv(1.0, ksum);
558 for (i = 0; i < n * n; ++i) {
559 kernel[i] *= v;
560 }
561}

◆ IGaussian2D() [2/2]

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

在文件 i_basic.h513 行定义.

513 {
514 int r, c, i = 0;
515 const float cen = (static_cast<float>(n - 1)) / 2;
516 const float nf =
517 IDiv(0.5f, (sigma * sigma)); // normalization factor = 1/(2sigma*sigma)
518 float dr, drsqr, dc, dcsqr, v, ksum = 0.f;
519 // pre-compute filter
520 for (r = 0; r < n; ++r) {
521 dr = static_cast<float>(r) - cen;
522 drsqr = ISqr(dr);
523 for (c = 0; c < n; ++c) {
524 dc = static_cast<float>(c) - cen;
525 dcsqr = ISqr(dc);
526 v = IExp(-(drsqr + dcsqr) * nf);
527 ksum += v;
528 kernel[i++] = v;
529 }
530 }
531 // normalize the kernel
532 v = IDiv(1.0f, ksum);
533 for (i = 0; i < n * n; ++i) {
534 kernel[i] *= v;
535 }
536}

◆ IGetPointcloudsDimWBound()

template<typename T >
void apollo::perception::algorithm::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

在文件 i_util.h27 行定义.

33 {
34 int i;
35 T x, y, z;
36
37 *dim_min_x = *dim_min_y = *dim_min_z = std::numeric_limits<T>::max() / 2;
38 *dim_max_x = *dim_max_y = *dim_max_z = -(std::numeric_limits<T>::max() / 2);
39 const T *cptr = threeds + start_offset;
40 for (i = 0; i < n; i++) {
41 x = cptr[0];
42 y = cptr[1];
43 z = cptr[2];
44 cptr += element_size;
45
46 if (x < bound_min_x || x > bound_max_x || y < bound_min_y ||
47 y > bound_max_y || z < bound_min_z || z > bound_max_z) {
48 continue;
49 } else {
50 *dim_min_x = IMin(dim_min_x, x);
51 *dim_max_x = IMax(dim_max_x, x);
52 *dim_min_y = IMin(dim_min_y, y);
53 *dim_max_y = IMax(dim_max_y, y);
54 *dim_min_z = IMin(dim_min_z, z);
55 *dim_max_z = IMax(dim_max_z, z);
56 }
57 }
58}

◆ IHamming()

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

在文件 i_basic.h275 行定义.

275 {
276 unsigned int distance = 0;
277 unsigned int val = a ^ b; // XOR
278 // Count the number of bits set
279 while (val != 0) {
280 // A bit is set, so increment the count and clear the bit
281 distance++;
282 val &= val - 1;
283 }
284 return distance; // Return the number of different bits
285}

◆ IHammingDiff()

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

在文件 i_blas.h2731 行定义.

2732 {
2733 unsigned int distance = 0;
2734 for (int i = 0; i < n; ++i) {
2735 distance += IHammingLut(x[i], y[i]);
2736 }
2737 return distance; // Return the number of differing bits
2738}
unsigned int IHammingLut(unsigned int a, unsigned int b)
Definition i_basic.h:287

◆ IHammingDiff16()

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

在文件 i_blas.h2768 行定义.

2769 {
2770 unsigned int distance = 0;
2771 distance += IHammingLut(x[0], y[0]);
2772 distance += IHammingLut(x[1], y[1]);
2773 distance += IHammingLut(x[2], y[2]);
2774 distance += IHammingLut(x[3], y[3]);
2775 distance += IHammingLut(x[4], y[4]);
2776 distance += IHammingLut(x[5], y[5]);
2777 distance += IHammingLut(x[6], y[6]);
2778 distance += IHammingLut(x[7], y[7]);
2779 distance += IHammingLut(x[8], y[8]);
2780 distance += IHammingLut(x[9], y[9]);
2781 distance += IHammingLut(x[10], y[10]);
2782 distance += IHammingLut(x[11], y[11]);
2783 distance += IHammingLut(x[12], y[12]);
2784 distance += IHammingLut(x[13], y[13]);
2785 distance += IHammingLut(x[14], y[14]);
2786 distance += IHammingLut(x[15], y[15]);
2787 return distance;
2788}

◆ IHammingDiff2()

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

在文件 i_blas.h2739 行定义.

2740 {
2741 unsigned int distance = 0;
2742 distance += IHammingLut(x[0], y[0]);
2743 distance += IHammingLut(x[1], y[1]);
2744 return distance;
2745}

◆ IHammingDiff4()

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

在文件 i_blas.h2746 行定义.

2747 {
2748 unsigned int distance = 0;
2749 distance += IHammingLut(x[0], y[0]);
2750 distance += IHammingLut(x[1], y[1]);
2751 distance += IHammingLut(x[2], y[2]);
2752 distance += IHammingLut(x[3], y[3]);
2753 return distance;
2754}

◆ IHammingDiff8()

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

在文件 i_blas.h2755 行定义.

2756 {
2757 unsigned int distance = 0;
2758 distance += IHammingLut(x[0], y[0]);
2759 distance += IHammingLut(x[1], y[1]);
2760 distance += IHammingLut(x[2], y[2]);
2761 distance += IHammingLut(x[3], y[3]);
2762 distance += IHammingLut(x[4], y[4]);
2763 distance += IHammingLut(x[5], y[5]);
2764 distance += IHammingLut(x[6], y[6]);
2765 distance += IHammingLut(x[7], y[7]);
2766 return distance;
2767}

◆ IHammingLut()

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

在文件 i_basic.h287 行定义.

287 {
288 unsigned int distance = 0;
289 unsigned int val = a ^ b; // XOR
290 unsigned char *p = (unsigned char *)&val;
291 // count the total # of "1s" in a xor b
292 distance = kIUByteBitCountLut[p[0]] + kIUByteBitCountLut[p[1]] +
293 kIUByteBitCountLut[p[2]] + kIUByteBitCountLut[p[3]];
294 return distance; // Return the number of different bits
295}

◆ IHomogeneousUnitize() [1/2]

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

在文件 i_blas.h3106 行定义.

3106 {
3107 IScale(x, y, n, IRec(x[n - 1]));
3108}
void IScale(T *x, int n, T sf)
Definition i_blas.h:1853

◆ IHomogeneousUnitize() [2/2]

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

在文件 i_blas.h3085 行定义.

3085 {
3086 IScale(x, n, IRec(x[n - 1]));
3087}

◆ IHomogeneousUnitize2() [1/2]

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

在文件 i_blas.h3110 行定义.

3110 {
3111 IScale2(x, y, IRec(x[1]));
3112}
void IScale2(T x[2], T sf)
Definition i_blas.h:1863

◆ IHomogeneousUnitize2() [2/2]

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

在文件 i_blas.h3089 行定义.

3089 {
3090 IScale2(x, IRec(x[1]));
3091}

◆ IHomogeneousUnitize3() [1/2]

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

在文件 i_blas.h3114 行定义.

3114 {
3115 IScale3(x, y, IRec(x[2]));
3116}
void IScale3(T x[3], T sf)
Definition i_blas.h:1868

◆ IHomogeneousUnitize3() [2/2]

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

在文件 i_blas.h3093 行定义.

3093 {
3094 IScale3(x, IRec(x[2]));
3095}

◆ IHomogeneousUnitize4() [1/2]

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

在文件 i_blas.h3118 行定义.

3118 {
3119 IScale4(x, y, IRec(x[3]));
3120}
void IScale4(T x[4], T sf)
Definition i_blas.h:1874

◆ IHomogeneousUnitize4() [2/2]

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

在文件 i_blas.h3097 行定义.

3097 {
3098 IScale4(x, IRec(x[3]));
3099}

◆ IHomogeneousUnitize9() [1/2]

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

在文件 i_blas.h3122 行定义.

3122 {
3123 IScale9(x, y, IRec(x[8]));
3124}
void IScale9(T x[9], T sf)
Definition i_blas.h:1919

◆ IHomogeneousUnitize9() [2/2]

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

在文件 i_blas.h3101 行定义.

3101 {
3102 IScale9(x, IRec(x[8]));
3103}

◆ IHomogenize()

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

在文件 i_blas.h3691 行定义.

3691 {
3692 for (int i = 0; i < n; ++i) {
3693 y[i] = x[i];
3694 }
3695 y[n] = static_cast<T>(1.0);
3696}

◆ IHomogenize1()

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

在文件 i_blas.h3698 行定义.

3698 {
3699 y[0] = x[0];
3700 y[1] = static_cast<T>(1.0);
3701}

◆ IHomogenize2()

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

在文件 i_blas.h3703 行定义.

3703 {
3704 y[0] = x[0];
3705 y[1] = x[1];
3706 y[2] = static_cast<T>(1.0);
3707}

◆ IHomogenize3()

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

在文件 i_blas.h3709 行定义.

3709 {
3710 y[0] = x[0];
3711 y[1] = x[1];
3712 y[2] = x[2];
3713 y[3] = static_cast<T>(1.0);
3714}

◆ IIndexedShuffle() [1/2]

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

在文件 i_sort.h80 行定义.

82 {
83 // pre-sort indices array into ascending order
84 if (is_sort_indices) {
85 IInsertionSort<int, ILess>(indices, nr_indexed_elements);
86 }
87 // move indexed elements to the left hand side of a
88 int j = IMin(n, nr_indexed_elements);
89 int m = IMin(n, nr_indexed_elements);
90 for (int i = 0; i < m; ++i) {
91 j = indices[i];
92 if (j != i) {
93 ISwap(a + i * element_size, a + j * element_size, element_size);
94 // swap indexed elements to the left
95 }
96 }
97}

◆ IIndexedShuffle() [2/2]

template<typename T >
void apollo::perception::algorithm::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

在文件 i_sort.h107 行定义.

109 {
110 // pre-sort indices array into ascending order
111 if (n <= 1) {
112 return;
113 }
114 if (is_sort_indices) {
115 IInsertionSort<int, ILess>(indices, nr_indexed_elements);
116 }
117 // move indexed elements to the left hand side of a
118 int j = IMin(n, nr_indexed_elements);
119 int m = IMin(n, nr_indexed_elements);
120 for (int i = 0; i < m; ++i) {
121 j = indices[i];
122 if (j != i) {
123 ISwap(a + i * element_size_a, a + j * element_size_a, element_size_a);
124 // swap indexed elements to the left
125 ISwap(b + i * element_size_b, b + j * element_size_b, element_size_b);
126 // swap indexed elements to the left
127 }
128 }
129}

◆ IInfinityNorm()

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

在文件 i_blas.h2892 行定义.

2892 {
2893 T infinity_norm = IAbsSum(A, n);
2894 T tmp;
2895 int i, ni = n;
2896 for (i = 1; i < m; ++i, ni += n) {
2897 tmp = IAbsSum(A + ni, n);
2898 if (infinity_norm < tmp) {
2899 infinity_norm = tmp;
2900 }
2901 }
2902 return infinity_norm;
2903}
T IAbsSum(const T *x, int n)
Definition i_blas.h:2423

◆ IInsertionSort()

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

在文件 i_sort.h58 行定义.

58 {
59 int i, j;
60 T tmp;
61 for (i = 1; i < n; i++) {
62 IMove(a[i], &tmp);
63 for (j = i; j > 0; j--) {
64 if (Compare(a[j - 1], tmp)) {
65 break;
66 }
67 IMove(a[j - 1], &a[j]);
68 }
69 IMove(tmp, &a[j]);
70 }
71}
void IMove(const T &a, T *b)
Definition i_basic.h:566

◆ IInterval()

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

在文件 i_basic.h334 行定义.

334 {
335 if (a <= min_val) {
336 return (min_val);
337 }
338 if (a >= max_val) {
339 return (max_val);
340 }
341 return (a);
342}

◆ IIntervalHalfopen()

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

在文件 i_basic.h345 行定义.

345 {
346 if (a <= min_val) {
347 return (min_val);
348 }
349 if (a >= max_val) {
350 return (max_val - 1);
351 }
352 return (a);
353}

◆ IInvert2x2() [1/3]

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

在文件 i_blas.h3926 行定义.

3926 {
3927 double d = IDeterminant2x2(A);
3928 double sf = IRec(d);
3929 Ai[0] = sf * (A[3]);
3930 Ai[1] = sf * (-A[1]);
3931 Ai[2] = sf * (-A[2]);
3932 Ai[3] = sf * (A[0]);
3933}
double IDeterminant2x2(const double A[4])
Definition i_blas.h:3811

◆ IInvert2x2() [2/3]

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

在文件 i_blas.h3935 行定义.

3935 {
3936 float d = IDeterminant2x2(A);
3937 float sf = IRec(d);
3938 Ai[0] = sf * (A[3]);
3939 Ai[1] = sf * (-A[1]);
3940 Ai[2] = sf * (-A[2]);
3941 Ai[3] = sf * (A[0]);
3942}

◆ IInvert2x2() [3/3]

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

在文件 i_blas.h3944 行定义.

3944 {
3945 int d = IDeterminant2x2(A);
3946 double sf = IRec(d);
3947 Ai[0] = sf * (A[3]);
3948 Ai[1] = sf * (-A[1]);
3949 Ai[2] = sf * (-A[2]);
3950 Ai[3] = sf * (A[0]);
3951}

◆ IInvert3x3() [1/3]

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

在文件 i_blas.h3989 行定义.

3989 {
3990 double sd0 = A[4] * A[8] - A[5] * A[7];
3991 double sd1 = A[5] * A[6] - A[3] * A[8];
3992 double sd2 = A[3] * A[7] - A[4] * A[6];
3993 double sd3 = A[2] * A[7] - A[1] * A[8];
3994 double sd4 = A[0] * A[8] - A[2] * A[6];
3995 double sd5 = A[1] * A[6] - A[0] * A[7];
3996 double sd6 = A[1] * A[5] - A[2] * A[4];
3997 double sd7 = A[2] * A[3] - A[0] * A[5];
3998 double sd8 = A[0] * A[4] - A[1] * A[3];
3999 double d = A[0] * sd0 + A[1] * sd1 + A[2] * sd2;
4000 double d_rec = IRec(d);
4001 Ai[0] = d_rec * sd0;
4002 Ai[1] = d_rec * sd3;
4003 Ai[2] = d_rec * sd6;
4004 Ai[3] = d_rec * sd1;
4005 Ai[4] = d_rec * sd4;
4006 Ai[5] = d_rec * sd7;
4007 Ai[6] = d_rec * sd2;
4008 Ai[7] = d_rec * sd5;
4009 Ai[8] = d_rec * sd8;
4010}

◆ IInvert3x3() [2/3]

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

在文件 i_blas.h4011 行定义.

4011 {
4012 float sd0 = A[4] * A[8] - A[5] * A[7];
4013 float sd1 = A[5] * A[6] - A[3] * A[8];
4014 float sd2 = A[3] * A[7] - A[4] * A[6];
4015 float sd3 = A[2] * A[7] - A[1] * A[8];
4016 float sd4 = A[0] * A[8] - A[2] * A[6];
4017 float sd5 = A[1] * A[6] - A[0] * A[7];
4018 float sd6 = A[1] * A[5] - A[2] * A[4];
4019 float sd7 = A[2] * A[3] - A[0] * A[5];
4020 float sd8 = A[0] * A[4] - A[1] * A[3];
4021 float d = A[0] * sd0 + A[1] * sd1 + A[2] * sd2;
4022 float d_rec = IRec(d);
4023 Ai[0] = d_rec * sd0;
4024 Ai[1] = d_rec * sd3;
4025 Ai[2] = d_rec * sd6;
4026 Ai[3] = d_rec * sd1;
4027 Ai[4] = d_rec * sd4;
4028 Ai[5] = d_rec * sd7;
4029 Ai[6] = d_rec * sd2;
4030 Ai[7] = d_rec * sd5;
4031 Ai[8] = d_rec * sd8;
4032}

◆ IInvert3x3() [3/3]

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

在文件 i_blas.h4033 行定义.

4033 {
4034 // subdeterminants:
4035 int sd0 = A[4] * A[8] - A[5] * A[7];
4036 int sd1 = A[5] * A[6] - A[3] * A[8];
4037 int sd2 = A[3] * A[7] - A[4] * A[6];
4038 int sd3 = A[2] * A[7] - A[1] * A[8];
4039 int sd4 = A[0] * A[8] - A[2] * A[6];
4040 int sd5 = A[1] * A[6] - A[0] * A[7];
4041 int sd6 = A[1] * A[5] - A[2] * A[4];
4042 int sd7 = A[2] * A[3] - A[0] * A[5];
4043 int sd8 = A[0] * A[4] - A[1] * A[3];
4044 int d = A[0] * sd0 + A[1] * sd1 + A[2] * sd2;
4045 double d_rec = IRec(d);
4046 Ai[0] = d_rec * sd0;
4047 Ai[1] = d_rec * sd3;
4048 Ai[2] = d_rec * sd6;
4049 Ai[3] = d_rec * sd1;
4050 Ai[4] = d_rec * sd4;
4051 Ai[5] = d_rec * sd7;
4052 Ai[6] = d_rec * sd2;
4053 Ai[7] = d_rec * sd5;
4054 Ai[8] = d_rec * sd8;
4055}

◆ IInvert3x3UpperTriangular() [1/3]

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

在文件 i_blas.h4134 行定义.

4134 {
4135 double A4A8 = A[4] * A[8];
4136 double A0rec = IRec(A[0]);
4137 Ai[0] = A0rec;
4138 Ai[1] = -IDiv(A[1], A[0] * A[4]);
4139 Ai[2] = (IDiv(A[1] * A[5], A4A8) - IDiv(A[2], A[8])) * A0rec;
4140 Ai[3] = 0;
4141 Ai[4] = IRec(A[4]);
4142 Ai[5] = -IDiv(A[5], A4A8);
4143 Ai[6] = 0;
4144 Ai[7] = 0;
4145 Ai[8] = IRec(A[8]);
4146}

◆ IInvert3x3UpperTriangular() [2/3]

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

在文件 i_blas.h4147 行定义.

4147 {
4148 float A4A8 = A[4] * A[8];
4149 float A0rec = IRec(A[0]);
4150 Ai[0] = A0rec;
4151 Ai[1] = -IDiv(A[1], A[0] * A[4]);
4152 Ai[2] = (IDiv(A[1] * A[5], A4A8) - IDiv(A[2], A[8])) * A0rec;
4153 Ai[3] = 0;
4154 Ai[4] = IRec(A[4]);
4155 Ai[5] = -IDiv(A[5], A4A8);
4156 Ai[6] = 0;
4157 Ai[7] = 0;
4158 Ai[8] = IRec(A[8]);
4159}

◆ IInvert3x3UpperTriangular() [3/3]

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

在文件 i_blas.h4160 行定义.

4160 {
4161 double A4A8 = static_cast<double>(A[4] * A[8]);
4162 double A0rec = IRec(A[0]);
4163 Ai[0] = A0rec;
4164 Ai[1] = -IDiv(static_cast<double>(A[1]), static_cast<double>(A[0] * A[4]));
4165 Ai[2] =
4166 (IDiv(static_cast<double>(A[1] * A[5]), A4A8) - IDiv(A[2], A[8])) * A0rec;
4167 Ai[3] = 0;
4168 Ai[4] = IRec(A[4]);
4169 Ai[5] = -IDiv(static_cast<double>(A[5]), A4A8);
4170 Ai[6] = 0;
4171 Ai[7] = 0;
4172 Ai[8] = IRec(A[8]);
4173}

◆ IL2Norm() [1/4]

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

在文件 i_blas.h2798 行定义.

2798 {
2799 return (ISqrt(ISquaresum(x, n)));
2800}
T ISquaresum(const T *x, int n)
Definition i_blas.h:2520

◆ IL2Norm() [2/4]

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

在文件 i_blas.h2795 行定义.

2795 {
2796 return (ISqrt(ISquaresum(x, n)));
2797}

◆ IL2Norm() [3/4]

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

在文件 i_blas.h2794 行定义.

2794{ return (ISqrt(ISquaresum(x, n))); }

◆ IL2Norm() [4/4]

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

在文件 i_blas.h2791 行定义.

2791 {
2792 return (ISqrt(ISquaresumU(x, n)));
2793}
int ISquaresumU(const unsigned char *x, int n)
Definition i_blas.h:2512

◆ IL2Norm1()

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

在文件 i_blas.h2804 行定义.

2804 {
2805 return (x[0]);
2806}

◆ IL2Norm10()

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

在文件 i_blas.h2840 行定义.

2840 {
2841 return (ISqrt(ISquaresum10(x)));
2842}
T ISquaresum10(const T x[10])
Definition i_blas.h:2568

◆ IL2Norm11()

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

在文件 i_blas.h2844 行定义.

2844 {
2845 return (ISqrt(ISquaresum11(x)));
2846}
T ISquaresum11(const T x[11])
Definition i_blas.h:2573

◆ IL2Norm12()

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

在文件 i_blas.h2848 行定义.

2848 {
2849 return (ISqrt(ISquaresum12(x)));
2850}
T ISquaresum12(const T x[12])
Definition i_blas.h:2579

◆ IL2Norm13()

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

在文件 i_blas.h2852 行定义.

2852 {
2853 return (ISqrt(ISquaresum13(x)));
2854}
T ISquaresum13(const T x[13])
Definition i_blas.h:2585

◆ IL2Norm14()

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

在文件 i_blas.h2856 行定义.

2856 {
2857 return (ISqrt(ISquaresum14(x)));
2858}
T ISquaresum14(const T x[14])
Definition i_blas.h:2591

◆ IL2Norm15()

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

在文件 i_blas.h2860 行定义.

2860 {
2861 return (ISqrt(ISquaresum15(x)));
2862}
T ISquaresum15(const T x[15])
Definition i_blas.h:2597

◆ IL2Norm16()

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

在文件 i_blas.h2864 行定义.

2864 {
2865 return (ISqrt(ISquaresum16(x)));
2866}
T ISquaresum16(const T x[16])
Definition i_blas.h:2603

◆ IL2Norm2()

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

在文件 i_blas.h2808 行定义.

2808 {
2809 return (ISqrt(ISquaresum2(x)));
2810}
T ISquaresum2(const T x[2])
Definition i_blas.h:2532

◆ IL2Norm3()

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

在文件 i_blas.h2812 行定义.

2812 {
2813 return (ISqrt(ISquaresum3(x)));
2814}
T ISquaresum3(const T x[3])
Definition i_blas.h:2536

◆ IL2Norm4()

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

在文件 i_blas.h2816 行定义.

2816 {
2817 return (ISqrt(ISquaresum4(x)));
2818}
T ISquaresum4(const T x[4])
Definition i_blas.h:2540

◆ IL2Norm5()

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

在文件 i_blas.h2820 行定义.

2820 {
2821 return (ISqrt(ISquaresum5(x)));
2822}
T ISquaresum5(const T x[5])
Definition i_blas.h:2544

◆ IL2Norm6()

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

在文件 i_blas.h2824 行定义.

2824 {
2825 return (ISqrt(ISquaresum6(x)));
2826}
T ISquaresum6(const T x[6])
Definition i_blas.h:2548

◆ IL2Norm7()

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

在文件 i_blas.h2828 行定义.

2828 {
2829 return (ISqrt(ISquaresum7(x)));
2830}
T ISquaresum7(const T x[7])
Definition i_blas.h:2553

◆ IL2Norm8()

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

在文件 i_blas.h2832 行定义.

2832 {
2833 return (ISqrt(ISquaresum8(x)));
2834}
T ISquaresum8(const T x[8])
Definition i_blas.h:2558

◆ IL2Norm9()

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

在文件 i_blas.h2836 行定义.

2836 {
2837 return (ISqrt(ISquaresum9(x)));
2838}
T ISquaresum9(const T x[9])
Definition i_blas.h:2563

◆ IL2NormAdv() [1/2]

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

在文件 i_blas.h2886 行定义.

2886 {
2887 return IL2NormAdv<T>(x[0], x[1]);
2888}

◆ IL2NormAdv() [2/2]

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

在文件 i_blas.h2871 行定义.

2871 {
2872 T absa = IAbs(a);
2873 T absb = IAbs(b);
2874 if (absa > absb) {
2875 return (absa * ISqrt(static_cast<T>(1.0) + ISqr(IDiv(absb, absa))));
2876 } else {
2877 return (absb == static_cast<T>(0.0)
2878 ? static_cast<T>(0.0)
2879 : absb * ISqrt(static_cast<T>(1.0) + ISqr(IDiv(absa, absb))));
2880 }
2881}

◆ ILarger()

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

在文件 i_sort.h32 行定义.

32 {
33 return a > b;
34}

◆ ILess()

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

在文件 i_sort.h26 行定义.

26 {
27 return a < b;
28}

◆ ILineFit2d()

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

在文件 i_line.h68 行定义.

68 {
69 T ma[4] = {x[0], x[1], xp[0], xp[1]};
70 ILineFit2dTotalLeastSquare(ma, l, 2);
71}

◆ ILineFit2dTotalLeastSquare()

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

在文件 i_line.h36 行定义.

36 {
37 IZero3(l);
38 if (n < 2) {
39 return;
40 }
41 T ma[4], eigv[2];
42 T mq[4] = {static_cast<T>(0.0), static_cast<T>(0.0), static_cast<T>(0.0),
43 static_cast<T>(0.0)};
44 // // compute the centroid of input data points
45 int i, length = 2 * n;
46 T xm = static_cast<T>(0.0);
47 T ym = static_cast<T>(0.0);
48 for (i = 0; i < length; i += 2) {
49 xm += x[i];
50 ym += x[i + 1];
51 }
52 xm = IDiv(xm, n);
53 ym = IDiv(ym, n);
54 for (i = 0; i < length; i += 2) {
55 x[i] -= xm;
56 x[i + 1] -= ym;
57 }
58 IMultAtAnx2(x, ma, n);
59 IEigSymmetric2x2Closed(ma, eigv, mq);
60 l[0] = mq[1];
61 l[1] = mq[3];
62 l[2] = -xm * l[0] - ym * l[1];
63}
void IEigSymmetric2x2Closed(const T *A, T *EV, T *Q)
Definition i_util.h:29
void IMultAtAnx2(const T *A, T *AtA, int n)
Definition i_blas.h:4812

◆ ILineToPointDistance2d()

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

在文件 i_line.h27 行定义.

27 {
28 return IDiv(IAbs(IDot2(l, p) + l[2]), IL2Norm2(l));
29}
T IL2Norm2(const T x[2])
Definition i_blas.h:2808
T IDot2(const T x[2], const T y[2])
Definition i_blas.h:2256

◆ ILog() [1/4]

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

在文件 i_basic.h133 行定义.

133{ return ((x > 0.0) ? log(x) : 0.0); }

◆ ILog() [2/4]

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

在文件 i_basic.h126 行定义.

126{ return ((x > 0.f) ? logf(x) : 0.f); }

◆ ILog() [3/4]

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

在文件 i_basic.h127 行定义.

127 {
128 return ((x > 0) ? log(static_cast<double>(x)) : 0.0);
129}

◆ ILog() [4/4]

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

在文件 i_basic.h130 行定义.

130 {
131 return ((x > 0) ? log(static_cast<double>(x)) : 0.0);
132}

◆ IMakeConstReference()

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

在文件 i_basic.h424 行定义.

424 {
425 for (int i = 0; i < m; i++) {
426 p[i] = &a[i * n];
427 }
428}

◆ IMakeConstReference12x12()

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

在文件 i_basic.h475 行定义.

475 {
476 p[0] = &a[0];
477 p[1] = &a[12];
478 p[2] = &a[24];
479 p[3] = &a[36];
480 p[4] = &a[48];
481 p[5] = &a[60];
482 p[6] = &a[72];
483 p[7] = &a[84];
484 p[8] = &a[96];
485 p[9] = &a[108];
486 p[10] = &a[120];
487 p[11] = &a[132];
488}

◆ IMakeConstReference2x2()

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

在文件 i_basic.h430 行定义.

430 {
431 p[0] = &a[0];
432 p[1] = &a[2];
433}

◆ IMakeConstReference3x3()

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

在文件 i_basic.h435 行定义.

435 {
436 p[0] = &a[0];
437 p[1] = &a[3];
438 p[2] = &a[6];
439}

◆ IMakeConstReference4x4()

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

在文件 i_basic.h441 行定义.

441 {
442 p[0] = &a[0];
443 p[1] = &a[4];
444 p[2] = &a[8];
445 p[3] = &a[12];
446}

◆ IMakeConstReference4x9()

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

在文件 i_basic.h448 行定义.

448 {
449 p[0] = &a[0];
450 p[1] = &a[9];
451 p[2] = &a[18];
452 p[3] = &a[27];
453}

◆ IMakeConstReference5x9()

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

在文件 i_basic.h455 行定义.

455 {
456 p[0] = &a[0];
457 p[1] = &a[9];
458 p[2] = &a[18];
459 p[3] = &a[27];
460 p[4] = &a[36];
461}

◆ IMakeConstReference9x9()

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

在文件 i_basic.h463 行定义.

463 {
464 p[0] = &a[0];
465 p[1] = &a[9];
466 p[2] = &a[18];
467 p[3] = &a[27];
468 p[4] = &a[36];
469 p[5] = &a[45];
470 p[6] = &a[54];
471 p[7] = &a[63];
472 p[8] = &a[72];
473}

◆ IMakeReference() [1/2]

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

在文件 i_basic.h492 行定义.

492 {
493 T *temp = a;
494 for (int i = 0; i < l; i++) {
495 for (int j = 0; j < m; j++) {
496 p[i][j] = temp;
497 temp += n;
498 }
499 }
500}

◆ IMakeReference() [2/2]

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

在文件 i_basic.h357 行定义.

357 {
358 for (int i = 0; i < m; i++) {
359 p[i] = &a[i * n];
360 }
361}

◆ IMakeReference12x12()

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

在文件 i_basic.h408 行定义.

408 {
409 p[0] = &a[0];
410 p[1] = &a[12];
411 p[2] = &a[24];
412 p[3] = &a[36];
413 p[4] = &a[48];
414 p[5] = &a[60];
415 p[6] = &a[72];
416 p[7] = &a[84];
417 p[8] = &a[96];
418 p[9] = &a[108];
419 p[10] = &a[120];
420 p[11] = &a[132];
421}

◆ IMakeReference2x2()

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

在文件 i_basic.h363 行定义.

363 {
364 p[0] = &a[0];
365 p[1] = &a[2];
366}

◆ IMakeReference3x3()

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

在文件 i_basic.h368 行定义.

368 {
369 p[0] = &a[0];
370 p[1] = &a[3];
371 p[2] = &a[6];
372}

◆ IMakeReference4x4()

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

在文件 i_basic.h374 行定义.

374 {
375 p[0] = &a[0];
376 p[1] = &a[4];
377 p[2] = &a[8];
378 p[3] = &a[12];
379}

◆ IMakeReference4x9()

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

在文件 i_basic.h381 行定义.

381 {
382 p[0] = &a[0];
383 p[1] = &a[9];
384 p[2] = &a[18];
385 p[3] = &a[27];
386}

◆ IMakeReference5x9()

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

在文件 i_basic.h388 行定义.

388 {
389 p[0] = &a[0];
390 p[1] = &a[9];
391 p[2] = &a[18];
392 p[3] = &a[27];
393 p[4] = &a[36];
394}

◆ IMakeReference9x9()

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

在文件 i_basic.h396 行定义.

396 {
397 p[0] = &a[0];
398 p[1] = &a[9];
399 p[2] = &a[18];
400 p[3] = &a[27];
401 p[4] = &a[36];
402 p[5] = &a[45];
403 p[6] = &a[54];
404 p[7] = &a[63];
405 p[8] = &a[72];
406}

◆ IMax()

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

在文件 i_basic.h161 行定义.

161 {
162 return ((a >= b) ? a : b);
163}

◆ IMaxAbsIndex() [1/3]

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

在文件 i_blas.h3353 行定义.

3353 {
3354 int bi;
3355 double b, t;
3356 if (n <= 0) {
3357 return (0);
3358 }
3359 b = IAbs(a[0]);
3360 bi = 0;
3361 for (int i = 1; i < n; i++)
3362 if ((t = IAbs(a[i])) > b) {
3363 b = t;
3364 bi = i;
3365 }
3366 return (bi);
3367}

◆ IMaxAbsIndex() [2/3]

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

在文件 i_blas.h3368 行定义.

3368 {
3369 int bi;
3370 float b, t;
3371 if (n <= 0) {
3372 return (0);
3373 }
3374 b = IAbs(a[0]);
3375 bi = 0;
3376 for (int i = 1; i < n; i++)
3377 if ((t = IAbs(a[i])) > b) {
3378 b = t;
3379 bi = i;
3380 }
3381 return (bi);
3382}

◆ IMaxAbsIndex() [3/3]

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

在文件 i_blas.h3383 行定义.

3383 {
3384 int bi;
3385 int b, t;
3386 if (n <= 0) {
3387 return (0);
3388 }
3389 b = IAbs(a[0]);
3390 bi = 0;
3391 for (int i = 1; i < n; i++)
3392 if ((t = IAbs(a[i])) > b) {
3393 b = t;
3394 bi = i;
3395 }
3396 return (bi);
3397}

◆ IMaxAbsIndexInterval() [1/3]

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

在文件 i_blas.h3447 行定义.

3447 {
3448 int bi;
3449 double b, t;
3450 b = IAbs(a[i1]);
3451 bi = i1;
3452 for (int i = i1 + 1; i < i2; i++) {
3453 if ((t = IAbs(a[i])) > b) {
3454 b = t;
3455 bi = i;
3456 }
3457 }
3458 return (bi);
3459}

◆ IMaxAbsIndexInterval() [2/3]

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

在文件 i_blas.h3460 行定义.

3460 {
3461 int bi;
3462 float b, t;
3463 b = IAbs(a[i1]);
3464 bi = i1;
3465 for (int i = i1 + 1; i < i2; i++) {
3466 if ((t = IAbs(a[i])) > b) {
3467 b = t;
3468 bi = i;
3469 }
3470 }
3471 return (bi);
3472}

◆ IMaxAbsIndexInterval() [3/3]

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

在文件 i_blas.h3473 行定义.

3473 {
3474 int bi;
3475 int b, t;
3476 b = IAbs(a[i1]);
3477 bi = i1;
3478 for (int i = i1 + 1; i < i2; i++) {
3479 if ((t = IAbs(a[i])) > b) {
3480 b = t;
3481 bi = i;
3482 }
3483 }
3484 return (bi);
3485}

◆ IMaxAbsIndexIntervalColumn() [1/3]

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

在文件 i_blas.h3530 行定义.

3530 {
3531 int bi;
3532 double b, t;
3533 const double *ref = a + n * i1;
3534 b = IAbs(*ref);
3535 bi = i1;
3536 ref += n;
3537 for (int i = i1 + 1; i < i2; ++i, ref += n) {
3538 if ((t = IAbs(*ref)) > b) {
3539 b = t;
3540 bi = i;
3541 }
3542 }
3543 return (bi);
3544}

◆ IMaxAbsIndexIntervalColumn() [2/3]

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

在文件 i_blas.h3545 行定义.

3545 {
3546 int bi;
3547 float b, t;
3548 const float *ref = a + i1 * n;
3549 b = IAbs(*ref);
3550 bi = i1;
3551 for (int i = i1 + 1; i < i2; ++i, ref += n) {
3552 if ((t = IAbs(*ref)) > b) {
3553 b = t;
3554 bi = i;
3555 }
3556 }
3557 return (bi);
3558}

◆ IMaxAbsIndexIntervalColumn() [3/3]

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

在文件 i_blas.h3559 行定义.

3559 {
3560 int b, bi, t;
3561 const int *ref = a + i1 * n;
3562 b = IAbs(*ref);
3563 bi = i1;
3564 for (int i = i1; i < i2; ++i, ref += n) {
3565 if ((t = IAbs(*ref)) > b) {
3566 b = t;
3567 bi = i;
3568 }
3569 }
3570 return (bi);
3571}

◆ IMaxAbsIndexSubdiagonalColumn()

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

在文件 i_blas.h3621 行定义.

3621 {
3622 int j, largest_j;
3623 T largest_val, temp;
3624 largest_val = IAbs(A[i * n + i]);
3625 largest_j = i;
3626 for (j = i + 1; j < n; j++) {
3627 temp = IAbs(A[j * n + i]);
3628 if (temp > largest_val) {
3629 largest_val = temp;
3630 largest_j = j;
3631 }
3632 }
3633 return largest_j;
3634}

◆ IMaxDiagonalElement()

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

在文件 i_blas.h3289 行定义.

3289 {
3290 T val, temp;
3291 if (n <= 0) {
3292 return (static_cast<T>(0.0));
3293 }
3294 val = a[0];
3295 int i, ni = n;
3296 for (i = 1; i < n; i++, ni += n) {
3297 temp = a[ni + i];
3298 if (temp > val) {
3299 val = temp;
3300 }
3301 }
3302 return (val);
3303}

◆ IMaxElement()

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

在文件 i_blas.h3236 行定义.

3236 {
3237 T val, temp;
3238 if (n <= 0) {
3239 return (static_cast<T>(0.0));
3240 }
3241 val = a[0];
3242 for (int i = 1; i < n; i++) {
3243 temp = a[i];
3244 if (temp > val) {
3245 val = temp;
3246 }
3247 }
3248 return (val);
3249}

◆ IMaxIndex() [1/3]

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

在文件 i_blas.h3306 行定义.

3306 {
3307 int bi;
3308 double b, t;
3309 if (n <= 0) {
3310 return (0);
3311 }
3312 b = a[0];
3313 bi = 0;
3314 for (int i = 1; i < n; i++)
3315 if ((t = a[i]) > b) {
3316 b = t;
3317 bi = i;
3318 }
3319 return (bi);
3320}

◆ IMaxIndex() [2/3]

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

在文件 i_blas.h3321 行定义.

3321 {
3322 int bi;
3323 float b, t;
3324 if (n <= 0) {
3325 return (0);
3326 }
3327 b = a[0];
3328 bi = 0;
3329 for (int i = 1; i < n; i++)
3330 if ((t = a[i]) > b) {
3331 b = t;
3332 bi = i;
3333 }
3334 return (bi);
3335}

◆ IMaxIndex() [3/3]

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

在文件 i_blas.h3336 行定义.

3336 {
3337 int bi;
3338 int b, t;
3339 if (n <= 0) {
3340 return (0);
3341 }
3342 b = a[0];
3343 bi = 0;
3344 for (int i = 1; i < n; i++)
3345 if ((t = a[i]) > b) {
3346 b = t;
3347 bi = i;
3348 }
3349 return (bi);
3350}

◆ IMean()

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

在文件 i_blas.h2434 行定义.

2434 {
2435 return ISum(x, n) / n;
2436}
T ISum(const T *x, int n)
Definition i_blas.h:2344

◆ IMean10()

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

在文件 i_blas.h2470 行定义.

2470 {
2471 return ISum10(x) / 10;
2472}
T ISum10(const T x[10])
Definition i_blas.h:2388

◆ IMean11()

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

在文件 i_blas.h2474 行定义.

2474 {
2475 return ISum11(x) / 11;
2476}
T ISum11(const T x[11])
Definition i_blas.h:2392

◆ IMean12()

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

在文件 i_blas.h2478 行定义.

2478 {
2479 return ISum12(x) / 12;
2480}
T ISum12(const T x[12])
Definition i_blas.h:2397

◆ IMean13()

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

在文件 i_blas.h2482 行定义.

2482 {
2483 return ISum13(x) / 13;
2484}
T ISum13(const T x[13])
Definition i_blas.h:2402

◆ IMean14()

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

在文件 i_blas.h2486 行定义.

2486 {
2487 return ISum14(x) / 14;
2488}
T ISum14(const T x[14])
Definition i_blas.h:2407

◆ IMean15()

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

在文件 i_blas.h2490 行定义.

2490 {
2491 return ISum15(x) / 15;
2492}
T ISum15(const T x[15])
Definition i_blas.h:2412

◆ IMean16()

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

在文件 i_blas.h2494 行定义.

2494 {
2495 return ISum16(x) / 16;
2496}
T ISum16(const T x[16])
Definition i_blas.h:2417

◆ IMean2()

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

在文件 i_blas.h2438 行定义.

2438 {
2439 return ISum2(x) / 2;
2440}

◆ IMean3()

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

在文件 i_blas.h2442 行定义.

2442 {
2443 return ISum3(x) / 3;
2444}

◆ IMean4()

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

在文件 i_blas.h2446 行定义.

2446 {
2447 return ISum4(x) / 4;
2448}

◆ IMean5()

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

在文件 i_blas.h2450 行定义.

2450 {
2451 return ISum5(x) / 5;
2452}

◆ IMean6()

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

在文件 i_blas.h2454 行定义.

2454 {
2455 return ISum6(x) / 6;
2456}

◆ IMean7()

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

在文件 i_blas.h2458 行定义.

2458 {
2459 return ISum7(x) / 7;
2460}

◆ IMean8()

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

在文件 i_blas.h2462 行定义.

2462 {
2463 return ISum8(x) / 8;
2464}

◆ IMean9()

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

在文件 i_blas.h2466 行定义.

2466 {
2467 return ISum9(x) / 9;
2468}

◆ IMeanU()

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

在文件 i_blas.h2432 行定义.

2432{ return ISumU(x, n) / n; }
int ISumU(const unsigned char *x, int n)
Definition i_blas.h:2336

◆ IMedian3()

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

在文件 i_sort.h37 行定义.

37 {
38 if (a <= b) {
39 if (c > a) {
40 if (c <= b) {
41 return (c);
42 }
43 return (b);
44 }
45 return (a);
46 }
47 if (c > b) {
48 if (c <= a) {
49 return (c);
50 }
51 return (a);
52 }
53 return (b);
54}

◆ IMin()

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

在文件 i_basic.h155 行定义.

155 {
156 return ((a <= b) ? a : b);
157}

◆ IMinAbsIndex() [1/3]

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

在文件 i_blas.h3399 行定义.

3399 {
3400 int bi;
3401 double b, t;
3402 if (n <= 0) {
3403 return (0);
3404 }
3405 b = IAbs(a[0]);
3406 bi = 0;
3407 for (int i = 1; i < n; i++)
3408 if ((t = IAbs(a[i])) < b) {
3409 b = t;
3410 bi = i;
3411 }
3412 return (bi);
3413}

◆ IMinAbsIndex() [2/3]

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

在文件 i_blas.h3414 行定义.

3414 {
3415 int bi;
3416 float b, t;
3417 if (n <= 0) {
3418 return (0);
3419 }
3420 b = IAbs(a[0]);
3421 bi = 0;
3422 for (int i = 1; i < n; i++)
3423 if ((t = IAbs(a[i])) < b) {
3424 b = t;
3425 bi = i;
3426 }
3427 return (bi);
3428}

◆ IMinAbsIndex() [3/3]

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

在文件 i_blas.h3429 行定义.

3429 {
3430 int bi;
3431 int b, t;
3432 if (n <= 0) {
3433 return (0);
3434 }
3435 b = IAbs(a[0]);
3436 bi = 0;
3437 for (int i = 1; i < n; i++)
3438 if ((t = IAbs(a[i])) < b) {
3439 b = t;
3440 bi = i;
3441 }
3442 return (bi);
3443}

◆ IMinAbsIndexInterval() [1/3]

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

在文件 i_blas.h3488 行定义.

3488 {
3489 int bi;
3490 double b, t;
3491 b = IAbs(a[i1]);
3492 bi = i1;
3493 for (int i = i1 + 1; i < i2; i++) {
3494 if ((t = IAbs(a[i])) < b) {
3495 b = t;
3496 bi = i;
3497 }
3498 }
3499 return (bi);
3500}

◆ IMinAbsIndexInterval() [2/3]

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

在文件 i_blas.h3501 行定义.

3501 {
3502 int bi;
3503 float b, t;
3504 b = IAbs(a[i1]);
3505 bi = i1;
3506 for (int i = i1 + 1; i < i2; i++) {
3507 if ((t = IAbs(a[i])) < b) {
3508 b = t;
3509 bi = i;
3510 }
3511 }
3512 return (bi);
3513}

◆ IMinAbsIndexInterval() [3/3]

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

在文件 i_blas.h3514 行定义.

3514 {
3515 int bi;
3516 int b, t;
3517 b = IAbs(a[i1]);
3518 bi = i1;
3519 for (int i = i1 + 1; i < i2; i++) {
3520 if ((t = IAbs(a[i])) < b) {
3521 b = t;
3522 bi = i;
3523 }
3524 }
3525 return (bi);
3526}

◆ IMinAbsIndexIntervalColumn() [1/3]

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

在文件 i_blas.h3575 行定义.

3575 {
3576 int bi;
3577 double b, t;
3578 const double *ref = a + n * i1;
3579 b = IAbs(*ref);
3580 bi = i1;
3581 for (int i = i1 + 1; i < i2; ++i, ref += n) {
3582 if ((t = IAbs(*ref)) < b) {
3583 b = t;
3584 bi = i;
3585 }
3586 }
3587 return (bi);
3588}

◆ IMinAbsIndexIntervalColumn() [2/3]

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

在文件 i_blas.h3589 行定义.

3589 {
3590 int bi;
3591 float b, t;
3592 const float *ref = a + i1 * n;
3593 b = IAbs(*ref);
3594 bi = i1;
3595 for (int i = i1 + 1; i < i2; ++i, ref += n) {
3596 if ((t = IAbs(*ref)) < b) {
3597 b = t;
3598 bi = i;
3599 }
3600 }
3601 return (bi);
3602}

◆ IMinAbsIndexIntervalColumn() [3/3]

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

在文件 i_blas.h3603 行定义.

3603 {
3604 int b, bi, t;
3605 const int *ref = a + i1 * n;
3606 b = IAbs(*ref);
3607 bi = i1;
3608 for (int i = i1; i < i2; ++i, ref += n) {
3609 if ((t = IAbs(*ref)) < b) {
3610 b = t;
3611 bi = i;
3612 }
3613 }
3614 return (bi);
3615}

◆ IMinElement()

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

在文件 i_blas.h3220 行定义.

3220 {
3221 T val, temp;
3222 if (n <= 0) {
3223 return (static_cast<T>(0.0));
3224 }
3225 val = a[0];
3226 for (int i = 1; i < n; i++) {
3227 temp = a[i];
3228 if (temp < val) {
3229 val = temp;
3230 }
3231 }
3232 return (val);
3233}

◆ IMinMaxElements()

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

在文件 i_blas.h3638 行定义.

3638 {
3639 T temp;
3640 if (n <= 0) {
3641 *min_val = *max_val = static_cast<T>(0.0);
3642 return;
3643 }
3644 *min_val = *max_val = a[0];
3645 for (int i = 1; i < n; i++) {
3646 temp = a[i];
3647 if (temp > *max_val) {
3648 *max_val = temp;
3649 }
3650 if (temp < *min_val) {
3651 *min_val = temp;
3652 }
3653 }
3654}

◆ IMove()

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

在文件 i_basic.h566 行定义.

566 {
567 *b = a;
568}

◆ IMultAAt2x3()

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

在文件 i_blas.h4904 行定义.

4904 {
4905 AAt[0] = A[0] * A[0] + A[1] * A[1] + A[2] * A[2];
4906 AAt[1] = AAt[2] = A[0] * A[3] + A[1] * A[4] + A[2] * A[5];
4907 AAt[3] = A[3] * A[3] + A[4] * A[4] + A[5] * A[5];
4908}

◆ IMultAAt3x3()

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

在文件 i_blas.h4911 行定义.

4911 {
4912 AAt[0] = (A[0] * A[0] + A[1] * A[1] + A[2] * A[2]);
4913 AAt[1] = AAt[3] = (A[0] * A[3] + A[1] * A[4] + A[2] * A[5]);
4914 AAt[2] = AAt[6] = (A[0] * A[6] + A[1] * A[7] + A[2] * A[8]);
4915 AAt[4] = (A[3] * A[3] + A[4] * A[4] + A[5] * A[5]);
4916 AAt[5] = AAt[7] = (A[3] * A[6] + A[4] * A[7] + A[5] * A[8]);
4917 AAt[8] = (A[6] * A[6] + A[7] * A[7] + A[8] * A[8]);
4918}

◆ IMultAAt4x1()

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

在文件 i_blas.h4921 行定义.

4921 {
4922 AAt[0] = A[0] * A[0];
4923 AAt[1] = AAt[4] = (A[0] * A[1]);
4924 AAt[2] = AAt[8] = (A[0] * A[2]);
4925 AAt[3] = AAt[12] = (A[0] * A[3]);
4926
4927 AAt[5] = A[1] * A[1];
4928 AAt[6] = AAt[9] = (A[1] * A[2]);
4929 AAt[7] = AAt[13] = (A[1] * A[3]);
4930
4931 AAt[10] = A[2] * A[2];
4932 AAt[11] = AAt[14] = (A[2] * A[3]);
4933
4934 AAt[15] = A[3] * A[3];
4935}

◆ IMultAB()

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

在文件 i_blas.h4425 行定义.

4425 {
4426 int in, io;
4427 T acc;
4428 for (int i = 0; i < m; i++) {
4429 in = i * n;
4430 io = i * o;
4431 for (int j = 0; j < o; j++) {
4432 acc = static_cast<T>(0.0);
4433 for (int k = 0; k < n; k++) {
4434 acc += A[in + k] * B[k * o + j];
4435 }
4436 AB[io + j] = acc;
4437 }
4438 }
4439}

◆ IMultAB2x2And2x2()

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

在文件 i_blas.h4457 行定义.

4457 {
4458 T a, b;
4459 a = A[0];
4460 b = A[1];
4461 AB[0] = a * B[0] + b * B[2];
4462 AB[1] = a * B[1] + b * B[3];
4463 a = A[2];
4464 b = A[3];
4465 AB[2] = a * B[0] + b * B[2];
4466 AB[3] = a * B[1] + b * B[3];
4467}

◆ IMultAB2x3And3x2()

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

在文件 i_blas.h4471 行定义.

4471 {
4472 T a, b, c;
4473 a = A[0];
4474 b = A[1];
4475 c = A[2];
4476 AB[0] = a * B[0] + b * B[2] + c * B[4];
4477 AB[1] = a * B[1] + b * B[3] + c * B[5];
4478 a = A[3];
4479 b = A[4];
4480 c = A[5];
4481 AB[2] = a * B[0] + b * B[2] + c * B[4];
4482 AB[3] = a * B[1] + b * B[3] + c * B[5];
4483}

◆ IMultAB2x3And3x3()

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

在文件 i_blas.h4487 行定义.

4487 {
4488 T a, b, c;
4489 a = A[0];
4490 b = A[1];
4491 c = A[2];
4492 AB[0] = a * B[0] + b * B[3] + c * B[6];
4493 AB[1] = a * B[1] + b * B[4] + c * B[7];
4494 AB[2] = a * B[2] + b * B[5] + c * B[8];
4495
4496 a = A[3];
4497 b = A[4];
4498 c = A[5];
4499 AB[3] = a * B[0] + b * B[3] + c * B[6];
4500 AB[4] = a * B[1] + b * B[4] + c * B[7];
4501 AB[5] = a * B[2] + b * B[5] + c * B[8];
4502}

◆ IMultAB2x3And3x4()

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

在文件 i_blas.h4506 行定义.

4506 {
4507 T a, b, c;
4508 a = A[0];
4509 b = A[1];
4510 c = A[2];
4511 AB[0] = a * B[0] + b * B[4] + c * B[8];
4512 AB[1] = a * B[1] + b * B[5] + c * B[9];
4513 AB[2] = a * B[2] + b * B[6] + c * B[10];
4514 AB[3] = a * B[3] + b * B[7] + c * B[11];
4515 a = A[3];
4516 b = A[4];
4517 c = A[5];
4518 AB[4] = a * B[0] + b * B[4] + c * B[8];
4519 AB[5] = a * B[1] + b * B[5] + c * B[9];
4520 AB[6] = a * B[2] + b * B[6] + c * B[10];
4521 AB[7] = a * B[3] + b * B[7] + c * B[11];
4522}

◆ IMultAB3x1And1x3()

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

在文件 i_blas.h4443 行定义.

4443 {
4444 AB[0] = A[0] * B[0];
4445 AB[1] = A[0] * B[1];
4446 AB[2] = A[0] * B[2];
4447 AB[3] = A[1] * B[0];
4448 AB[4] = A[1] * B[1];
4449 AB[5] = A[1] * B[2];
4450 AB[6] = A[2] * B[0];
4451 AB[7] = A[2] * B[1];
4452 AB[8] = A[2] * B[2];
4453}

◆ IMultAB3x3And3x3()

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

在文件 i_blas.h4526 行定义.

4526 {
4527 T a, b, c;
4528 a = A[0];
4529 b = A[1];
4530 c = A[2];
4531 AB[0] = a * B[0] + b * B[3] + c * B[6];
4532 AB[1] = a * B[1] + b * B[4] + c * B[7];
4533 AB[2] = a * B[2] + b * B[5] + c * B[8];
4534 a = A[3];
4535 b = A[4];
4536 c = A[5];
4537 AB[3] = a * B[0] + b * B[3] + c * B[6];
4538 AB[4] = a * B[1] + b * B[4] + c * B[7];
4539 AB[5] = a * B[2] + b * B[5] + c * B[8];
4540 a = A[6];
4541 b = A[7];
4542 c = A[8];
4543 AB[6] = a * B[0] + b * B[3] + c * B[6];
4544 AB[7] = a * B[1] + b * B[4] + c * B[7];
4545 AB[8] = a * B[2] + b * B[5] + c * B[8];
4546}

◆ IMultAB3x3And3x3WAUpperTriangular()

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

在文件 i_blas.h4619 行定义.

4620 {
4621 T a, b, c;
4622 a = A[0];
4623 b = A[1];
4624 c = A[2];
4625 AB[0] = a * B[0] + b * B[3] + c * B[6];
4626 AB[1] = a * B[1] + b * B[4] + c * B[7];
4627 AB[2] = a * B[2] + b * B[5] + c * B[8];
4628 b = A[4];
4629 c = A[5];
4630 AB[3] = b * B[3] + c * B[6];
4631 AB[4] = b * B[4] + c * B[7];
4632 AB[5] = b * B[5] + c * B[8];
4633 c = A[8];
4634 AB[6] = c * B[6];
4635 AB[7] = c * B[7];
4636 AB[8] = c * B[8];
4637}

◆ IMultAB3x3And3x3WBUpperTriangular()

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

在文件 i_blas.h4641 行定义.

4642 {
4643 T a, b, c;
4644 a = A[0];
4645 b = A[1];
4646 c = A[2];
4647 AB[0] = a * B[0];
4648 AB[1] = a * B[1] + b * B[4];
4649 AB[2] = a * B[2] + b * B[5] + c * B[8];
4650 a = A[3];
4651 b = A[4];
4652 c = A[5];
4653 AB[3] = a * B[0];
4654 AB[4] = a * B[1] + b * B[4];
4655 AB[5] = a * B[2] + b * B[5] + c * B[8];
4656 a = A[6];
4657 b = A[7];
4658 c = A[8];
4659 AB[6] = a * B[0];
4660 AB[7] = a * B[1] + b * B[4];
4661 AB[8] = a * B[2] + b * B[5] + c * B[8];
4662}

◆ IMultAB3x3And3x4()

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

在文件 i_blas.h4665 行定义.

4665 {
4666 AB[0] = A[0] * B[0] + A[1] * B[4] + A[2] * B[8];
4667 AB[1] = A[0] * B[1] + A[1] * B[5] + A[2] * B[9];
4668 AB[2] = A[0] * B[2] + A[1] * B[6] + A[2] * B[10];
4669 AB[3] = A[0] * B[3] + A[1] * B[7] + A[2] * B[11];
4670
4671 AB[4] = A[3] * B[0] + A[4] * B[4] + A[5] * B[8];
4672 AB[5] = A[3] * B[1] + A[4] * B[5] + A[5] * B[9];
4673 AB[6] = A[3] * B[2] + A[4] * B[6] + A[5] * B[10];
4674 AB[7] = A[3] * B[3] + A[4] * B[7] + A[5] * B[11];
4675
4676 AB[8] = A[6] * B[0] + A[7] * B[4] + A[8] * B[8];
4677 AB[9] = A[6] * B[1] + A[7] * B[5] + A[8] * B[9];
4678 AB[10] = A[6] * B[2] + A[7] * B[6] + A[8] * B[10];
4679 AB[11] = A[6] * B[3] + A[7] * B[7] + A[8] * B[11];
4680}

◆ IMultAB3x4And4x3()

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

在文件 i_blas.h4683 行定义.

4683 {
4684 T a, b, c, d;
4685 a = A[0];
4686 b = A[1];
4687 c = A[2];
4688 d = A[3];
4689 AB[0] = a * B[0] + b * B[3] + c * B[6] + d * B[9];
4690 AB[1] = a * B[1] + b * B[4] + c * B[7] + d * B[10];
4691 AB[2] = a * B[2] + b * B[5] + c * B[8] + d * B[11];
4692
4693 a = A[4];
4694 b = A[5];
4695 c = A[6];
4696 d = A[7];
4697 AB[3] = a * B[0] + b * B[3] + c * B[6] + d * B[9];
4698 AB[4] = a * B[1] + b * B[4] + c * B[7] + d * B[10];
4699 AB[5] = a * B[2] + b * B[5] + c * B[8] + d * B[11];
4700
4701 a = A[8];
4702 b = A[9];
4703 c = A[10];
4704 d = A[11];
4705 AB[6] = a * B[0] + b * B[3] + c * B[6] + d * B[9];
4706 AB[7] = a * B[1] + b * B[4] + c * B[7] + d * B[10];
4707 AB[8] = a * B[2] + b * B[5] + c * B[8] + d * B[11];
4708}

◆ IMultAB4x1And1x4()

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

在文件 i_blas.h4591 行定义.

4591 {
4592 T sf = A[0];
4593 AB[0] = sf * B[0];
4594 AB[1] = sf * B[1];
4595 AB[2] = sf * B[2];
4596 AB[3] = sf * B[3];
4597
4598 sf = A[1];
4599 AB[4] = sf * B[0];
4600 AB[5] = sf * B[1];
4601 AB[6] = sf * B[2];
4602 AB[7] = sf * B[3];
4603
4604 sf = A[2];
4605 AB[8] = sf * B[0];
4606 AB[9] = sf * B[1];
4607 AB[10] = sf * B[2];
4608 AB[11] = sf * B[3];
4609
4610 sf = A[3];
4611 AB[12] = sf * B[0];
4612 AB[13] = sf * B[1];
4613 AB[14] = sf * B[2];
4614 AB[15] = sf * B[3];
4615}

◆ IMultAB4x4And4x4()

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

在文件 i_blas.h4550 行定义.

4550 {
4551 T a, b, c, d;
4552 a = A[0];
4553 b = A[1];
4554 c = A[2];
4555 d = A[3];
4556 AB[0] = a * B[0] + b * B[4] + c * B[8] + d * B[12];
4557 AB[1] = a * B[1] + b * B[5] + c * B[9] + d * B[13];
4558 AB[2] = a * B[2] + b * B[6] + c * B[10] + d * B[14];
4559 AB[3] = a * B[3] + b * B[7] + c * B[11] + d * B[15];
4560
4561 a = A[4];
4562 b = A[5];
4563 c = A[6];
4564 d = A[7];
4565 AB[4] = a * B[0] + b * B[4] + c * B[8] + d * B[12];
4566 AB[5] = a * B[1] + b * B[5] + c * B[9] + d * B[13];
4567 AB[6] = a * B[2] + b * B[6] + c * B[10] + d * B[14];
4568 AB[7] = a * B[3] + b * B[7] + c * B[11] + d * B[15];
4569
4570 a = A[8];
4571 b = A[9];
4572 c = A[10];
4573 d = A[11];
4574 AB[8] = a * B[0] + b * B[4] + c * B[8] + d * B[12];
4575 AB[9] = a * B[1] + b * B[5] + c * B[9] + d * B[13];
4576 AB[10] = a * B[2] + b * B[6] + c * B[10] + d * B[14];
4577 AB[11] = a * B[3] + b * B[7] + c * B[11] + d * B[15];
4578
4579 a = A[12];
4580 b = A[13];
4581 c = A[14];
4582 d = A[15];
4583 AB[12] = a * B[0] + b * B[4] + c * B[8] + d * B[12];
4584 AB[13] = a * B[1] + b * B[5] + c * B[9] + d * B[13];
4585 AB[14] = a * B[2] + b * B[6] + c * B[10] + d * B[14];
4586 AB[15] = a * B[3] + b * B[7] + c * B[11] + d * B[15];
4587}

◆ IMultAB4x4WABlockDiagonal()

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

在文件 i_blas.h4954 行定义.

4955 {
4956 // A = A1 0
4957 // 0 A2
4958 // B = B1 B2
4959 // B3 B4
4960
4961 // A1B1
4962 AB[0] = A1[0] * B[0] + A1[1] * B[4];
4963 AB[1] = A1[0] * B[1] + A1[1] * B[5];
4964 AB[4] = A1[2] * B[0] + A1[3] * B[4];
4965 AB[5] = A1[2] * B[1] + A1[3] * B[5];
4966
4967 // A1B2
4968 AB[2] = A1[0] * B[2] + A1[1] * B[6];
4969 AB[3] = A1[0] * B[3] + A1[1] * B[7];
4970 AB[6] = A1[2] * B[2] + A1[3] * B[6];
4971 AB[7] = A1[2] * B[3] + A1[3] * B[7];
4972
4973 // A2B3
4974 AB[8] = A2[0] * B[8] + A2[1] * B[12];
4975 AB[9] = A2[0] * B[9] + A2[1] * B[13];
4976 AB[12] = A2[2] * B[8] + A2[3] * B[12];
4977 AB[13] = A2[2] * B[9] + A2[3] * B[13];
4978
4979 // A2B4
4980 AB[10] = A2[0] * B[10] + A2[1] * B[14];
4981 AB[11] = A2[0] * B[11] + A2[1] * B[15];
4982 AB[14] = A2[2] * B[10] + A2[3] * B[14];
4983 AB[15] = A2[2] * B[11] + A2[3] * B[15];
4984}

◆ IMultABC3x3And3x3And3x3()

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

在文件 i_blas.h4938 行定义.

4939 {
4940 T BC[9];
4941 IMultAB3x3And3x3(B, C, BC);
4942 IMultAB3x3And3x3(A, BC, ABC);
4943}
void IMultAB3x3And3x3(const T A[9], const T B[9], T AB[9])
Definition i_blas.h:4526

◆ IMultABt2x3And2x3()

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

在文件 i_blas.h4736 行定义.

4736 {
4737 ABt[0] = A[0] * B[0] + A[1] * B[1] + A[2] * B[2];
4738 ABt[1] = A[0] * B[3] + A[1] * B[4] + A[2] * B[5];
4739 ABt[2] = A[3] * B[0] + A[4] * B[1] + A[5] * B[2];
4740 ABt[3] = A[3] * B[3] + A[4] * B[4] + A[5] * B[5];
4741}

◆ IMultABt3x3And3x3()

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

在文件 i_blas.h4712 行定义.

4712 {
4713 T a, b, c;
4714 a = A[0];
4715 b = A[1];
4716 c = A[2];
4717 ABt[0] = a * B[0] + b * B[1] + c * B[2];
4718 ABt[1] = a * B[3] + b * B[4] + c * B[5];
4719 ABt[2] = a * B[6] + b * B[7] + c * B[8];
4720 a = A[3];
4721 b = A[4];
4722 c = A[5];
4723 ABt[3] = a * B[0] + b * B[1] + c * B[2];
4724 ABt[4] = a * B[3] + b * B[4] + c * B[5];
4725 ABt[5] = a * B[6] + b * B[7] + c * B[8];
4726 a = A[6];
4727 b = A[7];
4728 c = A[8];
4729 ABt[6] = a * B[0] + b * B[1] + c * B[2];
4730 ABt[7] = a * B[3] + b * B[4] + c * B[5];
4731 ABt[8] = a * B[6] + b * B[7] + c * B[8];
4732}

◆ IMultABt4x4And3x4()

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

在文件 i_blas.h4745 行定义.

4745 {
4746 ABt[0] = IDot4(A, B);
4747 ABt[1] = IDot4(A, B + 4);
4748 ABt[2] = IDot4(A, B + 8);
4749
4750 ABt[3] = IDot4(A + 4, B);
4751 ABt[4] = IDot4(A + 4, B + 4);
4752 ABt[5] = IDot4(A + 4, B + 8);
4753
4754 ABt[6] = IDot4(A + 8, B);
4755 ABt[7] = IDot4(A + 8, B + 4);
4756 ABt[8] = IDot4(A + 8, B + 8);
4757
4758 ABt[9] = IDot4(A + 12, B);
4759 ABt[10] = IDot4(A + 12, B + 4);
4760 ABt[11] = IDot4(A + 12, B + 8);
4761}
T IDot4(const T x[4], const T y[4])
Definition i_blas.h:2264

◆ IMultAtA()

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

在文件 i_blas.h4765 行定义.

4765 {
4766 int i, j, k, ni;
4767 T acc;
4768 const T *Ai, *Aj;
4769 for (i = 0; i < n; ++i) {
4770 ni = n * i;
4771 for (j = 0; j < i; ++j) {
4772 AtA[ni + j] = AtA[j * n + i];
4773 }
4774 for (j = i; j < n; ++j) {
4775 acc = static_cast<T>(0.0);
4776 Ai = A + i;
4777 Aj = A + j;
4778 for (k = 0; k < m; ++k, Ai += n, Aj += n) {
4779 acc += (*Ai) * (*Aj);
4780 }
4781 AtA[ni + j] = acc;
4782 }
4783 }
4784}

◆ IMultAtA2x2() [1/2]

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

在文件 i_blas.h4794 行定义.

4794 {
4795 T xx = static_cast<T>(0.0);
4796 T xy = static_cast<T>(0.0);
4797 T yy = static_cast<T>(0.0);
4798 T x, y;
4799 for (int i = 0; i < 2 * n; i += 2) {
4800 x = A[i];
4801 y = A[i + 1];
4802 xx += x * x;
4803 xy += x * y;
4804 yy += y * y;
4805 }
4806 AtA[0] = xx;
4807 AtA[1] = AtA[2] = xy;
4808 AtA[3] = yy;
4809}

◆ IMultAtA2x2() [2/2]

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

在文件 i_blas.h4787 行定义.

4787 {
4788 AtA[0] = A[0] * A[0] + A[2] * A[2];
4789 AtA[1] = AtA[2] = A[0] * A[1] + A[2] * A[3];
4790 AtA[3] = A[1] * A[1] + A[3] * A[3];
4791}

◆ IMultAtA3x3()

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

在文件 i_blas.h4830 行定义.

4830 {
4831 AtA[0] = A[0] * A[0] + A[3] * A[3] + A[6] * A[6];
4832 AtA[1] = AtA[3] = A[0] * A[1] + A[3] * A[4] + A[6] * A[7];
4833 AtA[2] = AtA[6] = A[0] * A[2] + A[3] * A[5] + A[6] * A[8];
4834 AtA[4] = A[1] * A[1] + A[4] * A[4] + A[7] * A[7];
4835 AtA[5] = AtA[7] = A[1] * A[2] + A[4] * A[5] + A[7] * A[8];
4836 AtA[8] = A[2] * A[2] + A[5] * A[5] + A[8] * A[8];
4837}

◆ IMultAtA4x4()

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

在文件 i_blas.h4869 行定义.

4869 {
4870 AtA[0] = A[0] * A[0] + A[4] * A[4] + A[8] * A[8] + A[12] * A[12];
4871 AtA[1] = AtA[4] = A[0] * A[1] + A[4] * A[5] + A[8] * A[9] + A[12] * A[13];
4872 AtA[2] = AtA[8] = A[0] * A[2] + A[4] * A[6] + A[8] * A[10] + A[12] * A[14];
4873 AtA[3] = AtA[12] = A[0] * A[3] + A[4] * A[7] + A[8] * A[11] + A[12] * A[15];
4874 AtA[5] = A[1] * A[1] + A[5] * A[5] + A[9] * A[9] + A[13] * A[13];
4875 AtA[6] = AtA[9] = A[1] * A[2] + A[5] * A[6] + A[9] * A[10] + A[13] * A[14];
4876 AtA[7] = AtA[13] = A[1] * A[3] + A[5] * A[7] + A[9] * A[11] + A[13] * A[15];
4877 AtA[10] = A[2] * A[2] + A[6] * A[6] + A[10] * A[10] + A[14] * A[14];
4878 AtA[11] = AtA[14] = A[2] * A[3] + A[6] * A[7] + A[10] * A[11] + A[14] * A[15];
4879 AtA[15] = A[3] * A[3] + A[7] * A[7] + A[11] * A[11] + A[15] * A[15];
4880}

◆ IMultAtAnx2()

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

在文件 i_blas.h4812 行定义.

4812 {
4813 T xx = static_cast<T>(0.0);
4814 T xy = static_cast<T>(0.0);
4815 T yy = static_cast<T>(0.0);
4816 T x, y;
4817 for (int i = 0; i < 2 * n; i += 2) {
4818 x = A[i];
4819 y = A[i + 1];
4820 xx += x * x;
4821 xy += x * y;
4822 yy += y * y;
4823 }
4824 AtA[0] = xx;
4825 AtA[1] = AtA[2] = xy;
4826 AtA[3] = yy;
4827}

◆ IMultAtAnx3()

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

在文件 i_blas.h4840 行定义.

4840 {
4841 T xx = static_cast<T>(0.0);
4842 T xy = static_cast<T>(0.0);
4843 T xz = static_cast<T>(0.0);
4844 T yy = static_cast<T>(0.0);
4845 T yz = static_cast<T>(0.0);
4846 T zz = static_cast<T>(0.0);
4847 T x, y, z;
4848 int i, j;
4849 for (i = 0, j = 0; i < n; i++) {
4850 x = A[j++];
4851 y = A[j++];
4852 z = A[j++];
4853 xx += x * x;
4854 xy += x * y;
4855 xz += x * z;
4856 yy += y * y;
4857 yz += y * z;
4858 zz += z * z;
4859 }
4860 AtA[0] = xx;
4861 AtA[1] = AtA[3] = xy;
4862 AtA[2] = AtA[6] = xz;
4863 AtA[4] = yy;
4864 AtA[5] = AtA[7] = yz;
4865 AtA[8] = zz;
4866}

◆ IMultAtB2x2And2x2()

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

在文件 i_blas.h4883 行定义.

4883 {
4884 AtB[0] = A[0] * B[0] + A[2] * B[2];
4885 AtB[1] = A[0] * B[1] + A[2] * B[3];
4886 AtB[2] = A[1] * B[0] + A[3] * B[2];
4887 AtB[3] = A[1] * B[1] + A[3] * B[3];
4888}

◆ IMultAtB3x3And3x3()

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

在文件 i_blas.h4891 行定义.

4891 {
4892 AtB[0] = A[0] * B[0] + A[3] * B[3] + A[6] * B[6];
4893 AtB[1] = A[0] * B[1] + A[3] * B[4] + A[6] * B[7];
4894 AtB[2] = A[0] * B[2] + A[3] * B[5] + A[6] * B[8];
4895 AtB[3] = A[1] * B[0] + A[4] * B[3] + A[7] * B[6];
4896 AtB[4] = A[1] * B[1] + A[4] * B[4] + A[7] * B[7];
4897 AtB[5] = A[1] * B[2] + A[4] * B[5] + A[7] * B[8];
4898 AtB[6] = A[2] * B[0] + A[5] * B[3] + A[8] * B[6];
4899 AtB[7] = A[2] * B[1] + A[5] * B[4] + A[8] * B[7];
4900 AtB[8] = A[2] * B[2] + A[5] * B[5] + A[8] * B[8];
4901}

◆ IMultAtBC3x3And3x3And3x3()

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

在文件 i_blas.h4946 行定义.

4947 {
4948 T BC[9];
4949 IMultAB3x3And3x3(B, C, BC);
4950 IMultAtB3x3And3x3(A, BC, AtBC);
4951}
void IMultAtB3x3And3x3(const T A[9], const T B[9], T AtB[9])
Definition i_blas.h:4891

◆ IMultAtx()

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

在文件 i_blas.h4319 行定义.

4319 {
4320 T acc;
4321 const T *Ai = nullptr;
4322 for (int i = 0; i < n; i++) {
4323 Ai = A + i;
4324 acc = T(0.0);
4325 for (int j = 0; j < m; j++, Ai += n) {
4326 acc += (*Ai) * x[j];
4327 }
4328 Atx[i] = acc;
4329 }
4330}

◆ IMultAtx3x3()

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

在文件 i_blas.h4369 行定义.

4369 {
4370 T x0, x1, x2;
4371 x0 = x[0];
4372 x1 = x[1];
4373 x2 = x[2];
4374 Atx[0] = A[0] * x0 + A[3] * x1 + A[6] * x2;
4375 Atx[1] = A[1] * x0 + A[4] * x1 + A[7] * x2;
4376 Atx[2] = A[2] * x0 + A[5] * x1 + A[8] * x2;
4377}

◆ IMultAtx4x3()

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

在文件 i_blas.h4404 行定义.

4404 {
4405 Atx[0] = A[0] * x[0] + A[4] * x[1] + A[8] * x[2];
4406 Atx[1] = A[1] * x[0] + A[5] * x[1] + A[9] * x[2];
4407 Atx[2] = A[2] * x[0] + A[6] * x[1] + A[10] * x[2];
4408 Atx[3] = A[3] * x[0] + A[7] * x[1] + A[11] * x[2];
4409}

◆ IMultAx()

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

在文件 i_blas.h4310 行定义.

4310 {
4311 for (int i = 0; i < m; i++) {
4312 Ax[i] = IDot(A + i * n, x, n);
4313 }
4314}
T IDot(const T *x, const T *y, int n)
Definition i_blas.h:2244

◆ IMultAx1x3()

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

在文件 i_blas.h4334 行定义.

4334 {
4335 Ax[0] = A[0] * x[0] + A[1] * x[1] + A[2] * x[2];
4336}

◆ IMultAx2x2()

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

在文件 i_blas.h4339 行定义.

4339 {
4340 T x0, x1;
4341 x0 = x[0];
4342 x1 = x[1];
4343 Ax[0] = A[0] * x0 + A[1] * x1;
4344 Ax[1] = A[2] * x0 + A[3] * x1;
4345}

◆ IMultAx2x3()

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

在文件 i_blas.h4348 行定义.

4348 {
4349 T x0, x1, x2;
4350 x0 = x[0];
4351 x1 = x[1];
4352 x2 = x[2];
4353 Ax[0] = A[0] * x0 + A[1] * x1 + A[2] * x2;
4354 Ax[1] = A[3] * x0 + A[4] * x1 + A[5] * x2;
4355}

◆ IMultAx3x3()

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

在文件 i_blas.h4358 行定义.

4358 {
4359 T x0, x1, x2;
4360 x0 = x[0];
4361 x1 = x[1];
4362 x2 = x[2];
4363 Ax[0] = A[0] * x0 + A[1] * x1 + A[2] * x2;
4364 Ax[1] = A[3] * x0 + A[4] * x1 + A[5] * x2;
4365 Ax[2] = A[6] * x0 + A[7] * x1 + A[8] * x2;
4366}

◆ IMultAx3x4()

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

在文件 i_blas.h4380 行定义.

4380 {
4381 T x0, x1, x2, x3;
4382 x0 = x[0];
4383 x1 = x[1];
4384 x2 = x[2];
4385 x3 = x[3];
4386 Ax[0] = A[0] * x0 + A[1] * x1 + A[2] * x2 + A[3] * x3;
4387 Ax[1] = A[4] * x0 + A[5] * x1 + A[6] * x2 + A[7] * x3;
4388 Ax[2] = A[8] * x0 + A[9] * x1 + A[10] * x2 + A[11] * x3;
4389}

◆ IMultAx4x3()

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

在文件 i_blas.h4392 行定义.

4392 {
4393 T x0, x1, x2;
4394 x0 = x[0];
4395 x1 = x[1];
4396 x2 = x[2];
4397 Ax[0] = A[0] * x0 + A[1] * x1 + A[2] * x2;
4398 Ax[1] = A[3] * x0 + A[4] * x1 + A[5] * x2;
4399 Ax[2] = A[6] * x0 + A[7] * x1 + A[8] * x2;
4400 Ax[3] = A[9] * x0 + A[10] * x1 + A[11] * x2;
4401}

◆ IMultAx4x4()

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

在文件 i_blas.h4412 行定义.

4412 {
4413 T x0, x1, x2, x3;
4414 x0 = x[0];
4415 x1 = x[1];
4416 x2 = x[2];
4417 x3 = x[3];
4418 Ax[0] = A[0] * x0 + A[1] * x1 + A[2] * x2 + A[3] * x3;
4419 Ax[1] = A[4] * x0 + A[5] * x1 + A[6] * x2 + A[7] * x3;
4420 Ax[2] = A[8] * x0 + A[9] * x1 + A[10] * x2 + A[11] * x3;
4421 Ax[3] = A[12] * x0 + A[13] * x1 + A[14] * x2 + A[15] * x3;
4422}

◆ INeg()

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

在文件 i_blas.h400 行定义.

400 {
401 for (int i = 0; i < n; i++) {
402 x[i] = -x[i];
403 }
404}

◆ INeg1() [1/2]

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

在文件 i_blas.h591 行定义.

591 {
592 y[0] = -x[0];
593}

◆ INeg1() [2/2]

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

在文件 i_blas.h406 行定义.

406 {
407 x[0] = -x[0];
408}

◆ INeg10() [1/2]

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

在文件 i_blas.h663 行定义.

663 {
664 y[0] = -x[0];
665 y[1] = -x[1];
666 y[2] = -x[2];
667 y[3] = -x[3];
668 y[4] = -x[4];
669 y[5] = -x[5];
670 y[6] = -x[6];
671 y[7] = -x[7];
672 y[8] = -x[8];
673 y[9] = -x[9];
674}

◆ INeg10() [2/2]

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

在文件 i_blas.h478 行定义.

478 {
479 x[0] = -x[0];
480 x[1] = -x[1];
481 x[2] = -x[2];
482 x[3] = -x[3];
483 x[4] = -x[4];
484 x[5] = -x[5];
485 x[6] = -x[6];
486 x[7] = -x[7];
487 x[8] = -x[8];
488 x[9] = -x[9];
489}

◆ INeg11() [1/2]

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

在文件 i_blas.h676 行定义.

676 {
677 y[0] = -x[0];
678 y[1] = -x[1];
679 y[2] = -x[2];
680 y[3] = -x[3];
681 y[4] = -x[4];
682 y[5] = -x[5];
683 y[6] = -x[6];
684 y[7] = -x[7];
685 y[8] = -x[8];
686 y[9] = -x[9];
687 y[10] = -x[10];
688}

◆ INeg11() [2/2]

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

在文件 i_blas.h491 行定义.

491 {
492 x[0] = -x[0];
493 x[1] = -x[1];
494 x[2] = -x[2];
495 x[3] = -x[3];
496 x[4] = -x[4];
497 x[5] = -x[5];
498 x[6] = -x[6];
499 x[7] = -x[7];
500 x[8] = -x[8];
501 x[9] = -x[9];
502 x[10] = -x[10];
503}

◆ INeg12() [1/2]

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

在文件 i_blas.h690 行定义.

690 {
691 y[0] = -x[0];
692 y[1] = -x[1];
693 y[2] = -x[2];
694 y[3] = -x[3];
695 y[4] = -x[4];
696 y[5] = -x[5];
697 y[6] = -x[6];
698 y[7] = -x[7];
699 y[8] = -x[8];
700 y[9] = -x[9];
701 y[10] = -x[10];
702 y[11] = -x[11];
703}

◆ INeg12() [2/2]

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

在文件 i_blas.h505 行定义.

505 {
506 x[0] = -x[0];
507 x[1] = -x[1];
508 x[2] = -x[2];
509 x[3] = -x[3];
510 x[4] = -x[4];
511 x[5] = -x[5];
512 x[6] = -x[6];
513 x[7] = -x[7];
514 x[8] = -x[8];
515 x[9] = -x[9];
516 x[10] = -x[10];
517 x[11] = -x[11];
518}

◆ INeg13() [1/2]

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

在文件 i_blas.h705 行定义.

705 {
706 y[0] = -x[0];
707 y[1] = -x[1];
708 y[2] = -x[2];
709 y[3] = -x[3];
710 y[4] = -x[4];
711 y[5] = -x[5];
712 y[6] = -x[6];
713 y[7] = -x[7];
714 y[8] = -x[8];
715 y[9] = -x[9];
716 y[10] = -x[10];
717 y[11] = -x[11];
718 y[12] = -x[12];
719}

◆ INeg13() [2/2]

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

在文件 i_blas.h520 行定义.

520 {
521 x[0] = -x[0];
522 x[1] = -x[1];
523 x[2] = -x[2];
524 x[3] = -x[3];
525 x[4] = -x[4];
526 x[5] = -x[5];
527 x[6] = -x[6];
528 x[7] = -x[7];
529 x[8] = -x[8];
530 x[9] = -x[9];
531 x[10] = -x[10];
532 x[11] = -x[11];
533 x[12] = -x[12];
534}

◆ INeg14() [1/2]

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

在文件 i_blas.h721 行定义.

721 {
722 y[0] = -x[0];
723 y[1] = -x[1];
724 y[2] = -x[2];
725 y[3] = -x[3];
726 y[4] = -x[4];
727 y[5] = -x[5];
728 y[6] = -x[6];
729 y[7] = -x[7];
730 y[8] = -x[8];
731 y[9] = -x[9];
732 y[10] = -x[10];
733 y[11] = -x[11];
734 y[12] = -x[12];
735 y[13] = -x[13];
736}

◆ INeg14() [2/2]

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

在文件 i_blas.h536 行定义.

536 {
537 x[0] = -x[0];
538 x[1] = -x[1];
539 x[2] = -x[2];
540 x[3] = -x[3];
541 x[4] = -x[4];
542 x[5] = -x[5];
543 x[6] = -x[6];
544 x[7] = -x[7];
545 x[8] = -x[8];
546 x[9] = -x[9];
547 x[10] = -x[10];
548 x[11] = -x[11];
549 x[12] = -x[12];
550 x[13] = -x[13];
551}

◆ INeg15() [1/2]

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

在文件 i_blas.h738 行定义.

738 {
739 y[0] = -x[0];
740 y[1] = -x[1];
741 y[2] = -x[2];
742 y[3] = -x[3];
743 y[4] = -x[4];
744 y[5] = -x[5];
745 y[6] = -x[6];
746 y[7] = -x[7];
747 y[8] = -x[8];
748 y[9] = -x[9];
749 y[10] = -x[10];
750 y[11] = -x[11];
751 y[12] = -x[12];
752 y[13] = -x[13];
753 y[14] = -x[14];
754}

◆ INeg15() [2/2]

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

在文件 i_blas.h553 行定义.

553 {
554 x[0] = -x[0];
555 x[1] = -x[1];
556 x[2] = -x[2];
557 x[3] = -x[3];
558 x[4] = -x[4];
559 x[5] = -x[5];
560 x[6] = -x[6];
561 x[7] = -x[7];
562 x[8] = -x[8];
563 x[9] = -x[9];
564 x[10] = -x[10];
565 x[11] = -x[11];
566 x[12] = -x[12];
567 x[13] = -x[13];
568 x[14] = -x[14];
569}

◆ INeg16() [1/2]

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

在文件 i_blas.h756 行定义.

756 {
757 y[0] = -x[0];
758 y[1] = -x[1];
759 y[2] = -x[2];
760 y[3] = -x[3];
761 y[4] = -x[4];
762 y[5] = -x[5];
763 y[6] = -x[6];
764 y[7] = -x[7];
765 y[8] = -x[8];
766 y[9] = -x[9];
767 y[10] = -x[10];
768 y[11] = -x[11];
769 y[12] = -x[12];
770 y[13] = -x[13];
771 y[14] = -x[14];
772 y[15] = -x[15];
773}

◆ INeg16() [2/2]

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

在文件 i_blas.h571 行定义.

571 {
572 x[0] = -x[0];
573 x[1] = -x[1];
574 x[2] = -x[2];
575 x[3] = -x[3];
576 x[4] = -x[4];
577 x[5] = -x[5];
578 x[6] = -x[6];
579 x[7] = -x[7];
580 x[8] = -x[8];
581 x[9] = -x[9];
582 x[10] = -x[10];
583 x[11] = -x[11];
584 x[12] = -x[12];
585 x[13] = -x[13];
586 x[14] = -x[14];
587 x[15] = -x[15];
588}

◆ INeg2() [1/2]

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

在文件 i_blas.h595 行定义.

595 {
596 y[0] = -x[0];
597 y[1] = -x[1];
598}

◆ INeg2() [2/2]

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

在文件 i_blas.h410 行定义.

410 {
411 x[0] = -x[0];
412 x[1] = -x[1];
413}

◆ INeg3() [1/2]

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

在文件 i_blas.h600 行定义.

600 {
601 y[0] = -x[0];
602 y[1] = -x[1];
603 y[2] = -x[2];
604}

◆ INeg3() [2/2]

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

在文件 i_blas.h415 行定义.

415 {
416 x[0] = -x[0];
417 x[1] = -x[1];
418 x[2] = -x[2];
419}

◆ INeg4() [1/2]

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

在文件 i_blas.h606 行定义.

606 {
607 y[0] = -x[0];
608 y[1] = -x[1];
609 y[2] = -x[2];
610 y[3] = -x[3];
611}

◆ INeg4() [2/2]

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

在文件 i_blas.h421 行定义.

421 {
422 x[0] = -x[0];
423 x[1] = -x[1];
424 x[2] = -x[2];
425 x[3] = -x[3];
426}

◆ INeg5() [1/2]

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

在文件 i_blas.h613 行定义.

613 {
614 y[0] = -x[0];
615 y[1] = -x[1];
616 y[2] = -x[2];
617 y[3] = -x[3];
618 y[4] = -x[4];
619}

◆ INeg5() [2/2]

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

在文件 i_blas.h428 行定义.

428 {
429 x[0] = -x[0];
430 x[1] = -x[1];
431 x[2] = -x[2];
432 x[3] = -x[3];
433 x[4] = -x[4];
434}

◆ INeg6() [1/2]

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

在文件 i_blas.h621 行定义.

621 {
622 y[0] = -x[0];
623 y[1] = -x[1];
624 y[2] = -x[2];
625 y[3] = -x[3];
626 y[4] = -x[4];
627 y[5] = -x[5];
628}

◆ INeg6() [2/2]

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

在文件 i_blas.h436 行定义.

436 {
437 x[0] = -x[0];
438 x[1] = -x[1];
439 x[2] = -x[2];
440 x[3] = -x[3];
441 x[4] = -x[4];
442 x[5] = -x[5];
443}

◆ INeg7() [1/2]

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

在文件 i_blas.h630 行定义.

630 {
631 y[0] = -x[0];
632 y[1] = -x[1];
633 y[2] = -x[2];
634 y[3] = -x[3];
635 y[4] = -x[4];
636 y[5] = -x[5];
637 y[6] = -x[6];
638}

◆ INeg7() [2/2]

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

在文件 i_blas.h445 行定义.

445 {
446 x[0] = -x[0];
447 x[1] = -x[1];
448 x[2] = -x[2];
449 x[3] = -x[3];
450 x[4] = -x[4];
451 x[5] = -x[5];
452 x[6] = -x[6];
453}

◆ INeg8() [1/2]

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

在文件 i_blas.h640 行定义.

640 {
641 y[0] = -x[0];
642 y[1] = -x[1];
643 y[2] = -x[2];
644 y[3] = -x[3];
645 y[4] = -x[4];
646 y[5] = -x[5];
647 y[6] = -x[6];
648 y[7] = -x[7];
649}

◆ INeg8() [2/2]

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

在文件 i_blas.h455 行定义.

455 {
456 x[0] = -x[0];
457 x[1] = -x[1];
458 x[2] = -x[2];
459 x[3] = -x[3];
460 x[4] = -x[4];
461 x[5] = -x[5];
462 x[6] = -x[6];
463 x[7] = -x[7];
464}

◆ INeg9() [1/2]

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

在文件 i_blas.h651 行定义.

651 {
652 y[0] = -x[0];
653 y[1] = -x[1];
654 y[2] = -x[2];
655 y[3] = -x[3];
656 y[4] = -x[4];
657 y[5] = -x[5];
658 y[6] = -x[6];
659 y[7] = -x[7];
660 y[8] = -x[8];
661}

◆ INeg9() [2/2]

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

在文件 i_blas.h466 行定义.

466 {
467 x[0] = -x[0];
468 x[1] = -x[1];
469 x[2] = -x[2];
470 x[3] = -x[3];
471 x[4] = -x[4];
472 x[5] = -x[5];
473 x[6] = -x[6];
474 x[7] = -x[7];
475 x[8] = -x[8];
476}

◆ INegCol()

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

在文件 i_blas.h777 行定义.

777 {
778 T *ref = A;
779 for (int r = 0; r < m; ++r, ref += n) {
780 ref[c] = -ref[c];
781 }
782}

◆ IPlaneEucliToSpher()

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

在文件 i_ground.cc1717 行定义.

1718 {
1719 if (!src.IsValid()) {
1720 dst->ForceInvalid();
1721 } else {
1722 GroundPlaneLiDAR p = src;
1723 assert(p.params[2] != 0 || p.params[1] != 0);
1724 p.ForceUnitNorm(); // to be safe
1725 p.ForcePositiveNormalZ();
1726 dst->theta = IAcos(p.params[0]);
1727 dst->phi = IAtan2(p.params[1], p.params[2]);
1728 dst->d = p.params[3];
1729 dst->SetNrSupport(src.GetNrSupport());
1730 dst->SetStatus(src.GetStatus());
1731 }
1732}

◆ IPlaneFit() [1/2]

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

在文件 i_plane.h429 行定义.

429 {
430 T mat_a[9] = {X1[0], X1[1], X1[2], X2[0], X2[1], X2[2], X3[0], X3[1], X3[2]};
431 IPlaneFitTotalLeastSquare(mat_a, pi, 3);
432}

◆ IPlaneFit() [2/2]

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

在文件 i_plane.h437 行定义.

437 {
438 T mat_a[9];
439 ICopy9(Xs, mat_a);
440 IPlaneFitTotalLeastSquare(mat_a, pi, 3);
441}
void ICopy9(const T src[9], T dst[9])
Definition i_blas.h:91
void IPlaneFitTotalLeastSquare(T *X, T *pi, int n)
Definition i_plane.h:140

◆ IPlaneFitAdv()

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

在文件 i_plane.h454 行定义.

454 {
455 T mat_a[9], mat_ap[9];
456 PlanePara<T> pi;
457 ICopy9(Xs, mat_a);
458 IPlaneFitTotalLeastSquare(mat_a, pi, mat_ap, 3);
459 ICopy4(pi.p, para);
460 ICopy3(pi.t, para + 4);
461 ICopy2(pi.data_stat, para + 7);
462}
void ICopy3(const T src[3], T dst[3])
Definition i_blas.h:40
void ICopy2(const T src[2], T dst[2])
Definition i_blas.h:35
void ICopy4(const T src[4], T dst[4])
Definition i_blas.h:46

◆ IPlaneFitDestroyed()

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

在文件 i_plane.h447 行定义.

447 {
449}
void IPlaneFitTotalLeastSquare3(T *X, T *pi)
Definition i_plane.h:182

◆ IPlaneFitTotalLeastSquare() [1/4]

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

在文件 i_plane.h217 行定义.

218 {
219 IZero4(pi);
220 if (centroid != nullptr) {
221 IZero3(centroid);
222 }
223 if (err_stat != nullptr) {
224 IZero2(err_stat);
225 }
226 if (n < 3) {
227 return;
228 }
229
230 int i, j, n3 = n * 3;
231 T mat_a[9], eigv[3], mat_q[9], t[3];
232 // compute the centroid of input Data points
233 T xm = static_cast<T>(0.0);
234 T ym = static_cast<T>(0.0);
235 T zm = static_cast<T>(0.0);
236 for (i = 0, j = 0; i < n; i++) {
237 xm += X[j++];
238 ym += X[j++];
239 zm += X[j++];
240 }
241 t[0] = xm / n;
242 t[1] = ym / n;
243 t[2] = zm / n;
244 for (i = 0; i < n3; i += 3) {
245 ISub3(X + i, t, Xp + i);
246 }
247 IMultAtANx3(Xp, mat_a, n);
248 IEigSymmetric3x3Closed(mat_a, eigv, mat_q);
249 // pi's normal vector is the eigen vector of
250 // mat_a corresponding to its smallest eigen value
251 pi[0] = mat_q[2];
252 pi[1] = mat_q[5];
253 pi[2] = mat_q[8];
254 IUnitize3(pi);
255 // the optimal plane should pass [xm, ym, zm]:
256 pi[3] = -IDot3(pi, t);
257
258 if (centroid != nullptr) {
259 ICopy3(t, centroid);
260 }
261
262 // Data stat:
263 if (err_stat != nullptr) {
264 const T *cptr_data = X;
265 for (i = 0; i < n; ++i) {
266 Xp[i] = IPlaneToPointDistance(pi, cptr_data);
267 cptr_data += 3;
268 }
269 err_stat[0] = IMean(Xp, n); // mean
270 err_stat[1] = ISdv(Xp, err_stat[0], n); // sdv
271 }
272}
T IPlaneToPointDistance(const T *pi, const T *p)
Definition i_plane.h:79
T IMean(const T *x, int n)
Definition i_blas.h:2434
T ISdv(const T *x, T mean, int n)
Definition i_blas.h:2500
void IEigSymmetric3x3Closed(const T *A, T *EV, T *Q)
Definition i_util.h:56
void ISub3(const T x[3], const T y[3], T z[3])
Definition i_blas.h:1405

◆ IPlaneFitTotalLeastSquare() [2/4]

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

在文件 i_plane.h281 行定义.

281 {
282 IZero4(pi);
283 if (n < 3 || n > m) {
284 return;
285 }
286 IIndexedShuffle(X, indices, m, 3, n);
287 int i, j;
288 T mat_a[9], eigv[3], mat_q[9];
289 // compute the centroid of input Data points
290 T xm = static_cast<T>(0.0);
291 T ym = static_cast<T>(0.0);
292 T zm = static_cast<T>(0.0);
293 for (i = 0, j = 0; i < n; i++) {
294 xm += X[j++];
295 ym += X[j++];
296 zm += X[j++];
297 }
298 xm /= n;
299 ym /= n;
300 zm /= n;
301 for (i = 0, j = 0; i < n; i++) {
302 X[j++] -= xm;
303 X[j++] -= ym;
304 X[j++] -= zm;
305 }
306 IMultAtANx3(X, mat_a, n);
307 IEigSymmetric3x3Closed(mat_a, eigv, mat_q);
308 // pi's normal vector is the eigen vector of
309 // mat_a corresponding to its smallest eigen value
310 pi[0] = mat_q[2];
311 pi[1] = mat_q[5];
312 pi[2] = mat_q[8];
313 // the optimal plane should pass [xm, ym, zm]:
314 pi[3] = -(pi[0] * xm + pi[1] * ym + pi[2] * zm);
315}

◆ IPlaneFitTotalLeastSquare() [3/4]

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

在文件 i_plane.h324 行定义.

325 {
326 IZero4(pi);
327 if (n < 3 || n > m) {
328 return;
329 }
330 IIndexedShuffle(X, indices, m, 3, n);
331 int i, j;
332 T mat_a[9], eigv[3], mat_q[9];
333 // compute the centroid of input Data points
334 T xm = static_cast<T>(0.0);
335 T ym = static_cast<T>(0.0);
336 T zm = static_cast<T>(0.0);
337 for (i = 0, j = 0; i < n; i++) {
338 xm += X[j++];
339 ym += X[j++];
340 zm += X[j++];
341 }
342 xm /= n;
343 ym /= n;
344 zm /= n;
345 for (i = 0, j = 0; i < n; i++) {
346 X[j++] -= xm;
347 X[j++] -= ym;
348 X[j++] -= zm;
349 }
350 IMultAtANx3(X, mat_a, n);
351 IEigSymmetric3x3Closed(mat_a, eigv, mat_q);
352 // pi's normal vector is the eigen vector of
353 // mat_a corresponding to its smallest eigen value
354 pi[0] = mat_q[2];
355 pi[1] = mat_q[5];
356 pi[2] = mat_q[8];
357 // the optimal plane should pass [xm, ym, zm]:
358 pi[3] = -(pi[0] * xm + pi[1] * ym + pi[2] * zm);
359
360 if (centroid != nullptr) {
361 centroid[0] = xm;
362 centroid[1] = ym;
363 centroid[2] = zm;
364 }
365}

◆ IPlaneFitTotalLeastSquare() [4/4]

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

在文件 i_plane.h140 行定义.

140 {
141 IZero4(pi);
142 if (n < 3) {
143 return;
144 }
145 int i, j;
146 T mat_a[9], eigv[3], mat_q[9];
147 // compute the centroid of input Data points
148 T xm = static_cast<T>(0.0);
149 T ym = static_cast<T>(0.0);
150 T zm = static_cast<T>(0.0);
151 for (i = 0, j = 0; i < n; i++) {
152 xm += X[j++];
153 ym += X[j++];
154 zm += X[j++];
155 }
156 xm /= static_cast<T>(n);
157 ym /= static_cast<T>(n);
158 zm /= static_cast<T>(n);
159 for (i = 0, j = 0; i < n; i++) {
160 X[j++] -= xm;
161 X[j++] -= ym;
162 X[j++] -= zm;
163 }
164 IMultAtAnx3(X, mat_a, n);
165 IEigSymmetric3x3Closed(mat_a, eigv, mat_q);
166 // pi's normal vector is the eigen vector of
167 // mat_a corresponding to its smallest eigen value
168 pi[0] = mat_q[2];
169 pi[1] = mat_q[5];
170 pi[2] = mat_q[8];
171 // the optimal plane should pass [xm, ym, zm]:
172 pi[3] = -(pi[0] * xm + pi[1] * ym + pi[2] * zm);
173}

◆ IPlaneFitTotalLeastSquare3()

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

在文件 i_plane.h182 行定义.

182 {
183 T mat_a[9];
184 T eigv[3];
185 T mat_q[9];
186 // compute the centroid of input Data points
187 IZero4(pi);
188 T xm = (X[0] + X[3] + X[6]) / 3;
189 T ym = (X[1] + X[4] + X[7]) / 3;
190 T zm = (X[2] + X[5] + X[8]) / 3;
191 X[0] -= xm;
192 X[1] -= ym;
193 X[2] -= zm;
194 X[3] -= xm;
195 X[4] -= ym;
196 X[5] -= zm;
197 X[6] -= xm;
198 X[7] -= ym;
199 X[8] -= zm;
200 IMultAtA3x3(X, mat_a);
201 IEigSymmetric3x3Closed(mat_a, eigv, mat_q);
202 // pi's normal vector is the eigen vector of
203 // mat_a corresponding to its smallest eigen value
204 pi[0] = mat_q[2];
205 pi[1] = mat_q[5];
206 pi[2] = mat_q[8];
207 // the optimal plane should pass [xm, ym, zm]:
208 pi[3] = -(pi[0] * xm + pi[1] * ym + pi[2] * zm);
209}
void IMultAtA3x3(const T A[9], T AtA[9])
Definition i_blas.h:4830

◆ IPlaneFitTotalLeastSquareAdv()

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

在文件 i_plane.h372 行定义.

373 {
374 IZero9(para);
375 if (n < 3 || n > m) {
376 return;
377 }
378 int i, j;
379 T *xp = IAlloc<T>(n * 3);
380 for (i = 0; i < n; i++) {
381 j = indices[i];
382 ICopy3(X + j * 3, xp + i * 3);
383 }
384 T mat_a[9], eigv[3], mat_q[9];
385 // compute the centroid of input Data points
386 T xm = static_cast<T>(0.0);
387 T ym = static_cast<T>(0.0);
388 T zm = static_cast<T>(0.0);
389 for (i = 0, j = 0; i < n; i++) {
390 xm += xp[j++];
391 ym += xp[j++];
392 zm += xp[j++];
393 }
394 xm /= n;
395 ym /= n;
396 zm /= n;
397 for (i = 0, j = 0; i < n; i++) {
398 xp[j++] -= xm;
399 xp[j++] -= ym;
400 xp[j++] -= zm;
401 }
402 IMultAtANx3(xp, mat_a, n);
403 IEigSymmetric3x3Closed(mat_a, eigv, mat_q);
404 // pi's normal vector is the eigen vector of
405 // mat_a corresponding to its smallest eigen value
406 para[0] = mat_q[2];
407 para[1] = mat_q[5];
408 para[2] = mat_q[8];
409 IUnitize3(para);
410 // the optimal plane should pass [xm, ym, zm]:
411 para[4] = xm;
412 para[5] = ym;
413 para[6] = zm;
414 para[3] = -IDot3(para, para + 4);
415 // Data stat:
416
417 for (i = 0; i < n; ++i) {
418 j = indices[i];
419 xp[i] = IPlaneToPointDistance(para, X + j * 3);
420 }
421 para[7] = IMean(xp, n);
422 para[8] = ISdv(xp, para[7], n);
423 IFree<T>(&xp);
424}

◆ IPlaneSpherToEucli()

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

在文件 i_ground.cc1734 行定义.

1735 {
1736 if (!src.IsValid()) {
1737 dst->ForceInvalid();
1738 } else {
1739 // assume positive nz;
1740 // ny = nz * ny_over_nz;
1741 // nx * nx + ny * ny + nz * nz = 1.0;
1742 // nz^2 + nz^2*ny_over_nz^2 = 1 - nx^2;
1743 // nz^2(1 + ny_over_nz^2) = 1 - nx^2;
1744 // nz = sqrt((1-nx^2)/(1 + ny_over_nz^2))
1745 // nz is positive, guaranteed
1746 float nx = ICos(src.theta);
1747 float ny_over_nz = ITan(src.phi);
1748 float nz = ISqrt((1 - nx * nx) / (1 + ny_over_nz * ny_over_nz));
1749 float ny = nz * ny_over_nz;
1750 dst->params[0] = nx;
1751 dst->params[1] = ny;
1752 dst->params[2] = nz;
1753 dst->params[3] = src.d;
1754 dst->SetNrSupport(src.GetNrSupport());
1755 dst->SetStatus(src.GetStatus());
1756 }
1757}

◆ IPlaneToPlaneNormalDeltaDegreeZUp()

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

在文件 i_plane.h115 行定义.

115 {
116 T normal_p[3], normal_q[3];
117 ICopy3(pi_p, normal_p);
118 ICopy3(pi_q, normal_q);
119
120 // Z is up
121 if (normal_p[2] < static_cast<T>(0.0)) {
122 INeg3(normal_p);
123 }
124 if (normal_q[2] < static_cast<T>(0.0)) {
125 INeg3(normal_q);
126 }
127
128 IScale3(normal_p, IRec(ISqrt(IQquaresum3(normal_p)))); // normalize
129 IScale3(normal_q, IRec(ISqrt(IQquaresum3(normal_q)))); // normalize
130 return IRadiansToDegree(IAcos(IDot3(normal_p, normal_q)));
131}

◆ IPlaneToPointDistance() [1/2]

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

在文件 i_plane.h79 行定义.

79 {
80 return IDiv(IAbs(IDot3(pi, p) + pi[3]), IL2Norm3(pi));
81}
T IL2Norm3(const T x[3])
Definition i_blas.h:2812

◆ IPlaneToPointDistance() [2/2]

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

在文件 i_plane.h86 行定义.

86 {
87 return IDiv(IAbs(IDot3(pi, p) + pi[3]), l2_norm3_pi);
88}

◆ IPlaneToPointDistanceWNormalizedPlaneNorm()

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

在文件 i_plane.h109 行定义.

109 {
110 return IAbs(IDot3(pi, p) + pi[3]);
111}

◆ IPlaneToPointDistanceWUnitNorm()

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

在文件 i_plane.h93 行定义.

93 {
94 return IAbs(IDot3(pi, p) + pi[3]);
95}

◆ IPlaneToPointSignedDistanceWUnitNorm()

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

在文件 i_plane.h102 行定义.

102 {
103 return IDot3(pi, p) + pi[3];
104}

◆ IPointInFrontOfCamera()

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

在文件 i_util.h150 行定义.

150 {
151 T Xmcop[3], v_norm;
152 ISub3(X, cop, Xmcop);
153 v_norm = IL2Norm3(Xmcop);
154 if (v_norm == static_cast<T>(0.0)) {
155 return false; // X is the cop
156 }
157 IScale3(Xmcop, IRec(v_norm));
158 return IDot3(Xmcop, prv) > static_cast<T>(0.0);
159}

◆ IPointOnPlaneProjection()

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

在文件 i_plane.h65 行定义.

65 {
66 T npi[4];
67 ICopy4(pi, npi);
68 T sf = IRec(IL2Norm3(npi));
69 IScale4(npi, sf); // plane with unit norm
70 sf = -(IDot3(npi, p) + npi[3]);
71 q[0] = p[0] + sf * npi[0];
72 q[1] = p[1] + sf * npi[1];
73 q[2] = p[2] + sf * npi[2];
74}

◆ IPow() [1/6]

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

在文件 i_basic.h150 行定义.

150{ return pow(a, b); }

◆ IPow() [2/6]

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

在文件 i_basic.h151 行定义.

151{ return pow(a, static_cast<double>(b)); }

◆ IPow() [3/6]

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

在文件 i_basic.h142 行定义.

142{ return powf(a, b); }

◆ IPow() [4/6]

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

在文件 i_basic.h143 行定义.

143{ return powf(a, static_cast<float>(b)); }

◆ IPow() [5/6]

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

在文件 i_basic.h144 行定义.

144 {
145 return pow(static_cast<double>(a), static_cast<double>(b));
146}

◆ IPow() [6/6]

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

在文件 i_basic.h147 行定义.

147 {
148 return pow(static_cast<double>(a), static_cast<double>(b));
149}

◆ IProjectThroughExtrinsic()

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

在文件 i_util.h103 行定义.

103 {
104 IMultAx3x3(R, X, x);
105 IAdd3(t, x);
106}
void IMultAx3x3(const T A[9], const T x[3], T Ax[3])
Definition i_blas.h:4358

◆ IProjectThroughIntrinsic()

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

在文件 i_util.h111 行定义.

111 {
112 x[0] = K[0] * X[0] + K[1] * X[1] + K[2] * X[2];
113 x[1] = K[4] * X[1] + K[5] * X[2];
114 x[2] = X[2];
115}

◆ IProjectThroughKRt()

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

在文件 i_util.h121 行定义.

122 {
123 T Rtx[3];
124 IProjectThroughExtrinsic(R, t, X, Rtx);
125 IProjectThroughIntrinsic(K, Rtx, x);
126}
void IProjectThroughExtrinsic(const T *R, const T *t, const T *X, T *x)
Definition i_util.h:103
void IProjectThroughIntrinsic(const T *K, const T *X, T *x)
Definition i_util.h:111

◆ IRadiansToDegree() [1/2]

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

在文件 i_basic.h263 行定义.

263 {
265}

◆ IRadiansToDegree() [2/2]

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

在文件 i_basic.h260 行定义.

260 {
262}

◆ IRamp()

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

在文件 i_basic.h504 行定义.

504 {
505 for (int i = 0; i < n; i++) {
506 a[i] = static_cast<T>(i);
507 }
508}

◆ IRandCoreD()

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

在文件 i_rand.h27 行定义.

27 {
28 int a;
29 a = *s / 127773;
30 *s = 16807 * (*s - a * 127773) - 2836 * a;
31 if (*s < 0) {
32 *s += 2147483647;
33 }
34 return ((1.0 / (static_cast<double>(2147483647))) * (*s));
35}

◆ IRandI()

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

在文件 i_rand.h39 行定义.

39 {
40 return (IIntervalHalfopen<int>(static_cast<int>(IRandCoreD(s) * pool_size), 0,
41 pool_size));
42}
double IRandCoreD(int *s)
Definition i_rand.h:27

◆ IRandomizedShuffle() [1/2]

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

在文件 i_rand.h78 行定义.

78 {
79 if (A == reinterpret_cast<T *>(NULL) || n <= 1 || l < 1) {
80 return;
81 }
82 int i, r;
83 for (i = n - 1; i > 0; i--) {
84 r = IRandI(i + 1, s); // pick a random index from 0 to i
85 ISwap(A + r * l, A + i * l, l);
86 }
87}

◆ IRandomizedShuffle() [2/2]

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

在文件 i_rand.h94 行定义.

94 {
95 if (A == reinterpret_cast<T *>(NULL) || B == reinterpret_cast<T *>(NULL) ||
96 n <= 1 || la < 1 || lb < 1) {
97 return;
98 }
99 int i, r;
100 for (i = n - 1; i > 0; i--) {
101 r = IRandI(i + 1, s); /*pick a random index from 0 to i*/
102 ISwap(A + r * la, A + i * la, la);
103 ISwap(B + r * lb, B + i * lb, lb);
104 }
105}

◆ IRandomizedShuffle1()

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

在文件 i_rand.h110 行定义.

110 {
111 if (A == reinterpret_cast<T *>(NULL) || n <= 1) {
112 return;
113 }
114 int i, r;
115 for (i = n - 1; i > 0; i--) {
116 // pick a random index from 0 to i
117 r = IRandI(i + 1, s);
118 ISwap(A[r], A[i]);
119 }
120}

◆ IRandomSample()

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

在文件 i_rand.h47 行定义.

47 {
48 int temp, curr;
49 if (pool_size < n) {
50 for (int i = 0; i < n; i++) {
51 sample[i] = IRandI(pool_size, s);
52 }
53 } else {
54 for (int i = 0; i < n; i++) {
55 // generate integer for an integer pool that descreases with i
56 temp = IRandI(pool_size - i, s);
57 // go through previous storted integers, if smaller, store, and move the
58 // rest of the array one step. if larger or equal, increase by 1 and go
59 // to the next. This ensures even distribution
60 for (int j = 0; j < i; j++) {
61 curr = sample[j];
62 if (temp < curr) {
63 sample[j] = temp;
64 temp = curr;
65 } else {
66 temp++;
67 }
68 }
69 // store the final integer
70 sample[i] = temp;
71 }
72 }
73}
int IRandI(int pool_size, int *s)
Definition i_rand.h:39

◆ IRansacTrials()

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

在文件 i_ransac.h30 行定义.

31 {
32 return inlierprob > 0.0
33 ? IRound(IDiv(ILog(1.0 - confidence),
34 ILog(1.0 - IPow(inlierprob, sample_size))))
35 : std::numeric_limits<int>::max();
36}
Definition future.h:29

◆ IRec() [1/4]

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

在文件 i_basic.h72 行定义.

72{ return ((a != 0.0) ? ((1.0) / a) : 1.0); }

◆ IRec() [2/4]

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

在文件 i_basic.h69 行定义.

69{ return ((a != 0.0f) ? ((1.0f) / a) : 1.0f); }

◆ IRec() [3/4]

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

在文件 i_basic.h70 行定义.

70{ return ((a != 0) ? ((1.0) / a) : 1.0); }

◆ IRec() [4/4]

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

在文件 i_basic.h71 行定义.

71{ return ((a != 0) ? ((1.0) / a) : 1.0); }

◆ IRound() [1/3]

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

在文件 i_basic.h202 行定义.

202 {
203 return ((a >= 0.0) ? (static_cast<int>(a + 0.5))
204 : (static_cast<int>(a - 0.5)));
205}

◆ IRound() [2/3]

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

在文件 i_basic.h198 行定义.

198 {
199 return ((a >= 0.f) ? (static_cast<int>(a + 0.5f))
200 : (static_cast<int>(a - 0.5f)));
201}

◆ IRound() [3/3]

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

在文件 i_basic.h197 行定义.

197{ return (a); }

◆ ISafeUnitize() [1/4]

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

在文件 i_blas.h2933 行定义.

2933 {
2934 double norm = IL2Norm(x, n);
2936 IFill(y, n, IRec(ISqrt(n)));
2937 } else {
2938 IScale(x, y, n, 1.0 / norm);
2939 }
2940}
void IFill(T *a, int n, T val)
Definition i_blas.h:242

◆ ISafeUnitize() [2/4]

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

在文件 i_blas.h2909 行定义.

2909 {
2910 double norm = IL2Norm(x, n);
2912 IFill(x, n, IRec(ISqrt(n)));
2913 } else {
2914 IScale(x, n, 1.0 / norm);
2915 }
2916}

◆ ISafeUnitize() [3/4]

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

在文件 i_blas.h2941 行定义.

2941 {
2942 float norm = IL2Norm(x, n);
2944 IFill(y, n, static_cast<float>(IRec(ISqrt(n))));
2945 } else {
2946 IScale(x, y, n, static_cast<float>(1.0) / norm);
2947 }
2948}

◆ ISafeUnitize() [4/4]

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

在文件 i_blas.h2917 行定义.

2917 {
2918 float norm = IL2Norm(x, n);
2920 IFill(x, n, static_cast<float>(IRec(ISqrt(n))));
2921 } else {
2922 IScale(x, n, static_cast<float>(1.0) / norm);
2923 }
2924}

◆ IScale() [1/2]

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

在文件 i_blas.h2045 行定义.

2045 {
2046 for (int i = 0; i < n; i++) {
2047 y[i] = x[i] * sf;
2048 }
2049}

◆ IScale() [2/2]

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

在文件 i_blas.h1853 行定义.

1853 {
1854 for (int i = 0; i < n; i++) {
1855 x[i] *= sf;
1856 }
1857}

◆ IScale1() [1/2]

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

在文件 i_blas.h2051 行定义.

2051 {
2052 y[0] = x[0] * sf;
2053}

◆ IScale1() [2/2]

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

在文件 i_blas.h1859 行定义.

1859 {
1860 x[0] *= sf;
1861}

◆ IScale10() [1/2]

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

在文件 i_blas.h2123 行定义.

2123 {
2124 y[0] = x[0] * sf;
2125 y[1] = x[1] * sf;
2126 y[2] = x[2] * sf;
2127 y[3] = x[3] * sf;
2128 y[4] = x[4] * sf;
2129 y[5] = x[5] * sf;
2130 y[6] = x[6] * sf;
2131 y[7] = x[7] * sf;
2132 y[8] = x[8] * sf;
2133 y[9] = x[9] * sf;
2134}

◆ IScale10() [2/2]

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

在文件 i_blas.h1931 行定义.

1931 {
1932 x[0] *= sf;
1933 x[1] *= sf;
1934 x[2] *= sf;
1935 x[3] *= sf;
1936 x[4] *= sf;
1937 x[5] *= sf;
1938 x[6] *= sf;
1939 x[7] *= sf;
1940 x[8] *= sf;
1941 x[9] *= sf;
1942}

◆ IScale11() [1/2]

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

在文件 i_blas.h2136 行定义.

2136 {
2137 y[0] = x[0] * sf;
2138 y[1] = x[1] * sf;
2139 y[2] = x[2] * sf;
2140 y[3] = x[3] * sf;
2141 y[4] = x[4] * sf;
2142 y[5] = x[5] * sf;
2143 y[6] = x[6] * sf;
2144 y[7] = x[7] * sf;
2145 y[8] = x[8] * sf;
2146 y[9] = x[9] * sf;
2147 y[10] = x[10] * sf;
2148}

◆ IScale11() [2/2]

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

在文件 i_blas.h1944 行定义.

1944 {
1945 x[0] *= sf;
1946 x[1] *= sf;
1947 x[2] *= sf;
1948 x[3] *= sf;
1949 x[4] *= sf;
1950 x[5] *= sf;
1951 x[6] *= sf;
1952 x[7] *= sf;
1953 x[8] *= sf;
1954 x[9] *= sf;
1955 x[10] *= sf;
1956}

◆ IScale12() [1/2]

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

在文件 i_blas.h2150 行定义.

2150 {
2151 y[0] = x[0] * sf;
2152 y[1] = x[1] * sf;
2153 y[2] = x[2] * sf;
2154 y[3] = x[3] * sf;
2155 y[4] = x[4] * sf;
2156 y[5] = x[5] * sf;
2157 y[6] = x[6] * sf;
2158 y[7] = x[7] * sf;
2159 y[8] = x[8] * sf;
2160 y[9] = x[9] * sf;
2161 y[10] = x[10] * sf;
2162 y[11] = x[11] * sf;
2163}

◆ IScale12() [2/2]

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

在文件 i_blas.h1958 行定义.

1958 {
1959 x[0] *= sf;
1960 x[1] *= sf;
1961 x[2] *= sf;
1962 x[3] *= sf;
1963 x[4] *= sf;
1964 x[5] *= sf;
1965 x[6] *= sf;
1966 x[7] *= sf;
1967 x[8] *= sf;
1968 x[9] *= sf;
1969 x[10] *= sf;
1970 x[11] *= sf;
1971}

◆ IScale13() [1/2]

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

在文件 i_blas.h2165 行定义.

2165 {
2166 y[0] = x[0] * sf;
2167 y[1] = x[1] * sf;
2168 y[2] = x[2] * sf;
2169 y[3] = x[3] * sf;
2170 y[4] = x[4] * sf;
2171 y[5] = x[5] * sf;
2172 y[6] = x[6] * sf;
2173 y[7] = x[7] * sf;
2174 y[8] = x[8] * sf;
2175 y[9] = x[9] * sf;
2176 y[10] = x[10] * sf;
2177 y[11] = x[11] * sf;
2178 y[12] = x[12] * sf;
2179}

◆ IScale13() [2/2]

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

在文件 i_blas.h1973 行定义.

1973 {
1974 x[0] *= sf;
1975 x[1] *= sf;
1976 x[2] *= sf;
1977 x[3] *= sf;
1978 x[4] *= sf;
1979 x[5] *= sf;
1980 x[6] *= sf;
1981 x[7] *= sf;
1982 x[8] *= sf;
1983 x[9] *= sf;
1984 x[10] *= sf;
1985 x[11] *= sf;
1986 x[12] *= sf;
1987}

◆ IScale14() [1/2]

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

在文件 i_blas.h2181 行定义.

2181 {
2182 y[0] = x[0] * sf;
2183 y[1] = x[1] * sf;
2184 y[2] = x[2] * sf;
2185 y[3] = x[3] * sf;
2186 y[4] = x[4] * sf;
2187 y[5] = x[5] * sf;
2188 y[6] = x[6] * sf;
2189 y[7] = x[7] * sf;
2190 y[8] = x[8] * sf;
2191 y[9] = x[9] * sf;
2192 y[10] = x[10] * sf;
2193 y[11] = x[11] * sf;
2194 y[12] = x[12] * sf;
2195 y[13] = x[13] * sf;
2196}

◆ IScale14() [2/2]

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

在文件 i_blas.h1989 行定义.

1989 {
1990 x[0] *= sf;
1991 x[1] *= sf;
1992 x[2] *= sf;
1993 x[3] *= sf;
1994 x[4] *= sf;
1995 x[5] *= sf;
1996 x[6] *= sf;
1997 x[7] *= sf;
1998 x[8] *= sf;
1999 x[9] *= sf;
2000 x[10] *= sf;
2001 x[11] *= sf;
2002 x[12] *= sf;
2003 x[13] *= sf;
2004}

◆ IScale15() [1/2]

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

在文件 i_blas.h2198 行定义.

2198 {
2199 y[0] = x[0] * sf;
2200 y[1] = x[1] * sf;
2201 y[2] = x[2] * sf;
2202 y[3] = x[3] * sf;
2203 y[4] = x[4] * sf;
2204 y[5] = x[5] * sf;
2205 y[6] = x[6] * sf;
2206 y[7] = x[7] * sf;
2207 y[8] = x[8] * sf;
2208 y[9] = x[9] * sf;
2209 y[10] = x[10] * sf;
2210 y[11] = x[11] * sf;
2211 y[12] = x[12] * sf;
2212 y[13] = x[13] * sf;
2213 y[14] = x[14] * sf;
2214}

◆ IScale15() [2/2]

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

在文件 i_blas.h2006 行定义.

2006 {
2007 x[0] *= sf;
2008 x[1] *= sf;
2009 x[2] *= sf;
2010 x[3] *= sf;
2011 x[4] *= sf;
2012 x[5] *= sf;
2013 x[6] *= sf;
2014 x[7] *= sf;
2015 x[8] *= sf;
2016 x[9] *= sf;
2017 x[10] *= sf;
2018 x[11] *= sf;
2019 x[12] *= sf;
2020 x[13] *= sf;
2021 x[14] *= sf;
2022}

◆ IScale16() [1/2]

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

在文件 i_blas.h2216 行定义.

2216 {
2217 y[0] = x[0] * sf;
2218 y[1] = x[1] * sf;
2219 y[2] = x[2] * sf;
2220 y[3] = x[3] * sf;
2221 y[4] = x[4] * sf;
2222 y[5] = x[5] * sf;
2223 y[6] = x[6] * sf;
2224 y[7] = x[7] * sf;
2225 y[8] = x[8] * sf;
2226 y[9] = x[9] * sf;
2227 y[10] = x[10] * sf;
2228 y[11] = x[11] * sf;
2229 y[12] = x[12] * sf;
2230 y[13] = x[13] * sf;
2231 y[14] = x[14] * sf;
2232 y[15] = x[15] * sf;
2233}

◆ IScale16() [2/2]

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

在文件 i_blas.h2024 行定义.

2024 {
2025 x[0] *= sf;
2026 x[1] *= sf;
2027 x[2] *= sf;
2028 x[3] *= sf;
2029 x[4] *= sf;
2030 x[5] *= sf;
2031 x[6] *= sf;
2032 x[7] *= sf;
2033 x[8] *= sf;
2034 x[9] *= sf;
2035 x[10] *= sf;
2036 x[11] *= sf;
2037 x[12] *= sf;
2038 x[13] *= sf;
2039 x[14] *= sf;
2040 x[15] *= sf;
2041}

◆ IScale2() [1/2]

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

在文件 i_blas.h2055 行定义.

2055 {
2056 y[0] = x[0] * sf;
2057 y[1] = x[1] * sf;
2058}

◆ IScale2() [2/2]

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

在文件 i_blas.h1863 行定义.

1863 {
1864 x[0] *= sf;
1865 x[1] *= sf;
1866}

◆ IScale3() [1/2]

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

在文件 i_blas.h2060 行定义.

2060 {
2061 y[0] = x[0] * sf;
2062 y[1] = x[1] * sf;
2063 y[2] = x[2] * sf;
2064}

◆ IScale3() [2/2]

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

在文件 i_blas.h1868 行定义.

1868 {
1869 x[0] *= sf;
1870 x[1] *= sf;
1871 x[2] *= sf;
1872}

◆ IScale4() [1/2]

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

在文件 i_blas.h2066 行定义.

2066 {
2067 y[0] = x[0] * sf;
2068 y[1] = x[1] * sf;
2069 y[2] = x[2] * sf;
2070 y[3] = x[3] * sf;
2071}

◆ IScale4() [2/2]

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

在文件 i_blas.h1874 行定义.

1874 {
1875 x[0] *= sf;
1876 x[1] *= sf;
1877 x[2] *= sf;
1878 x[3] *= sf;
1879}

◆ IScale5() [1/2]

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

在文件 i_blas.h2073 行定义.

2073 {
2074 y[0] = x[0] * sf;
2075 y[1] = x[1] * sf;
2076 y[2] = x[2] * sf;
2077 y[3] = x[3] * sf;
2078 y[4] = x[4] * sf;
2079}

◆ IScale5() [2/2]

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

在文件 i_blas.h1881 行定义.

1881 {
1882 x[0] *= sf;
1883 x[1] *= sf;
1884 x[2] *= sf;
1885 x[3] *= sf;
1886 x[4] *= sf;
1887}

◆ IScale6() [1/2]

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

在文件 i_blas.h2081 行定义.

2081 {
2082 y[0] = x[0] * sf;
2083 y[1] = x[1] * sf;
2084 y[2] = x[2] * sf;
2085 y[3] = x[3] * sf;
2086 y[4] = x[4] * sf;
2087 y[5] = x[5] * sf;
2088}

◆ IScale6() [2/2]

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

在文件 i_blas.h1889 行定义.

1889 {
1890 x[0] *= sf;
1891 x[1] *= sf;
1892 x[2] *= sf;
1893 x[3] *= sf;
1894 x[4] *= sf;
1895 x[5] *= sf;
1896}

◆ IScale7() [1/2]

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

在文件 i_blas.h2090 行定义.

2090 {
2091 y[0] = x[0] * sf;
2092 y[1] = x[1] * sf;
2093 y[2] = x[2] * sf;
2094 y[3] = x[3] * sf;
2095 y[4] = x[4] * sf;
2096 y[5] = x[5] * sf;
2097 y[6] = x[6] * sf;
2098}

◆ IScale7() [2/2]

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

在文件 i_blas.h1898 行定义.

1898 {
1899 x[0] *= sf;
1900 x[1] *= sf;
1901 x[2] *= sf;
1902 x[3] *= sf;
1903 x[4] *= sf;
1904 x[5] *= sf;
1905 x[6] *= sf;
1906}

◆ IScale8() [1/2]

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

在文件 i_blas.h2100 行定义.

2100 {
2101 y[0] = x[0] * sf;
2102 y[1] = x[1] * sf;
2103 y[2] = x[2] * sf;
2104 y[3] = x[3] * sf;
2105 y[4] = x[4] * sf;
2106 y[5] = x[5] * sf;
2107 y[6] = x[6] * sf;
2108 y[7] = x[7] * sf;
2109}

◆ IScale8() [2/2]

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

在文件 i_blas.h1908 行定义.

1908 {
1909 x[0] *= sf;
1910 x[1] *= sf;
1911 x[2] *= sf;
1912 x[3] *= sf;
1913 x[4] *= sf;
1914 x[5] *= sf;
1915 x[6] *= sf;
1916 x[7] *= sf;
1917}

◆ IScale9() [1/2]

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

在文件 i_blas.h2111 行定义.

2111 {
2112 y[0] = x[0] * sf;
2113 y[1] = x[1] * sf;
2114 y[2] = x[2] * sf;
2115 y[3] = x[3] * sf;
2116 y[4] = x[4] * sf;
2117 y[5] = x[5] * sf;
2118 y[6] = x[6] * sf;
2119 y[7] = x[7] * sf;
2120 y[8] = x[8] * sf;
2121}

◆ IScale9() [2/2]

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

在文件 i_blas.h1919 行定义.

1919 {
1920 x[0] *= sf;
1921 x[1] *= sf;
1922 x[2] *= sf;
1923 x[3] *= sf;
1924 x[4] *= sf;
1925 x[5] *= sf;
1926 x[6] *= sf;
1927 x[7] *= sf;
1928 x[8] *= sf;
1929}

◆ IsCamerasFieldOverlap()

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

在文件 camera_homography.cc46 行定义.

50 {
51 size_t f_width = from_camera.get_width();
52 size_t f_height = from_camera.get_height();
53 size_t to_width = to_camera.get_width();
54 size_t to_height = to_camera.get_height();
55 Eigen::Matrix3d f2t_rotation = extrinsic.topLeftCorner(3, 3);
56 Eigen::Matrix<double, 4, 2> points;
57 points << 0.0, 0.0, static_cast<double>(f_width), 0.0,
58 static_cast<double>(f_width), static_cast<double>(f_height), 0.0,
59 static_cast<double>(f_height);
60 Eigen::Vector2d pt_min(std::numeric_limits<double>::max(),
61 std::numeric_limits<double>::max());
62 Eigen::Vector2d pt_max(-std::numeric_limits<double>::max(),
63 -std::numeric_limits<double>::max());
64 Eigen::Matrix3d from_camera_intrinsic_inverse =
65 from_camera.get_intrinsic_params().cast<double>().inverse();
66 for (int i = 0; i < 4; ++i) {
67 Eigen::Vector2d point_out;
68 bool status = PointCamera1ToCamera2(
69 points.block<1, 2>(i, 0), from_camera_intrinsic_inverse,
70 to_camera.get_intrinsic_params().cast<double>(), f2t_rotation,
71 &point_out);
72 if (status) {
73 pt_min = pt_min.cwiseMin(point_out);
74 pt_max = pt_max.cwiseMax(point_out);
75 }
76 }
77 (*up_left) = pt_min.cwiseMax(Eigen::Vector2d(0, 0));
78 (*low_right) = pt_max.cwiseMin(Eigen::Vector2d(to_width, to_height));
79 if ((up_left->array() < low_right->array()).all()) {
80 return true;
81 }
82 return false;
83}
Eigen::Matrix3f get_intrinsic_params() const
Definition camera.h:62
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)

◆ ISdv()

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

在文件 i_blas.h2500 行定义.

2500 {
2501 if (n < 2) {
2502 return static_cast<T>(0.0);
2503 }
2504 T sdv = static_cast<T>(0.0);
2505 for (int i = 0; i < n; ++i) {
2506 sdv += ISqr(x[i] - mean);
2507 }
2508 return ISqrt(IDiv(sdv, n - 1));
2509}

◆ IShiftHomogeneous3()

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

在文件 i_blas.h5026 行定义.

5026 {
5027 if (n <= 1) {
5028 return;
5029 }
5030 int i, nm1 = n - 1;
5031 int dst = 2;
5032 int src = 3;
5033 for (i = 0; i < nm1; ++i) {
5034 ISwap(A[dst], A[src]);
5035 ISwap(A[dst + 1], A[src + 1]);
5036 dst += 2;
5037 src += 3;
5038 }
5039}

◆ IShiftHomogeneous4()

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

在文件 i_blas.h5047 行定义.

5047 {
5048 if (n <= 1) {
5049 return;
5050 }
5051 int i, nm1 = n - 1;
5052 int dst = 3;
5053 int src = 4;
5054 for (i = 0; i < nm1; ++i) {
5055 ISwap(A[dst], A[src]);
5056 ISwap(A[dst + 1], A[src + 1]);
5057 ISwap(A[dst + 2], A[src + 2]);
5058 dst += 3;
5059 src += 4;
5060 }
5061}

◆ ISign()

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

在文件 i_basic.h176 行定义.

176 {
177 if (a > T(0.0))
178 return (T(1.0));
179 else if (a < T(0.0))
180 return (T(-1.0));
181 else
182 return (T(0.0));
183}

◆ ISignedUnitize2()

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

在文件 i_blas.h3072 行定义.

3072 {
3073 IScale2(x, ISignNeverZero(x[1]) * IRec(IL2Norm2(x)));
3074}

◆ ISignedUnitize3()

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

在文件 i_blas.h3076 行定义.

3076 {
3077 IScale3(x, ISignNeverZero(x[2]) * IRec(IL2Norm3(x)));
3078}

◆ ISignedUnitize4()

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

在文件 i_blas.h3080 行定义.

3080 {
3081 IScale4(x, ISignNeverZero(x[3]) * IRec(IL2Norm4(x)));
3082}
T IL2Norm4(const T x[4])
Definition i_blas.h:2816

◆ ISignNeverZero()

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

在文件 i_basic.h189 行定义.

189 {
190 if (a >= T(0.0))
191 return (T(1.0));
192 else
193 return (T(-1.0));
194}

◆ ISin() [1/2]

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

在文件 i_basic.h215 行定义.

215{ return sin(alpha); }

◆ ISin() [2/2]

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

在文件 i_basic.h214 行定义.

214{ return sinf(alpha); }

◆ IsLineSegments2DIntersect()

template<typename T >
bool apollo::perception::algorithm::IsLineSegments2DIntersect ( const Eigen::Matrix< T, 2, 1 > &  p1,
const Eigen::Matrix< T, 2, 1 > &  q1,
const Eigen::Matrix< T, 2, 1 > &  p2,
const Eigen::Matrix< T, 2, 1 > &  q2 
)

在文件 common.h391 行定义.

395 {
396 // find orientation of ordered triplet (p, q, r).
397 // returns values:
398 // 0 --> p, q and r are collinear
399 // 1 --> Clockwise
400 // 2 --> Counterclockwise
401 auto find_orientation = [](const Eigen::Matrix<T, 2, 1> &p,
402 const Eigen::Matrix<T, 2, 1> &q,
403 const Eigen::Matrix<T, 2, 1> &r) -> int {
404 // comparing slopes of line segments (p, q) and (q, r)
405 // k1 = (q[1] - p[1]) / (q[0] - p[0])
406 // k2 = (r[1] - q[1]) / (r[0] - q[0])
407 // if k1 < k2, -> counterclockwise
408 // if k1 > k2, -> clockwise
409 // if k1 == k2, -> collinear
410 float ret = (q[1] - p[1]) * (r[0] - q[0]) - (q[0] - p[0]) * (r[1] - q[1]);
411 // collinear
412 if (std::fabs(ret) < std::numeric_limits<float>::epsilon()) {
413 return 0;
414 }
415 // clock or counterclock wise
416 return (ret > 0.f) ? 1 : 2;
417 };
418
419 // given three 'collinear' points p, q, r
420 // check whether point p is on line segment (q, r)
421 auto is_on_segment = [](const Eigen::Matrix<T, 2, 1> &p,
422 const Eigen::Matrix<T, 2, 1> &q,
423 const Eigen::Matrix<T, 2, 1> &r) -> bool {
424 return p[0] <= std::max(q[0], r[0])
425 && p[0] >= std::min(q[0], r[0])
426 && p[1] <= std::max(q[1], r[1])
427 && p[1] >= std::min(q[1], r[1]);
428 };
429
430 // Two line segments (p1, q1) and (p2, q2) intersect <=>
431 // (p1, q1, p2) and (p1, q1, q2) have different orientations and
432 // (p2, q2, p1) and (p2, q2, q1) have different orientations.
433 int orientation_p1_q1_p2 = find_orientation(p1, q1, p2);
434 int orientation_p1_q1_q2 = find_orientation(p1, q1, q2);
435 int orientation_p2_q2_p1 = find_orientation(p2, q2, p1);
436 int orientation_p2_q2_q1 = find_orientation(p2, q2, q1);
437 if (orientation_p1_q1_p2 != orientation_p1_q1_q2
438 && orientation_p2_q2_p1 != orientation_p2_q2_q1) {
439 return true;
440 }
441
442 // Special cases, two line segments are collinear
443 if (orientation_p1_q1_p2 == 0 && is_on_segment(p2, p1, q1)) {
444 return true;
445 }
446 if (orientation_p1_q1_q2 == 0 && is_on_segment(q2, p1, q1)) {
447 return true;
448 }
449 if (orientation_p2_q2_p1 == 0 && is_on_segment(p1, p2, q2)) {
450 return true;
451 }
452 if (orientation_p2_q2_q1 == 0 && is_on_segment(q1, p2, q2)) {
453 return true;
454 }
455 return false;
456}

◆ IsObjectBboxInRoi() [1/2]

bool apollo::perception::algorithm::IsObjectBboxInRoi ( const HdmapStructConstPtr  roi,
const ObjectConstPtr  obj 
)

在文件 roi_filter.cc59 行定义.

60 {
61 Eigen::Vector3d bbox_center = obj->center;
62 PointD ct;
63 ct.x = bbox_center[0];
64 ct.y = bbox_center[1];
65 ct.z = bbox_center[2];
66 Eigen::Vector3d bbox_dir = obj->direction.cast<double>();
67 bbox_dir(2) = 0.0;
68 if (bbox_dir.norm() < std::numeric_limits<float>::epsilon()) {
69 return IsPtInRoi(roi, ct);
70 }
71 bbox_dir.normalize();
72 Eigen::Vector3d bbox_ortho_dir =
73 Eigen::Vector3d(-bbox_dir(1), bbox_dir(0), 0.0f);
74 double bbox_length = obj->size[0];
75 double bbox_width = obj->size[1];
76 Eigen::Vector3d bbox_corners[4];
77 bbox_corners[0] = bbox_center + bbox_dir * bbox_length / 2 +
78 bbox_ortho_dir * bbox_width / 2;
79 bbox_corners[1] = bbox_center - bbox_dir * bbox_length / 2 +
80 bbox_ortho_dir * bbox_width / 2;
81 bbox_corners[2] = bbox_center + bbox_dir * bbox_length / 2 -
82 bbox_ortho_dir * bbox_width / 2;
83 bbox_corners[3] = bbox_center - bbox_dir * bbox_length / 2 -
84 bbox_ortho_dir * bbox_width / 2;
85 for (int i = 0; i < 4; ++i) {
86 PointD corner;
87 corner.x = bbox_corners[i][0];
88 corner.y = bbox_corners[i][1];
89 corner.z = bbox_corners[i][2];
90 if (IsPtInRoi(roi, corner)) {
91 return true;
92 }
93 }
94 return false;
95}
bool IsPtInRoi(const HdmapStructConstPtr roi, const PointD pt)
Definition roi_filter.cc:37

◆ IsObjectBboxInRoi() [2/2]

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

◆ IsObjectInRoi() [1/2]

bool apollo::perception::algorithm::IsObjectInRoi ( const HdmapStructConstPtr  roi,
const ObjectConstPtr  obj 
)

在文件 roi_filter.cc51 行定义.

51 {
52 PointD ct;
53 ct.x = obj->center[0];
54 ct.y = obj->center[1];
55 ct.z = obj->center[2];
56 return IsPtInRoi(roi, ct);
57}

◆ IsObjectInRoi() [2/2]

bool apollo::perception::algorithm::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::algorithm::ISolve2x2 ( const double  A[4],
const double  b[2],
double  x[2] 
)
inline

在文件 i_blas.h4176 行定义.

4176 {
4177 double d, rec;
4178 d = IDeterminant2x2(A);
4179 rec = IRec(d);
4180 x[0] = rec * (A[3] * b[0] - A[1] * b[1]);
4181 x[1] = rec * (A[0] * b[1] - A[2] * b[0]);
4182}

◆ ISolve2x2() [2/2]

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

在文件 i_blas.h4183 行定义.

4183 {
4184 float d, rec;
4185 d = IDeterminant2x2(A);
4186 rec = IRec(d);
4187 x[0] = rec * (A[3] * b[0] - A[1] * b[1]);
4188 x[1] = rec * (A[0] * b[1] - A[2] * b[0]);
4189}

◆ ISolve3x3() [1/2]

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

在文件 i_blas.h4191 行定义.

4191 {
4192 double d, rec, da0, da1, da2;
4193 d = IDeterminant3x3(A);
4194 rec = IRec(d);
4195 da0 = b[0] * (A[4] * A[8] - A[5] * A[7]) +
4196 b[1] * (A[2] * A[7] - A[1] * A[8]) + b[2] * (A[1] * A[5] - A[2] * A[4]);
4197 da1 = b[0] * (A[5] * A[6] - A[3] * A[8]) +
4198 b[1] * (A[0] * A[8] - A[2] * A[6]) + b[2] * (A[2] * A[3] - A[0] * A[5]);
4199 da2 = b[0] * (A[3] * A[7] - A[4] * A[6]) +
4200 b[1] * (A[1] * A[6] - A[0] * A[7]) + b[2] * (A[0] * A[4] - A[1] * A[3]);
4201 x[0] = da0 * rec;
4202 x[1] = da1 * rec;
4203 x[2] = da2 * rec;
4204}
double IDeterminant3x3(const double A[9])
Definition i_blas.h:3822

◆ ISolve3x3() [2/2]

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

在文件 i_blas.h4205 行定义.

4205 {
4206 float d, rec, da0, da1, da2;
4207 d = IDeterminant3x3(A);
4208 rec = IRec(d);
4209 da0 = b[0] * (A[4] * A[8] - A[5] * A[7]) +
4210 b[1] * (A[2] * A[7] - A[1] * A[8]) + b[2] * (A[1] * A[5] - A[2] * A[4]);
4211 da1 = b[0] * (A[5] * A[6] - A[3] * A[8]) +
4212 b[1] * (A[0] * A[8] - A[2] * A[6]) + b[2] * (A[2] * A[3] - A[0] * A[5]);
4213 da2 = b[0] * (A[3] * A[7] - A[4] * A[6]) +
4214 b[1] * (A[1] * A[6] - A[0] * A[7]) + b[2] * (A[0] * A[4] - A[1] * A[3]);
4215 x[0] = da0 * rec;
4216 x[1] = da1 * rec;
4217 x[2] = da2 * rec;
4218}

◆ IsPointInBBox()

template<typename PointT >
bool apollo::perception::algorithm::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 
)

在文件 common.h85 行定义.

90 {
91 using T = typename PointT::Type;
92 Eigen::Matrix<T, 3, 1> eig(point.x, point.y, point.z);
93 Eigen::Matrix<T, 3, 1> diff = eig - gnd_c;
94 T x = diff.dot(dir_x);
95 if (fabs(x) > size[0] * 0.5) {
96 return false;
97 }
98 T y = diff.dot(dir_y);
99 if (fabs(y) > size[1] * 0.5) {
100 return false;
101 }
102 T z = diff.dot(dir_z);
103 if (fabs(z) > size[2] * 0.5) {
104 return false;
105 }
106 return true;
107}

◆ IsPointXYInPolygon2DXY()

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

在文件 common.h35 行定义.

36 {
37 using Type = typename PointT::Type;
38 bool in_poly = false;
39 Type x1 = 0.0;
40 Type x2 = 0.0;
41 Type y1 = 0.0;
42 Type y2 = 0.0;
43 size_t nr_poly_points = polygon.size();
44 // start with the last point to make the check last point<->first point the
45 // first one
46 Type xold = polygon.at(nr_poly_points - 1).x;
47 Type yold = polygon.at(nr_poly_points - 1).y;
48 for (size_t i = 0; i < nr_poly_points; ++i) {
49 Type xnew = polygon.at(i).x;
50 Type ynew = polygon.at(i).y;
51 if (xnew > xold) {
52 x1 = xold;
53 x2 = xnew;
54 y1 = yold;
55 y2 = ynew;
56 } else {
57 x1 = xnew;
58 x2 = xold;
59 y1 = ynew;
60 y2 = yold;
61 }
62 // if the point is on the boundary, then it is defined as in the polygon
63 Type value = (point.y - y1) * (x2 - x1) - (y2 - y1) * (point.x - x1);
64 Type temp = std::sqrt((x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1));
65 if (temp < std::numeric_limits<Type>::epsilon()) {
66 continue;
67 }
68 Type distance = std::abs(value) / temp;
69 if (x1 <= point.x && point.x <= x2 &&
70 distance < std::numeric_limits<Type>::epsilon()) {
71 return true;
72 }
73 if ((x1 < point.x) == (point.x <= x2) && value < 0.f) {
74 in_poly = !in_poly;
75 }
76 xold = xnew;
77 yold = ynew;
78 }
79 return in_poly;
80}

◆ IsPtInRoi() [1/2]

bool apollo::perception::algorithm::IsPtInRoi ( const HdmapStructConstPtr  roi,
const PointD  pt 
)

在文件 roi_filter.cc37 行定义.

37 {
38 for (std::size_t j = 0; j < roi->road_polygons.size(); j++) {
39 if (IsPointXYInPolygon2DXY(pt, roi->road_polygons[j])) {
40 return true;
41 }
42 }
43 for (std::size_t j = 0; j < roi->junction_polygons.size(); j++) {
44 if (IsPointXYInPolygon2DXY(pt, roi->junction_polygons[j])) {
45 return true;
46 }
47 }
48 return false;
49}
bool IsPointXYInPolygon2DXY(const PointT &point, const base::PointCloud< PointT > &polygon)
Definition common.h:35

◆ IsPtInRoi() [2/2]

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

◆ ISqr() [1/6]

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

在文件 i_basic.h107 行定义.

107{ return (static_cast<int>(a) * static_cast<int>(a)); }

◆ ISqr() [2/6]

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

在文件 i_basic.h106 行定义.

106{ return (a * a); }

◆ ISqr() [3/6]

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

在文件 i_basic.h103 行定义.

103{ return (a * a); }

◆ ISqr() [4/6]

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

在文件 i_basic.h104 行定义.

104{ return (a * a); }

◆ ISqr() [5/6]

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

在文件 i_basic.h108 行定义.

108 {
109 return (static_cast<int>(a) * static_cast<int>(a));
110}

◆ ISqr() [6/6]

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

在文件 i_basic.h105 行定义.

105{ return (a * a); }

◆ ISqrSkewSymmetric3x3()

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

在文件 i_blas.h3742 行定义.

3742 {
3743 T x0_sqr = ISqr(x[0]);
3744 T x1_sqr = ISqr(x[1]);
3745 T x2_sqr = ISqr(x[2]);
3746 e_x2[0] = -(x1_sqr + x2_sqr);
3747 e_x2[1] = e_x2[3] = x[0] * x[1];
3748 e_x2[4] = -(x2_sqr + x0_sqr);
3749 e_x2[2] = e_x2[6] = x[2] * x[0];
3750 e_x2[8] = -(x0_sqr + x1_sqr);
3751 e_x2[5] = e_x2[7] = x[1] * x[2];
3752}

◆ ISqrt() [1/4]

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

在文件 i_basic.h83 行定义.

83{ return (a >= 0.0) ? (sqrt(a)) : 0.0; }

◆ ISqrt() [2/4]

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

在文件 i_basic.h76 行定义.

76{ return (a >= 0.0f) ? (sqrtf(a)) : 0.0f; }

◆ ISqrt() [3/4]

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

在文件 i_basic.h77 行定义.

77 {
78 return (a > 0) ? (sqrt(static_cast<double>(a))) : 0.0;
79}

◆ ISqrt() [4/4]

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

在文件 i_basic.h80 行定义.

80 {
81 return (a > 0) ? (sqrt(static_cast<double>(a))) : 0.0;
82}

◆ ISquaresum()

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

在文件 i_blas.h2520 行定义.

2520 {
2521 T acc = static_cast<T>(0.0);
2522 for (int i = 0; i < n; ++i) {
2523 acc += ISqr(x[i]);
2524 }
2525 return acc;
2526}

◆ ISquaresum1()

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

在文件 i_blas.h2528 行定义.

2528 {
2529 return (ISqr(x[0]));
2530}

◆ ISquaresum10()

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

在文件 i_blas.h2568 行定义.

2568 {
2569 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2570 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]));
2571}

◆ ISquaresum11()

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

在文件 i_blas.h2573 行定义.

2573 {
2574 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2575 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]) +
2576 ISqr(x[10]));
2577}

◆ ISquaresum12()

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

在文件 i_blas.h2579 行定义.

2579 {
2580 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2581 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]) +
2582 ISqr(x[10]) + ISqr(x[11]));
2583}

◆ ISquaresum13()

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

在文件 i_blas.h2585 行定义.

2585 {
2586 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2587 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]) +
2588 ISqr(x[10]) + ISqr(x[11]) + ISqr(x[12]));
2589}

◆ ISquaresum14()

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

在文件 i_blas.h2591 行定义.

2591 {
2592 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2593 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]) +
2594 ISqr(x[10]) + ISqr(x[11]) + ISqr(x[12]) + ISqr(x[13]));
2595}

◆ ISquaresum15()

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

在文件 i_blas.h2597 行定义.

2597 {
2598 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2599 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]) +
2600 ISqr(x[10]) + ISqr(x[11]) + ISqr(x[12]) + ISqr(x[13]) + ISqr(x[14]));
2601}

◆ ISquaresum16()

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

在文件 i_blas.h2603 行定义.

2603 {
2604 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2605 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]) + ISqr(x[9]) +
2606 ISqr(x[10]) + ISqr(x[11]) + ISqr(x[12]) + ISqr(x[13]) + ISqr(x[14]) +
2607 ISqr(x[15]));
2608}

◆ ISquaresum2()

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

在文件 i_blas.h2532 行定义.

2532 {
2533 return (ISqr(x[0]) + ISqr(x[1]));
2534}

◆ ISquaresum3()

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

在文件 i_blas.h2536 行定义.

2536 {
2537 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]));
2538}

◆ ISquaresum4()

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

在文件 i_blas.h2540 行定义.

2540 {
2541 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]));
2542}

◆ ISquaresum5()

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

在文件 i_blas.h2544 行定义.

2544 {
2545 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]));
2546}

◆ ISquaresum6()

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

在文件 i_blas.h2548 行定义.

2548 {
2549 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2550 ISqr(x[5]));
2551}

◆ ISquaresum7()

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

在文件 i_blas.h2553 行定义.

2553 {
2554 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2555 ISqr(x[5]) + ISqr(x[6]));
2556}

◆ ISquaresum8()

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

在文件 i_blas.h2558 行定义.

2558 {
2559 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2560 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]));
2561}

◆ ISquaresum9()

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

在文件 i_blas.h2563 行定义.

2563 {
2564 return (ISqr(x[0]) + ISqr(x[1]) + ISqr(x[2]) + ISqr(x[3]) + ISqr(x[4]) +
2565 ISqr(x[5]) + ISqr(x[6]) + ISqr(x[7]) + ISqr(x[8]));
2566}

◆ ISquaresumDiffU() [1/2]

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

在文件 i_blas.h2621 行定义.

2621 {
2622 T acc = static_cast<T>(0.0);
2623 for (int i = 0; i < n; i++) {
2624 acc += ISqr(x[i] - y[i]);
2625 }
2626 return acc;
2627}

◆ ISquaresumDiffU() [2/2]

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

在文件 i_blas.h2612 行定义.

2613 {
2614 int acc = 0;
2615 for (int i = 0; i < n; i++) {
2616 acc += ISqr(static_cast<int>(x[i]) - static_cast<int>(y[i]));
2617 }
2618 return acc;
2619}

◆ ISquaresumDiffU1()

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

在文件 i_blas.h2629 行定义.

2629 {
2630 return (ISqr(x[0] - y[0]));
2631}

◆ ISquaresumDiffU10()

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

在文件 i_blas.h2674 行定义.

2674 {
2675 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2676 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2677 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2678 ISqr(x[9] - y[9]));
2679}

◆ ISquaresumDiffU11()

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

在文件 i_blas.h2681 行定义.

2681 {
2682 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2683 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2684 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2685 ISqr(x[9] - y[9]) + ISqr(x[10] - y[10]));
2686}

◆ ISquaresumDiffU12()

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

在文件 i_blas.h2688 行定义.

2688 {
2689 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2690 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2691 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2692 ISqr(x[9] - y[9]) + ISqr(x[10] - y[10]) + ISqr(x[11] - y[11]));
2693}

◆ ISquaresumDiffU13()

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

在文件 i_blas.h2695 行定义.

2695 {
2696 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2697 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2698 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2699 ISqr(x[9] - y[9]) + ISqr(x[10] - y[10]) + ISqr(x[11] - y[11]) +
2700 ISqr(x[12] - y[12]));
2701}

◆ ISquaresumDiffU14()

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

在文件 i_blas.h2703 行定义.

2703 {
2704 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2705 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2706 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2707 ISqr(x[9] - y[9]) + ISqr(x[10] - y[10]) + ISqr(x[11] - y[11]) +
2708 ISqr(x[12] - y[12]) + ISqr(x[13] - y[13]));
2709}

◆ ISquaresumDiffU15()

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

在文件 i_blas.h2711 行定义.

2711 {
2712 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2713 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2714 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2715 ISqr(x[9] - y[9]) + ISqr(x[10] - y[10]) + ISqr(x[11] - y[11]) +
2716 ISqr(x[12] - y[12]) + ISqr(x[13] - y[13]) + ISqr(x[14] - y[14]));
2717}

◆ ISquaresumDiffU16()

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

在文件 i_blas.h2719 行定义.

2719 {
2720 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2721 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2722 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]) +
2723 ISqr(x[9] - y[9]) + ISqr(x[10] - y[10]) + ISqr(x[11] - y[11]) +
2724 ISqr(x[12] - y[12]) + ISqr(x[13] - y[13]) + ISqr(x[14] - y[14]) +
2725 ISqr(x[15] - y[15]));
2726}

◆ ISquaresumDiffU2()

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

在文件 i_blas.h2633 行定义.

2633 {
2634 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]));
2635}

◆ ISquaresumDiffU3()

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

在文件 i_blas.h2637 行定义.

2637 {
2638 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]));
2639}

◆ ISquaresumDiffU4()

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

在文件 i_blas.h2641 行定义.

2641 {
2642 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2643 ISqr(x[3] - y[3]));
2644}

◆ ISquaresumDiffU5()

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

在文件 i_blas.h2646 行定义.

2646 {
2647 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2648 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]));
2649}

◆ ISquaresumDiffU6()

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

在文件 i_blas.h2651 行定义.

2651 {
2652 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2653 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]));
2654}

◆ ISquaresumDiffU7()

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

在文件 i_blas.h2656 行定义.

2656 {
2657 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2658 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2659 ISqr(x[6] - y[6]));
2660}

◆ ISquaresumDiffU8()

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

在文件 i_blas.h2662 行定义.

2662 {
2663 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2664 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2665 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]));
2666}

◆ ISquaresumDiffU9()

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

在文件 i_blas.h2668 行定义.

2668 {
2669 return (ISqr(x[0] - y[0]) + ISqr(x[1] - y[1]) + ISqr(x[2] - y[2]) +
2670 ISqr(x[3] - y[3]) + ISqr(x[4] - y[4]) + ISqr(x[5] - y[5]) +
2671 ISqr(x[6] - y[6]) + ISqr(x[7] - y[7]) + ISqr(x[8] - y[8]));
2672}

◆ ISquaresumU()

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

在文件 i_blas.h2512 行定义.

2512 {
2513 int acc = 0;
2514 for (int i = 0; i < n; i++) {
2515 acc += ISqr(x[i]);
2516 }
2517 return (acc);
2518}

◆ ISub() [1/3]

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

在文件 i_blas.h1390 行定义.

1390 {
1391 for (int i = 0; i < n; i++) {
1392 z[i] = x[i] - y[i];
1393 }
1394}

◆ ISub() [2/3]

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

在文件 i_blas.h1582 行定义.

1582 {
1583 for (int i = 0; i < n; i++) {
1584 y[i] -= x[i];
1585 }
1586}

◆ ISub() [3/3]

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

在文件 i_blas.h1383 行定义.

1383 {
1384 for (int i = 0; i < n; i++) {
1385 x[i] -= k;
1386 }
1387}

◆ ISub1() [1/2]

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

在文件 i_blas.h1396 行定义.

1396 {
1397 z[0] = x[0] - y[0];
1398}

◆ ISub1() [2/2]

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

在文件 i_blas.h1588 行定义.

1588 {
1589 y[0] -= x[0];
1590}

◆ ISub10() [1/2]

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

在文件 i_blas.h1468 行定义.

1468 {
1469 z[0] = x[0] - y[0];
1470 z[1] = x[1] - y[1];
1471 z[2] = x[2] - y[2];
1472 z[3] = x[3] - y[3];
1473 z[4] = x[4] - y[4];
1474 z[5] = x[5] - y[5];
1475 z[6] = x[6] - y[6];
1476 z[7] = x[7] - y[7];
1477 z[8] = x[8] - y[8];
1478 z[9] = x[9] - y[9];
1479}

◆ ISub10() [2/2]

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

在文件 i_blas.h1660 行定义.

1660 {
1661 y[0] -= x[0];
1662 y[1] -= x[1];
1663 y[2] -= x[2];
1664 y[3] -= x[3];
1665 y[4] -= x[4];
1666 y[5] -= x[5];
1667 y[6] -= x[6];
1668 y[7] -= x[7];
1669 y[8] -= x[8];
1670 y[9] -= x[9];
1671}

◆ ISub11() [1/2]

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

在文件 i_blas.h1481 行定义.

1481 {
1482 z[0] = x[0] - y[0];
1483 z[1] = x[1] - y[1];
1484 z[2] = x[2] - y[2];
1485 z[3] = x[3] - y[3];
1486 z[4] = x[4] - y[4];
1487 z[5] = x[5] - y[5];
1488 z[6] = x[6] - y[6];
1489 z[7] = x[7] - y[7];
1490 z[8] = x[8] - y[8];
1491 z[9] = x[9] - y[9];
1492 z[10] = x[10] - y[10];
1493}

◆ ISub11() [2/2]

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

在文件 i_blas.h1673 行定义.

1673 {
1674 y[0] -= x[0];
1675 y[1] -= x[1];
1676 y[2] -= x[2];
1677 y[3] -= x[3];
1678 y[4] -= x[4];
1679 y[5] -= x[5];
1680 y[6] -= x[6];
1681 y[7] -= x[7];
1682 y[8] -= x[8];
1683 y[9] -= x[9];
1684 y[10] -= x[10];
1685}

◆ ISub12() [1/2]

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

在文件 i_blas.h1495 行定义.

1495 {
1496 z[0] = x[0] - y[0];
1497 z[1] = x[1] - y[1];
1498 z[2] = x[2] - y[2];
1499 z[3] = x[3] - y[3];
1500 z[4] = x[4] - y[4];
1501 z[5] = x[5] - y[5];
1502 z[6] = x[6] - y[6];
1503 z[7] = x[7] - y[7];
1504 z[8] = x[8] - y[8];
1505 z[9] = x[9] - y[9];
1506 z[10] = x[10] - y[10];
1507 z[11] = x[11] - y[11];
1508}

◆ ISub12() [2/2]

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

在文件 i_blas.h1687 行定义.

1687 {
1688 y[0] -= x[0];
1689 y[1] -= x[1];
1690 y[2] -= x[2];
1691 y[3] -= x[3];
1692 y[4] -= x[4];
1693 y[5] -= x[5];
1694 y[6] -= x[6];
1695 y[7] -= x[7];
1696 y[8] -= x[8];
1697 y[9] -= x[9];
1698 y[10] -= x[10];
1699 y[11] -= x[11];
1700}

◆ ISub13() [1/2]

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

在文件 i_blas.h1510 行定义.

1510 {
1511 z[0] = x[0] - y[0];
1512 z[1] = x[1] - y[1];
1513 z[2] = x[2] - y[2];
1514 z[3] = x[3] - y[3];
1515 z[4] = x[4] - y[4];
1516 z[5] = x[5] - y[5];
1517 z[6] = x[6] - y[6];
1518 z[7] = x[7] - y[7];
1519 z[8] = x[8] - y[8];
1520 z[9] = x[9] - y[9];
1521 z[10] = x[10] - y[10];
1522 z[11] = x[11] - y[11];
1523 z[12] = x[12] - y[12];
1524}

◆ ISub13() [2/2]

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

在文件 i_blas.h1702 行定义.

1702 {
1703 y[0] -= x[0];
1704 y[1] -= x[1];
1705 y[2] -= x[2];
1706 y[3] -= x[3];
1707 y[4] -= x[4];
1708 y[5] -= x[5];
1709 y[6] -= x[6];
1710 y[7] -= x[7];
1711 y[8] -= x[8];
1712 y[9] -= x[9];
1713 y[10] -= x[10];
1714 y[11] -= x[11];
1715 y[12] -= x[12];
1716}

◆ ISub14() [1/2]

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

在文件 i_blas.h1526 行定义.

1526 {
1527 z[0] = x[0] - y[0];
1528 z[1] = x[1] - y[1];
1529 z[2] = x[2] - y[2];
1530 z[3] = x[3] - y[3];
1531 z[4] = x[4] - y[4];
1532 z[5] = x[5] - y[5];
1533 z[6] = x[6] - y[6];
1534 z[7] = x[7] - y[7];
1535 z[8] = x[8] - y[8];
1536 z[9] = x[9] - y[9];
1537 z[10] = x[10] - y[10];
1538 z[11] = x[11] - y[11];
1539 z[12] = x[12] - y[12];
1540 z[13] = x[13] - y[13];
1541}

◆ ISub14() [2/2]

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

在文件 i_blas.h1718 行定义.

1718 {
1719 y[0] -= x[0];
1720 y[1] -= x[1];
1721 y[2] -= x[2];
1722 y[3] -= x[3];
1723 y[4] -= x[4];
1724 y[5] -= x[5];
1725 y[6] -= x[6];
1726 y[7] -= x[7];
1727 y[8] -= x[8];
1728 y[9] -= x[9];
1729 y[10] -= x[10];
1730 y[11] -= x[11];
1731 y[12] -= x[12];
1732 y[13] -= x[13];
1733}

◆ ISub15() [1/2]

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

在文件 i_blas.h1543 行定义.

1543 {
1544 z[0] = x[0] - y[0];
1545 z[1] = x[1] - y[1];
1546 z[2] = x[2] - y[2];
1547 z[3] = x[3] - y[3];
1548 z[4] = x[4] - y[4];
1549 z[5] = x[5] - y[5];
1550 z[6] = x[6] - y[6];
1551 z[7] = x[7] - y[7];
1552 z[8] = x[8] - y[8];
1553 z[9] = x[9] - y[9];
1554 z[10] = x[10] - y[10];
1555 z[11] = x[11] - y[11];
1556 z[12] = x[12] - y[12];
1557 z[13] = x[13] - y[13];
1558 z[14] = x[14] - y[14];
1559}

◆ ISub15() [2/2]

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

在文件 i_blas.h1735 行定义.

1735 {
1736 y[0] -= x[0];
1737 y[1] -= x[1];
1738 y[2] -= x[2];
1739 y[3] -= x[3];
1740 y[4] -= x[4];
1741 y[5] -= x[5];
1742 y[6] -= x[6];
1743 y[7] -= x[7];
1744 y[8] -= x[8];
1745 y[9] -= x[9];
1746 y[10] -= x[10];
1747 y[11] -= x[11];
1748 y[12] -= x[12];
1749 y[13] -= x[13];
1750 y[14] -= x[14];
1751}

◆ ISub16() [1/2]

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

在文件 i_blas.h1561 行定义.

1561 {
1562 z[0] = x[0] - y[0];
1563 z[1] = x[1] - y[1];
1564 z[2] = x[2] - y[2];
1565 z[3] = x[3] - y[3];
1566 z[4] = x[4] - y[4];
1567 z[5] = x[5] - y[5];
1568 z[6] = x[6] - y[6];
1569 z[7] = x[7] - y[7];
1570 z[8] = x[8] - y[8];
1571 z[9] = x[9] - y[9];
1572 z[10] = x[10] - y[10];
1573 z[11] = x[11] - y[11];
1574 z[12] = x[12] - y[12];
1575 z[13] = x[13] - y[13];
1576 z[14] = x[14] - y[14];
1577 z[15] = x[15] - y[15];
1578}

◆ ISub16() [2/2]

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

在文件 i_blas.h1753 行定义.

1753 {
1754 y[0] -= x[0];
1755 y[1] -= x[1];
1756 y[2] -= x[2];
1757 y[3] -= x[3];
1758 y[4] -= x[4];
1759 y[5] -= x[5];
1760 y[6] -= x[6];
1761 y[7] -= x[7];
1762 y[8] -= x[8];
1763 y[9] -= x[9];
1764 y[10] -= x[10];
1765 y[11] -= x[11];
1766 y[12] -= x[12];
1767 y[13] -= x[13];
1768 y[14] -= x[14];
1769 y[15] -= x[15];
1770}

◆ ISub2() [1/2]

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

在文件 i_blas.h1400 行定义.

1400 {
1401 z[0] = x[0] - y[0];
1402 z[1] = x[1] - y[1];
1403}

◆ ISub2() [2/2]

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

在文件 i_blas.h1592 行定义.

1592 {
1593 y[0] -= x[0];
1594 y[1] -= x[1];
1595}

◆ ISub3() [1/2]

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

在文件 i_blas.h1405 行定义.

1405 {
1406 z[0] = x[0] - y[0];
1407 z[1] = x[1] - y[1];
1408 z[2] = x[2] - y[2];
1409}

◆ ISub3() [2/2]

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

在文件 i_blas.h1597 行定义.

1597 {
1598 y[0] -= x[0];
1599 y[1] -= x[1];
1600 y[2] -= x[2];
1601}

◆ ISub4() [1/2]

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

在文件 i_blas.h1411 行定义.

1411 {
1412 z[0] = x[0] - y[0];
1413 z[1] = x[1] - y[1];
1414 z[2] = x[2] - y[2];
1415 z[3] = x[3] - y[3];
1416}

◆ ISub4() [2/2]

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

在文件 i_blas.h1603 行定义.

1603 {
1604 y[0] -= x[0];
1605 y[1] -= x[1];
1606 y[2] -= x[2];
1607 y[3] -= x[3];
1608}

◆ ISub5() [1/2]

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

在文件 i_blas.h1418 行定义.

1418 {
1419 z[0] = x[0] - y[0];
1420 z[1] = x[1] - y[1];
1421 z[2] = x[2] - y[2];
1422 z[3] = x[3] - y[3];
1423 z[4] = x[4] - y[4];
1424}

◆ ISub5() [2/2]

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

在文件 i_blas.h1610 行定义.

1610 {
1611 y[0] -= x[0];
1612 y[1] -= x[1];
1613 y[2] -= x[2];
1614 y[3] -= x[3];
1615 y[4] -= x[4];
1616}

◆ ISub6() [1/2]

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

在文件 i_blas.h1426 行定义.

1426 {
1427 z[0] = x[0] - y[0];
1428 z[1] = x[1] - y[1];
1429 z[2] = x[2] - y[2];
1430 z[3] = x[3] - y[3];
1431 z[4] = x[4] - y[4];
1432 z[5] = x[5] - y[5];
1433}

◆ ISub6() [2/2]

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

在文件 i_blas.h1618 行定义.

1618 {
1619 y[0] -= x[0];
1620 y[1] -= x[1];
1621 y[2] -= x[2];
1622 y[3] -= x[3];
1623 y[4] -= x[4];
1624 y[5] -= x[5];
1625}

◆ ISub7() [1/2]

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

在文件 i_blas.h1435 行定义.

1435 {
1436 z[0] = x[0] - y[0];
1437 z[1] = x[1] - y[1];
1438 z[2] = x[2] - y[2];
1439 z[3] = x[3] - y[3];
1440 z[4] = x[4] - y[4];
1441 z[5] = x[5] - y[5];
1442 z[6] = x[6] - y[6];
1443}

◆ ISub7() [2/2]

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

在文件 i_blas.h1627 行定义.

1627 {
1628 y[0] -= x[0];
1629 y[1] -= x[1];
1630 y[2] -= x[2];
1631 y[3] -= x[3];
1632 y[4] -= x[4];
1633 y[5] -= x[5];
1634 y[6] -= x[6];
1635}

◆ ISub8() [1/2]

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

在文件 i_blas.h1445 行定义.

1445 {
1446 z[0] = x[0] - y[0];
1447 z[1] = x[1] - y[1];
1448 z[2] = x[2] - y[2];
1449 z[3] = x[3] - y[3];
1450 z[4] = x[4] - y[4];
1451 z[5] = x[5] - y[5];
1452 z[6] = x[6] - y[6];
1453 z[7] = x[7] - y[7];
1454}

◆ ISub8() [2/2]

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

在文件 i_blas.h1637 行定义.

1637 {
1638 y[0] -= x[0];
1639 y[1] -= x[1];
1640 y[2] -= x[2];
1641 y[3] -= x[3];
1642 y[4] -= x[4];
1643 y[5] -= x[5];
1644 y[6] -= x[6];
1645 y[7] -= x[7];
1646}

◆ ISub9() [1/2]

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

在文件 i_blas.h1456 行定义.

1456 {
1457 z[0] = x[0] - y[0];
1458 z[1] = x[1] - y[1];
1459 z[2] = x[2] - y[2];
1460 z[3] = x[3] - y[3];
1461 z[4] = x[4] - y[4];
1462 z[5] = x[5] - y[5];
1463 z[6] = x[6] - y[6];
1464 z[7] = x[7] - y[7];
1465 z[8] = x[8] - y[8];
1466}

◆ ISub9() [2/2]

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

在文件 i_blas.h1648 行定义.

1648 {
1649 y[0] -= x[0];
1650 y[1] -= x[1];
1651 y[2] -= x[2];
1652 y[3] -= x[3];
1653 y[4] -= x[4];
1654 y[5] -= x[5];
1655 y[6] -= x[6];
1656 y[7] -= x[7];
1657 y[8] -= x[8];
1658}

◆ ISubdeterminants2x4() [1/3]

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

在文件 i_blas.h3840 行定义.

3841 {
3842 sd[0] = x[0] * y[1] - x[1] * y[0];
3843 sd[1] = x[0] * y[2] - x[2] * y[0];
3844 sd[2] = x[0] * y[3] - x[3] * y[0];
3845 sd[3] = x[1] * y[2] - x[2] * y[1];
3846 sd[4] = x[1] * y[3] - x[3] * y[1];
3847 sd[5] = x[2] * y[3] - x[3] * y[2];
3848}

◆ ISubdeterminants2x4() [2/3]

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

在文件 i_blas.h3849 行定义.

3850 {
3851 sd[0] = x[0] * y[1] - x[1] * y[0];
3852 sd[1] = x[0] * y[2] - x[2] * y[0];
3853 sd[2] = x[0] * y[3] - x[3] * y[0];
3854 sd[3] = x[1] * y[2] - x[2] * y[1];
3855 sd[4] = x[1] * y[3] - x[3] * y[1];
3856 sd[5] = x[2] * y[3] - x[3] * y[2];
3857}

◆ ISubdeterminants2x4() [3/3]

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

在文件 i_blas.h3858 行定义.

3858 {
3859 sd[0] = x[0] * y[1] - x[1] * y[0];
3860 sd[1] = x[0] * y[2] - x[2] * y[0];
3861 sd[2] = x[0] * y[3] - x[3] * y[0];
3862 sd[3] = x[1] * y[2] - x[2] * y[1];
3863 sd[4] = x[1] * y[3] - x[3] * y[1];
3864 sd[5] = x[2] * y[3] - x[3] * y[2];
3865}

◆ ISubdeterminants3x4() [1/3]

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

在文件 i_blas.h3869 行定义.

3870 {
3871 double ssd[6];
3872 ISubdeterminants2x4(x, y, ssd);
3873 sd[0] = z[1] * ssd[5] - z[2] * ssd[4] + z[3] * ssd[3];
3874 sd[1] = z[0] * ssd[5] - z[2] * ssd[2] + z[3] * ssd[1];
3875 sd[2] = z[0] * ssd[4] - z[1] * ssd[2] + z[3] * ssd[0];
3876 sd[3] = z[0] * ssd[3] - z[1] * ssd[1] + z[2] * ssd[0];
3877}
void ISubdeterminants2x4(const double x[4], const double y[4], double sd[6])
Definition i_blas.h:3840

◆ ISubdeterminants3x4() [2/3]

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

在文件 i_blas.h3878 行定义.

3879 {
3880 float ssd[6];
3881 ISubdeterminants2x4(x, y, ssd);
3882 sd[0] = z[1] * ssd[5] - z[2] * ssd[4] + z[3] * ssd[3];
3883 sd[1] = z[0] * ssd[5] - z[2] * ssd[2] + z[3] * ssd[1];
3884 sd[2] = z[0] * ssd[4] - z[1] * ssd[2] + z[3] * ssd[0];
3885 sd[3] = z[0] * ssd[3] - z[1] * ssd[1] + z[2] * ssd[0];
3886}

◆ ISubdeterminants3x4() [3/3]

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

在文件 i_blas.h3887 行定义.

3888 {
3889 int ssd[6];
3890 ISubdeterminants2x4(x, y, ssd);
3891 sd[0] = z[1] * ssd[5] - z[2] * ssd[4] + z[3] * ssd[3];
3892 sd[1] = z[0] * ssd[5] - z[2] * ssd[2] + z[3] * ssd[1];
3893 sd[2] = z[0] * ssd[4] - z[1] * ssd[2] + z[3] * ssd[0];
3894 sd[3] = z[0] * ssd[3] - z[1] * ssd[1] + z[2] * ssd[0];
3895}

◆ ISubScaled()

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

在文件 i_blas.h1773 行定义.

1773 {
1774 for (int i = 0; i < n; i++) {
1775 y[i] -= (x[i] * k);
1776 }
1777}

◆ ISubScaled1()

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

在文件 i_blas.h1779 行定义.

1779 {
1780 y[0] -= x[0] * k;
1781}

◆ ISubScaled2()

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

在文件 i_blas.h1783 行定义.

1783 {
1784 y[0] -= x[0] * k;
1785 y[1] -= x[1] * k;
1786}

◆ ISubScaled3()

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

在文件 i_blas.h1788 行定义.

1788 {
1789 y[0] -= x[0] * k;
1790 y[1] -= x[1] * k;
1791 y[2] -= x[2] * k;
1792}

◆ ISubScaled4()

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

在文件 i_blas.h1794 行定义.

1794 {
1795 y[0] -= x[0] * k;
1796 y[1] -= x[1] * k;
1797 y[2] -= x[2] * k;
1798 y[3] -= x[3] * k;
1799}

◆ ISubScaled5()

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

在文件 i_blas.h1801 行定义.

1801 {
1802 y[0] -= x[0] * k;
1803 y[1] -= x[1] * k;
1804 y[2] -= x[2] * k;
1805 y[3] -= x[3] * k;
1806 y[4] -= x[4] * k;
1807}

◆ ISubScaled6()

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

在文件 i_blas.h1809 行定义.

1809 {
1810 y[0] -= x[0] * k;
1811 y[1] -= x[1] * k;
1812 y[2] -= x[2] * k;
1813 y[3] -= x[3] * k;
1814 y[4] -= x[4] * k;
1815 y[5] -= x[5] * k;
1816}

◆ ISubScaled7()

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

在文件 i_blas.h1818 行定义.

1818 {
1819 y[0] -= x[0] * k;
1820 y[1] -= x[1] * k;
1821 y[2] -= x[2] * k;
1822 y[3] -= x[3] * k;
1823 y[4] -= x[4] * k;
1824 y[5] -= x[5] * k;
1825 y[6] -= x[6] * k;
1826}

◆ ISubScaled8()

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

在文件 i_blas.h1828 行定义.

1828 {
1829 y[0] -= x[0] * k;
1830 y[1] -= x[1] * k;
1831 y[2] -= x[2] * k;
1832 y[3] -= x[3] * k;
1833 y[4] -= x[4] * k;
1834 y[5] -= x[5] * k;
1835 y[6] -= x[6] * k;
1836 y[7] -= x[7] * k;
1837}

◆ ISubScaled9()

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

在文件 i_blas.h1839 行定义.

1839 {
1840 y[0] -= x[0] * k;
1841 y[1] -= x[1] * k;
1842 y[2] -= x[2] * k;
1843 y[3] -= x[3] * k;
1844 y[4] -= x[4] * k;
1845 y[5] -= x[5] * k;
1846 y[6] -= x[6] * k;
1847 y[7] -= x[7] * k;
1848 y[8] -= x[8] * k;
1849}

◆ ISum()

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

在文件 i_blas.h2344 行定义.

2344 {
2345 T acc = static_cast<T>(0.0);
2346 for (int i = 0; i < n; ++i) {
2347 acc += x[i];
2348 }
2349 return acc;
2350}

◆ ISum1()

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

在文件 i_blas.h2352 行定义.

2352 {
2353 return (x[0]);
2354}

◆ ISum10()

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

在文件 i_blas.h2388 行定义.

2388 {
2389 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9]);
2390}

◆ ISum11()

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

在文件 i_blas.h2392 行定义.

2392 {
2393 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9] +
2394 x[10]);
2395}

◆ ISum12()

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

在文件 i_blas.h2397 行定义.

2397 {
2398 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9] +
2399 x[10] + x[11]);
2400}

◆ ISum13()

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

在文件 i_blas.h2402 行定义.

2402 {
2403 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9] +
2404 x[10] + x[11] + x[12]);
2405}

◆ ISum14()

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

在文件 i_blas.h2407 行定义.

2407 {
2408 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9] +
2409 x[10] + x[11] + x[12] + x[13]);
2410}

◆ ISum15()

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

在文件 i_blas.h2412 行定义.

2412 {
2413 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9] +
2414 x[10] + x[11] + x[12] + x[13] + x[14]);
2415}

◆ ISum16()

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

在文件 i_blas.h2417 行定义.

2417 {
2418 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8] + x[9] +
2419 x[10] + x[11] + x[12] + x[13] + x[14] + x[15]);
2420}

◆ ISum2()

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

在文件 i_blas.h2356 行定义.

2356 {
2357 return (x[0] + x[1]);
2358}

◆ ISum3()

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

在文件 i_blas.h2360 行定义.

2360 {
2361 return (x[0] + x[1] + x[2]);
2362}

◆ ISum4()

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

在文件 i_blas.h2364 行定义.

2364 {
2365 return (x[0] + x[1] + x[2] + x[3]);
2366}

◆ ISum5()

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

在文件 i_blas.h2368 行定义.

2368 {
2369 return (x[0] + x[1] + x[2] + x[3] + x[4]);
2370}

◆ ISum6()

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

在文件 i_blas.h2372 行定义.

2372 {
2373 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5]);
2374}

◆ ISum7()

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

在文件 i_blas.h2376 行定义.

2376 {
2377 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6]);
2378}

◆ ISum8()

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

在文件 i_blas.h2380 行定义.

2380 {
2381 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7]);
2382}

◆ ISum9()

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

在文件 i_blas.h2384 行定义.

2384 {
2385 return (x[0] + x[1] + x[2] + x[3] + x[4] + x[5] + x[6] + x[7] + x[8]);
2386}

◆ ISumU()

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

在文件 i_blas.h2336 行定义.

2336 {
2337 int acc = 0;
2338 for (int i = 0; i < n; ++i) {
2339 acc += static_cast<int>(x[i]);
2340 }
2341 return acc;
2342}

◆ ISwap() [1/2]

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

在文件 i_basic.h299 行定义.

299 {
300 T temp;
301 temp = a;
302 a = b;
303 b = temp;
304}

◆ ISwap() [2/2]

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

在文件 i_basic.h306 行定义.

306 {
307 for (int i = 0; i < n; i++) {
308 ISwap(a[i], b[i]);
309 }
310}
void ISwap(T &a, T &b)
Definition i_basic.h:299

◆ ISwap2()

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

在文件 i_basic.h312 行定义.

312 {
313 ISwap(a[0], b[0]);
314 ISwap(a[1], b[1]);
315}

◆ ISwap3()

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

在文件 i_basic.h317 行定义.

317 {
318 ISwap(a[0], b[0]);
319 ISwap(a[1], b[1]);
320 ISwap(a[2], b[2]);
321}

◆ ISwap4()

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

在文件 i_basic.h323 行定义.

323 {
324 ISwap(a[0], b[0]);
325 ISwap(a[1], b[1]);
326 ISwap(a[2], b[2]);
327 ISwap(a[3], b[3]);
328}

◆ ISwapCols()

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

在文件 i_blas.h4993 行定义.

4993 {
4994 T *ref = A;
4995 for (int i = 0; i < m; i++, ref += n) {
4996 ISwap(ref[c1], ref[c2]);
4997 }
4998}

◆ ISwapColsInterval()

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

在文件 i_blas.h5010 行定义.

5011 {
5012 int i_begin = IMax(0, i1);
5013 int i_end = IMin(m, i2);
5014 T *ref = A + i_begin * n;
5015 for (int i = i_begin; i < i_end; i++, ref += n) {
5016 ISwap(ref[c1], ref[c2]);
5017 }
5018}

◆ ISwapRows()

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

在文件 i_blas.h4988 行定义.

4988 {
4989 ISwap(A + r1 * n, A + r2 * n, n);
4990}

◆ ISwapRowsInterval()

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

在文件 i_blas.h5002 行定义.

5003 {
5004 int i_begin = IMax(0, i1);
5005 int i_end = IMin(n, i2);
5006 ISwap(A + r1 * n + i_begin, A + r2 * n + i_begin, (i_end - i_begin));
5007}

◆ ITan() [1/2]

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

在文件 i_basic.h219 行定义.

219{ return tan(alpha); }

◆ ITan() [2/2]

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

在文件 i_basic.h218 行定义.

218{ return tanf(alpha); }

◆ ITrace2x2() [1/2]

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

在文件 i_blas.h3804 行定义.

3804{ return (A[0] + A[3]); }

◆ ITrace2x2() [2/2]

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

在文件 i_blas.h3805 行定义.

3805{ return (A[0] + A[3]); }

◆ ITrace3x3() [1/2]

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

在文件 i_blas.h3807 行定义.

3807{ return (A[0] + A[4] + A[8]); }

◆ ITrace3x3() [2/2]

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

在文件 i_blas.h3808 行定义.

3808{ return (A[0] + A[4] + A[8]); }

◆ ITranspose() [1/2]

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

在文件 i_blas.h4231 行定义.

4231 {
4232 for (int r = 0; r < m; ++r) {
4233 for (int c = 0; c < n; ++c) {
4234 At[c * m + r] = A[r * n + c];
4235 }
4236 }
4237}

◆ ITranspose() [2/2]

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

在文件 i_blas.h4222 行定义.

4222 {
4223 for (int r = 0; r < n; ++r) {
4224 for (int c = r; c < n; ++c) {
4225 ISwap(A[r * n + c], A[c * n + r]);
4226 }
4227 }
4228}

◆ ITranspose2x2() [1/2]

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

在文件 i_blas.h4243 行定义.

4243 {
4244 At[0] = A[0];
4245 At[1] = A[2];
4246 At[2] = A[1];
4247 At[3] = A[3];
4248}

◆ ITranspose2x2() [2/2]

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

在文件 i_blas.h4239 行定义.

4239 {
4240 ISwap(A[1], A[2]);
4241}

◆ ITranspose3x3() [1/2]

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

在文件 i_blas.h4256 行定义.

4256 {
4257 At[0] = A[0];
4258 At[1] = A[3];
4259 At[2] = A[6];
4260 At[3] = A[1];
4261 At[4] = A[4];
4262 At[5] = A[7];
4263 At[6] = A[2];
4264 At[7] = A[5];
4265 At[8] = A[8];
4266}

◆ ITranspose3x3() [2/2]

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

在文件 i_blas.h4250 行定义.

4250 {
4251 ISwap(A[1], A[3]);
4252 ISwap(A[2], A[6]);
4253 ISwap(A[5], A[7]);
4254}

◆ ITranspose4x4() [1/2]

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

在文件 i_blas.h4277 行定义.

4277 {
4278 At[0] = A[0];
4279 At[1] = A[4];
4280 At[2] = A[8];
4281 At[3] = A[12];
4282 At[4] = A[1];
4283 At[5] = A[5];
4284 At[6] = A[9];
4285 At[7] = A[13];
4286 At[8] = A[2];
4287 At[9] = A[6];
4288 At[10] = A[10];
4289 At[11] = A[14];
4290 At[12] = A[3];
4291 At[13] = A[7];
4292 At[14] = A[11];
4293 At[15] = A[15];
4294}

◆ ITranspose4x4() [2/2]

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

在文件 i_blas.h4268 行定义.

4268 {
4269 ISwap(A[1], A[4]);
4270 ISwap(A[2], A[8]);
4271 ISwap(A[6], A[9]);
4272 ISwap(A[3], A[12]);
4273 ISwap(A[7], A[13]);
4274 ISwap(A[11], A[14]);
4275}

◆ IUnitize() [1/4]

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

在文件 i_blas.h2927 行定义.

2927 {
2928 IScale(x, y, n, IRec(IL2Norm(x, n)));
2929}

◆ IUnitize() [2/4]

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

在文件 i_blas.h2930 行定义.

2930 {
2931 IScale(x, y, n, IRec(IL2Norm(x, n)));
2932}

◆ IUnitize() [3/4]

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

在文件 i_blas.h2907 行定义.

2907{ IScale(x, n, IRec(IL2Norm(x, n))); }

◆ IUnitize() [4/4]

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

在文件 i_blas.h2908 行定义.

2908{ IScale(x, n, IRec(IL2Norm(x, n))); }

◆ IUnitize10() [1/2]

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

在文件 i_blas.h3043 行定义.

3043 {
3044 IScale10(x, y, IRec(IL2Norm10(x)));
3045}
void IScale10(T x[10], T sf)
Definition i_blas.h:1931
T IL2Norm10(const T x[10])
Definition i_blas.h:2840

◆ IUnitize10() [2/2]

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

在文件 i_blas.h2983 行定义.

2983 {
2984 IScale10(x, IRec(IL2Norm10(x)));
2985}

◆ IUnitize11() [1/2]

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

在文件 i_blas.h3047 行定义.

3047 {
3048 IScale11(x, y, IRec(IL2Norm11(x)));
3049}
T IL2Norm11(const T x[11])
Definition i_blas.h:2844
void IScale11(T x[11], T sf)
Definition i_blas.h:1944

◆ IUnitize11() [2/2]

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

在文件 i_blas.h2987 行定义.

2987 {
2988 IScale11(x, IRec(IL2Norm11(x)));
2989}

◆ IUnitize12() [1/2]

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

在文件 i_blas.h3051 行定义.

3051 {
3052 IScale12(x, y, IRec(IL2Norm12(x)));
3053}
T IL2Norm12(const T x[12])
Definition i_blas.h:2848
void IScale12(T x[12], T sf)
Definition i_blas.h:1958

◆ IUnitize12() [2/2]

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

在文件 i_blas.h2991 行定义.

2991 {
2992 IScale12(x, IRec(IL2Norm12(x)));
2993}

◆ IUnitize13() [1/2]

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

在文件 i_blas.h3055 行定义.

3055 {
3056 IScale13(x, y, IRec(IL2Norm13(x)));
3057}
void IScale13(T x[13], T sf)
Definition i_blas.h:1973
T IL2Norm13(const T x[13])
Definition i_blas.h:2852

◆ IUnitize13() [2/2]

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

在文件 i_blas.h2995 行定义.

2995 {
2996 IScale13(x, IRec(IL2Norm13(x)));
2997}

◆ IUnitize14() [1/2]

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

在文件 i_blas.h3059 行定义.

3059 {
3060 IScale14(x, y, IRec(IL2Norm14(x)));
3061}
void IScale14(T x[14], T sf)
Definition i_blas.h:1989
T IL2Norm14(const T x[14])
Definition i_blas.h:2856

◆ IUnitize14() [2/2]

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

在文件 i_blas.h2999 行定义.

2999 {
3000 IScale14(x, IRec(IL2Norm14(x)));
3001}

◆ IUnitize15() [1/2]

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

在文件 i_blas.h3063 行定义.

3063 {
3064 IScale15(x, y, IRec(IL2Norm15(x)));
3065}
T IL2Norm15(const T x[15])
Definition i_blas.h:2860
void IScale15(T x[15], T sf)
Definition i_blas.h:2006

◆ IUnitize15() [2/2]

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

在文件 i_blas.h3003 行定义.

3003 {
3004 IScale15(x, IRec(IL2Norm15(x)));
3005}

◆ IUnitize16() [1/2]

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

在文件 i_blas.h3067 行定义.

3067 {
3068 IScale16(x, y, IRec(IL2Norm16(x)));
3069}
T IL2Norm16(const T x[16])
Definition i_blas.h:2864
void IScale16(T x[16], T sf)
Definition i_blas.h:2024

◆ IUnitize16() [2/2]

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

在文件 i_blas.h3007 行定义.

3007 {
3008 IScale16(x, IRec(IL2Norm16(x)));
3009}

◆ IUnitize2() [1/2]

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

在文件 i_blas.h3011 行定义.

3011 {
3012 IScale2(x, y, IRec(IL2Norm2(x)));
3013}

◆ IUnitize2() [2/2]

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

在文件 i_blas.h2951 行定义.

2951 {
2952 IScale2(x, IRec(IL2Norm2(x)));
2953}

◆ IUnitize3() [1/2]

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

在文件 i_blas.h3015 行定义.

3015 {
3016 IScale3(x, y, IRec(IL2Norm3(x)));
3017}

◆ IUnitize3() [2/2]

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

在文件 i_blas.h2955 行定义.

2955 {
2956 IScale3(x, IRec(IL2Norm3(x)));
2957}

◆ IUnitize4() [1/2]

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

在文件 i_blas.h3019 行定义.

3019 {
3020 IScale4(x, y, IRec(IL2Norm4(x)));
3021}

◆ IUnitize4() [2/2]

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

在文件 i_blas.h2959 行定义.

2959 {
2960 IScale4(x, IRec(IL2Norm4(x)));
2961}

◆ IUnitize5() [1/2]

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

在文件 i_blas.h3023 行定义.

3023 {
3024 IScale5(x, y, IRec(IL2Norm5(x)));
3025}
void IScale5(T x[5], T sf)
Definition i_blas.h:1881
T IL2Norm5(const T x[5])
Definition i_blas.h:2820

◆ IUnitize5() [2/2]

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

在文件 i_blas.h2963 行定义.

2963 {
2964 IScale5(x, IRec(IL2Norm5(x)));
2965}

◆ IUnitize6() [1/2]

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

在文件 i_blas.h3027 行定义.

3027 {
3028 IScale6(x, y, IRec(IL2Norm6(x)));
3029}
T IL2Norm6(const T x[6])
Definition i_blas.h:2824
void IScale6(T x[6], T sf)
Definition i_blas.h:1889

◆ IUnitize6() [2/2]

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

在文件 i_blas.h2967 行定义.

2967 {
2968 IScale6(x, IRec(IL2Norm6(x)));
2969}

◆ IUnitize7() [1/2]

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

在文件 i_blas.h3031 行定义.

3031 {
3032 IScale7(x, y, IRec(IL2Norm7(x)));
3033}
void IScale7(T x[7], T sf)
Definition i_blas.h:1898
T IL2Norm7(const T x[7])
Definition i_blas.h:2828

◆ IUnitize7() [2/2]

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

在文件 i_blas.h2971 行定义.

2971 {
2972 IScale7(x, IRec(IL2Norm7(x)));
2973}

◆ IUnitize8() [1/2]

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

在文件 i_blas.h3035 行定义.

3035 {
3036 IScale8(x, y, IRec(IL2Norm8(x)));
3037}
void IScale8(T x[8], T sf)
Definition i_blas.h:1908
T IL2Norm8(const T x[8])
Definition i_blas.h:2832

◆ IUnitize8() [2/2]

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

在文件 i_blas.h2975 行定义.

2975 {
2976 IScale8(x, IRec(IL2Norm8(x)));
2977}

◆ IUnitize9() [1/2]

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

在文件 i_blas.h3039 行定义.

3039 {
3040 IScale9(x, y, IRec(IL2Norm9(x)));
3041}
T IL2Norm9(const T x[9])
Definition i_blas.h:2836

◆ IUnitize9() [2/2]

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

在文件 i_blas.h2979 行定义.

2979 {
2980 IScale9(x, IRec(IL2Norm9(x)));
2981}

◆ IUnprojectThroughIntrinsic()

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

在文件 i_util.h137 行定义.

137 {
138 T fx_rec = IRec(K[0]);
139 T fy_rec = IRec(K[4]);
140 T fxfy_rec = IRec(K[0] * K[4]);
141 X[0] = fx_rec * x[0] - (K[1] * fxfy_rec) * x[1] +
142 (K[1] * K[5] * fxfy_rec - K[2] * fx_rec) * x[2];
143 X[1] = fy_rec * x[1] - (K[5] * fy_rec) * x[2];
144 X[2] = x[2];
145}

◆ IUpperTriangular2x2()

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

在文件 i_blas.h3782 行定义.

3782 {
3783 A[0] = a0;
3784 A[1] = a1;
3785 A[2] = static_cast<T>(0.0);
3786 A[3] = a3;
3787}

◆ IUpperTriangular3x3()

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

在文件 i_blas.h3791 行定义.

3791 {
3792 A[0] = a0;
3793 A[1] = a1;
3794 A[2] = a2;
3795 A[3] = static_cast<T>(0.0);
3796 A[4] = a4;
3797 A[5] = a5;
3798 A[6] = static_cast<T>(0.0);
3799 A[7] = static_cast<T>(0.0);
3800 A[8] = a8;
3801}

◆ IVerifyAlignment()

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

在文件 i_alloc.h150 行定义.

150 {
151 std::size_t mask = static_cast<size_t>((1 << alignment_power) - 1);
152 if (((size_t)mem) & mask) {
153 return 0;
154 } else {
155 return 1;
156 }
157}

◆ IWithin1D()

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

在文件 i_basic.h573 行定义.

573 {
574 return (x >= start && x < (length + start));
575}

◆ IWithin2D() [1/2]

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

在文件 i_basic.h582 行定义.

583 {
584 return (p[0] >= x_upper_left && p[1] >= y_upper_left &&
585 p[0] < width + x_upper_left && p[1] < height + y_upper_left);
586}

◆ IWithin2D() [2/2]

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

在文件 i_basic.h592 行定义.

593 {
594 return (x >= x_upper_left && y >= y_upper_left && x < width + x_upper_left &&
595 y < height + y_upper_left);
596}

◆ IZero()

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

在文件 i_blas.h320 行定义.

320 {
321 for (int i = 0; i < n; i++) {
322 a[i] = static_cast<T>(0.0);
323 }
324}

◆ IZero1()

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

在文件 i_blas.h326 行定义.

326 {
327 a[0] = static_cast<T>(0.0);
328}

◆ IZero10()

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

在文件 i_blas.h363 行定义.

363 {
364 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] =
365 static_cast<T>(0.0);
366}

◆ IZero11()

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

在文件 i_blas.h368 行定义.

368 {
369 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
370 static_cast<T>(0.0);
371}

◆ IZero12()

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

在文件 i_blas.h373 行定义.

373 {
374 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
375 a[11] = static_cast<T>(0.0);
376}

◆ IZero13()

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

在文件 i_blas.h378 行定义.

378 {
379 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
380 a[11] = a[12] = static_cast<T>(0.0);
381}

◆ IZero14()

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

在文件 i_blas.h383 行定义.

383 {
384 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
385 a[11] = a[12] = a[13] = static_cast<T>(0.0);
386}

◆ IZero15()

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

在文件 i_blas.h388 行定义.

388 {
389 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
390 a[11] = a[12] = a[13] = a[14] = static_cast<T>(0.0);
391}

◆ IZero16()

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

在文件 i_blas.h393 行定义.

393 {
394 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] = a[9] = a[10] =
395 a[11] = a[12] = a[13] = a[14] = a[15] = static_cast<T>(0.0);
396}

◆ IZero2()

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

在文件 i_blas.h330 行定义.

330 {
331 a[0] = a[1] = static_cast<T>(0.0);
332}

◆ IZero3()

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

在文件 i_blas.h334 行定义.

334 {
335 a[0] = a[1] = a[2] = static_cast<T>(0.0);
336}

◆ IZero4()

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

在文件 i_blas.h338 行定义.

338 {
339 a[0] = a[1] = a[2] = a[3] = static_cast<T>(0.0);
340}

◆ IZero5()

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

在文件 i_blas.h342 行定义.

342 {
343 a[0] = a[1] = a[2] = a[3] = a[4] = static_cast<T>(0.0);
344}

◆ IZero6()

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

在文件 i_blas.h346 行定义.

346 {
347 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = static_cast<T>(0.0);
348}

◆ IZero7()

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

在文件 i_blas.h350 行定义.

350 {
351 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = static_cast<T>(0.0);
352}

◆ IZero8()

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

在文件 i_blas.h354 行定义.

354 {
355 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = static_cast<T>(0.0);
356}

◆ IZero9()

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

在文件 i_blas.h358 行定义.

358 {
359 a[0] = a[1] = a[2] = a[3] = a[4] = a[5] = a[6] = a[7] = a[8] =
360 static_cast<T>(0.0);
361}

◆ LoadBrownCameraIntrinsic()

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

在文件 io_util.cc59 行定义.

60 {
61 if (!PathExists(yaml_file) || model == nullptr) {
62 return false;
63 }
64
65 YAML::Node node = YAML::LoadFile(yaml_file);
66 if (node.IsNull()) {
67 AINFO << "Load " << yaml_file << " failed! please check!";
68 return false;
69 }
70
71 float camera_width = 0.0f;
72 float camera_height = 0.0f;
73 Eigen::VectorXf params(9 + 5 + 3); // add k4, k5, k6
74 try {
75 camera_width = node["width"].as<float>();
76 camera_height = node["height"].as<float>();
77 for (size_t i = 0; i < 9; ++i) {
78 params(i) = node["K"][i].as<float>();
79 }
80 for (size_t i = 0; i < 8; ++i) {
81 params(9 + i) = node["D"][i].as<float>();
82 }
83
84 model->set_params(static_cast<size_t>(camera_width),
85 static_cast<size_t>(camera_height), params);
86 } catch (YAML::Exception &e) {
87 AERROR << "load camera intrisic file " << yaml_file
88 << " with error, YAML exception: " << e.what();
89 return false;
90 }
91
92 return true;
93}
bool set_params(size_t width, size_t height, const Eigen::VectorXf &params) override

◆ LoadOmnidirectionalCameraIntrinsics()

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

在文件 io_util.cc95 行定义.

97 {
98 if (!PathExists(yaml_file) || model == nullptr) {
99 return false;
100 }
101
102 YAML::Node node = YAML::LoadFile(yaml_file);
103 if (node.IsNull()) {
104 AINFO << "Load " << yaml_file << " failed! please check!";
105 return false;
106 }
107
108 if (!node["width"].IsDefined() || !node["height"].IsDefined() ||
109 !node["center"].IsDefined() || !node["affine"].IsDefined() ||
110 !node["cam2world"].IsDefined() || !node["world2cam"].IsDefined() ||
111 !node["focallength"].IsDefined() || !node["principalpoint"].IsDefined()) {
112 AINFO << "Invalid intrinsics file for an omnidirectional camera.";
113 return false;
114 }
115
116 try {
117 int camera_width = 0;
118 int camera_height = 0;
119
120 std::vector<float> params; // center|affine|f|p|i,cam2world|j,world2cam
121
122 camera_width = node["width"].as<int>();
123 camera_height = node["height"].as<int>();
124
125 params.push_back(node["center"]["x"].as<float>());
126 params.push_back(node["center"]["y"].as<float>());
127
128 params.push_back(node["affine"]["c"].as<float>());
129 params.push_back(node["affine"]["d"].as<float>());
130 params.push_back(node["affine"]["e"].as<float>());
131
132 params.push_back(node["focallength"].as<float>());
133 params.push_back(node["principalpoint"]["x"].as<float>());
134 params.push_back(node["principalpoint"]["y"].as<float>());
135
136 params.push_back(static_cast<float>(node["cam2world"].size()));
137
138 for (size_t i = 0; i < node["cam2world"].size(); ++i) {
139 params.push_back(node["cam2world"][i].as<float>());
140 }
141
142 params.push_back(static_cast<float>(node["world2cam"].size()));
143
144 for (size_t i = 0; i < node["world2cam"].size(); ++i) {
145 params.push_back(node["world2cam"][i].as<float>());
146 }
147
148 Eigen::VectorXf eigen_params(params.size());
149 for (size_t i = 0; i < params.size(); ++i) {
150 eigen_params(i) = params[i];
151 }
152
153 model->set_params(camera_width, camera_height, eigen_params);
154 } catch (YAML::Exception &e) {
155 AERROR << "load camera intrisic file " << yaml_file
156 << " with error, YAML exception: " << e.what();
157 return false;
158 }
159
160 return true;
161}
bool set_params(size_t width, size_t height, const Eigen::VectorXf &params) override

◆ ObjectInRoiCheck() [1/2]

bool apollo::perception::algorithm::ObjectInRoiCheck ( const HdmapStructConstPtr  roi,
const std::vector< ObjectPtr > &  objects,
std::vector< ObjectPtr > *  valid_objects 
)

在文件 roi_filter.cc97 行定义.

99 {
100 if (roi == nullptr ||
101 (roi->road_polygons.empty() && roi->junction_polygons.empty())) {
102 valid_objects->assign(objects.begin(), objects.end());
103 return true;
104 }
105
106 valid_objects->clear();
107 valid_objects->reserve(objects.size());
108 for (std::size_t i = 0; i < objects.size(); i++) {
109 if (IsObjectInRoi(roi, objects[i])) {
110 valid_objects->push_back(objects[i]);
111 }
112 }
113
114 return valid_objects->size() > 0;
115}

◆ ObjectInRoiCheck() [2/2]

bool apollo::perception::algorithm::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::algorithm::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 
)

在文件 camera_homography.cc27 行定义.

31 {
32 Eigen::Vector3d pt = point.homogeneous();
33 Eigen::Vector3d camera2_3d =
34 static_cast<Eigen::Matrix<double, 3, 1, 0, 3, 1>>(
35 trans_camera1_to_camera2 * camera1_intrinsic_inverse * pt);
36
37 double z = camera2_3d(2);
38 if (fabs(z) > 1e-6) {
39 *point_out = (camera2_intrinsic * camera2_3d / z).head(2);
40 return true;
41 }
42 return false;
43}

◆ ReadPoseFile()

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

在文件 io_util.cc33 行定义.

34 {
35 if (pose == nullptr || frame_id == nullptr || time_stamp == nullptr) {
36 AERROR << "Nullptr error.";
37 return false;
38 }
39
40 std::ifstream fin(filename.c_str());
41 if (!fin.is_open()) {
42 AERROR << "Failed to open pose file: " << filename;
43 return false;
44 }
45
46 Eigen::Vector3d translation;
47 Eigen::Quaterniond quat;
48 fin >> *frame_id >> *time_stamp >> translation(0) >> translation(1) >>
49 translation(2) >> quat.x() >> quat.y() >> quat.z() >> quat.w();
50
51 *pose = Eigen::Affine3d::Identity();
52 pose->prerotate(quat);
53 pose->pretranslate(translation);
54
55 fin.close();
56 return true;
57}

◆ 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::algorithm::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 
)

在文件 i_ransac.h46 行定义.

52 {
53 const int kSize = s;
54 const int kLength = l;
55 const int kLp = lp;
56 const int kKsize = k;
57 int indices[kSize];
58 T samples_x[kLength * kSize];
59 T samples_xp[kLp * kSize];
60 T tmp_model[kKsize];
61 T cost = std::numeric_limits<T>::max();
62 T best_cost = std::numeric_limits<T>::max();
63
64 if (n < min_nr_inliers) {
65 return false;
66 }
67
68 double actual_inlierprob = 0.0, tmp_inlierprob;
69 int nr_trials = IRansacTrials(s, confidence, inlierprob);
70
71 int nr_inliers = 0;
72 int rseed = I_DEFAULT_SEED;
73 int sample_count = 0;
74 int i, idxl, idxlp, il, ilp;
75 *consensus_size = 0; // initialize the size of the consensus set to zero
76 IZero(model, k); // initialize the model with zeros
77
78 if (random_shuffle_inputs) {
79 IRandomizedShuffle(x, xp, n, l, lp, &rseed);
80 }
81
82 while (nr_trials > sample_count) {
83 // generate random indices
84 IRandomSample(indices, s, n, &rseed);
85 // prepare data for model fitting
86 for (i = 0; i < s; ++i) {
87 idxl = indices[i] * l;
88 idxlp = indices[i] * lp;
89 il = i * l;
90 ilp = i * lp;
91 ICopy(x + idxl, samples_x + il, l);
92 ICopy(xp + idxlp, samples_xp + ilp, lp);
93 }
94
95 // estimate model
96 HypogenFunc(samples_x, samples_xp, tmp_model);
97
98 // validate model
99 CostFunc(tmp_model, x, xp, n, &nr_inliers, inliers + n, &cost, error_tol);
100 if ((nr_inliers > *consensus_size) ||
101 (nr_inliers == *consensus_size && cost < best_cost)) {
102 *consensus_size = nr_inliers;
103 best_cost = cost;
104 ICopy(tmp_model, model, k);
105 ICopy(inliers + n, inliers, *consensus_size); // record inlier indices
106 if (adaptive_trial_count) {
107 tmp_inlierprob = IDiv(static_cast<double>(*consensus_size), n);
108 if (tmp_inlierprob > actual_inlierprob) {
109 actual_inlierprob = tmp_inlierprob;
110 nr_trials = IRansacTrials(s, confidence, actual_inlierprob);
111 }
112 }
113 }
114 sample_count++;
115 }
116 bool succeeded = *consensus_size >= min_nr_inliers;
117
118 if (succeeded && re_est_model_w_inliers && RefitFunc != nullptr) {
119 RefitFunc(x, xp, inliers, model, n, *consensus_size);
120 }
121 return succeeded;
122}

◆ TransformPoint()

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

在文件 common.h36 行定义.

37 {
38 Eigen::Vector3d point3d(point_in.x, point_in.y, point_in.z);
39 point3d = pose * point3d;
40 point_out->x = static_cast<typename PointT::Type>(point3d.x());
41 point_out->y = static_cast<typename PointT::Type>(point3d.y());
42 point_out->z = static_cast<typename PointT::Type>(point3d.z());
43}

◆ TransformPointCloud() [1/2]

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

在文件 common.h48 行定义.

50 {
51 if (cloud_out->size() < cloud_in.size()) {
52 cloud_out->resize(cloud_in.size());
53 }
54 for (size_t i = 0; i < cloud_in.size(); ++i) {
55 TransformPoint<PointT>(cloud_in.at(i), pose, &(cloud_out->at(i)));
56 }
57}
virtual void resize(size_t size)
Definition point_cloud.h:88

◆ TransformPointCloud() [2/2]

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

在文件 common.h62 行定义.

63 {
64 TransformPointCloud<PointT>(*cloud_in_out, pose, cloud_in_out);
65}

变量说明

◆ I_DEFAULT_SEED

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

在文件 i_rand.h24 行定义.