|
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 > |
T | CalculateCosTheta2DXY (const Eigen::Matrix< T, 3, 1 > &v1, const Eigen::Matrix< T, 3, 1 > &v2) |
|
template<typename T > |
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 > ¢er0, const Eigen::Matrix< Type, 3, 1 > &size0, const Eigen::Matrix< Type, 3, 1 > ¢er1, 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 > |
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 > |
T | IMin (T a, T b) |
|
template<typename T > |
T | IMax (T a, T b) |
|
template<typename T > |
T | IAverage (T a, T b) |
|
template<typename T > |
T | ISign (T a) |
|
template<typename T > |
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 > |
T | IInterval (T a, T min_val, T max_val) |
|
template<typename T > |
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 > |
T | IDot (const T *x, const T *y, int n) |
|
template<typename T > |
T | IDot1 (const T x[1], const T y[1]) |
|
template<typename T > |
T | IDot2 (const T x[2], const T y[2]) |
|
template<typename T > |
T | IDot3 (const T x[3], const T y[3]) |
|
template<typename T > |
T | IDot4 (const T x[4], const T y[4]) |
|
template<typename T > |
T | IDot5 (const T x[5], const T y[5]) |
|
template<typename T > |
T | IDot6 (const T x[6], const T y[6]) |
|
template<typename T > |
T | IDot7 (const T x[7], const T y[7]) |
|
template<typename T > |
T | IDot8 (const T x[8], const T y[8]) |
|
template<typename T > |
T | IDot9 (const T x[9], const T y[9]) |
|
template<typename T > |
T | IDot10 (const T x[10], const T y[10]) |
|
template<typename T > |
T | IDot11 (const T x[11], const T y[11]) |
|
template<typename T > |
T | IDot12 (const T x[12], const T y[12]) |
|
template<typename T > |
T | IDot13 (const T x[13], const T y[13]) |
|
template<typename T > |
T | IDot14 (const T x[14], const T y[14]) |
|
template<typename T > |
T | IDot15 (const T x[15], const T y[15]) |
|
template<typename T > |
T | IDot16 (const T x[16], const T y[16]) |
|
int | ISumU (const unsigned char *x, int n) |
|
template<typename T > |
T | ISum (const T *x, int n) |
|
template<typename T > |
T | ISum1 (const T x[1]) |
|
template<typename T > |
T | ISum2 (const T x[2]) |
|
template<typename T > |
T | ISum3 (const T x[3]) |
|
template<typename T > |
T | ISum4 (const T x[4]) |
|
template<typename T > |
T | ISum5 (const T x[5]) |
|
template<typename T > |
T | ISum6 (const T x[6]) |
|
template<typename T > |
T | ISum7 (const T x[7]) |
|
template<typename T > |
T | ISum8 (const T x[8]) |
|
template<typename T > |
T | ISum9 (const T x[9]) |
|
template<typename T > |
T | ISum10 (const T x[10]) |
|
template<typename T > |
T | ISum11 (const T x[11]) |
|
template<typename T > |
T | ISum12 (const T x[12]) |
|
template<typename T > |
T | ISum13 (const T x[13]) |
|
template<typename T > |
T | ISum14 (const T x[14]) |
|
template<typename T > |
T | ISum15 (const T x[15]) |
|
template<typename T > |
T | ISum16 (const T x[16]) |
|
template<typename T > |
T | IAbsSum (const T *x, int n) |
|
int | IMeanU (const unsigned char *x, int n) |
|
template<typename T > |
T | IMean (const T *x, int n) |
|
template<typename T > |
T | IMean2 (const T x[2]) |
|
template<typename T > |
T | IMean3 (const T x[3]) |
|
template<typename T > |
T | IMean4 (const T x[4]) |
|
template<typename T > |
T | IMean5 (const T x[5]) |
|
template<typename T > |
T | IMean6 (const T x[6]) |
|
template<typename T > |
T | IMean7 (const T x[7]) |
|
template<typename T > |
T | IMean8 (const T x[8]) |
|
template<typename T > |
T | IMean9 (const T x[9]) |
|
template<typename T > |
T | IMean10 (const T x[10]) |
|
template<typename T > |
T | IMean11 (const T x[11]) |
|
template<typename T > |
T | IMean12 (const T x[12]) |
|
template<typename T > |
T | IMean13 (const T x[13]) |
|
template<typename T > |
T | IMean14 (const T x[14]) |
|
template<typename T > |
T | IMean15 (const T x[15]) |
|
template<typename T > |
T | IMean16 (const T x[16]) |
|
template<typename T > |
T | ISdv (const T *x, T mean, int n) |
|
int | ISquaresumU (const unsigned char *x, int n) |
|
template<typename T > |
T | ISquaresum (const T *x, int n) |
|
template<typename T > |
T | ISquaresum1 (const T x[1]) |
|
template<typename T > |
T | ISquaresum2 (const T x[2]) |
|
template<typename T > |
T | ISquaresum3 (const T x[3]) |
|
template<typename T > |
T | ISquaresum4 (const T x[4]) |
|
template<typename T > |
T | ISquaresum5 (const T x[5]) |
|
template<typename T > |
T | ISquaresum6 (const T x[6]) |
|
template<typename T > |
T | ISquaresum7 (const T x[7]) |
|
template<typename T > |
T | ISquaresum8 (const T x[8]) |
|
template<typename T > |
T | ISquaresum9 (const T x[9]) |
|
template<typename T > |
T | ISquaresum10 (const T x[10]) |
|
template<typename T > |
T | ISquaresum11 (const T x[11]) |
|
template<typename T > |
T | ISquaresum12 (const T x[12]) |
|
template<typename T > |
T | ISquaresum13 (const T x[13]) |
|
template<typename T > |
T | ISquaresum14 (const T x[14]) |
|
template<typename T > |
T | ISquaresum15 (const T x[15]) |
|
template<typename T > |
T | ISquaresum16 (const T x[16]) |
|
int | ISquaresumDiffU (const unsigned char *x, const unsigned char *y, int n) |
|
template<typename T > |
T | ISquaresumDiffU (const T *x, const T *y, int n) |
|
template<typename T > |
T | ISquaresumDiffU1 (const T x[1], const T y[1]) |
|
template<typename T > |
T | ISquaresumDiffU2 (const T x[2], const T y[2]) |
|
template<typename T > |
T | ISquaresumDiffU3 (const T x[3], const T y[3]) |
|
template<typename T > |
T | ISquaresumDiffU4 (const T x[4], const T y[4]) |
|
template<typename T > |
T | ISquaresumDiffU5 (const T x[5], const T y[5]) |
|
template<typename T > |
T | ISquaresumDiffU6 (const T x[6], const T y[6]) |
|
template<typename T > |
T | ISquaresumDiffU7 (const T x[7], const T y[7]) |
|
template<typename T > |
T | ISquaresumDiffU8 (const T x[8], const T y[8]) |
|
template<typename T > |
T | ISquaresumDiffU9 (const T x[9], const T y[9]) |
|
template<typename T > |
T | ISquaresumDiffU10 (const T x[10], const T y[10]) |
|
template<typename T > |
T | ISquaresumDiffU11 (const T x[11], const T y[11]) |
|
template<typename T > |
T | ISquaresumDiffU12 (const T x[12], const T y[12]) |
|
template<typename T > |
T | ISquaresumDiffU13 (const T x[13], const T y[13]) |
|
template<typename T > |
T | ISquaresumDiffU14 (const T x[14], const T y[14]) |
|
template<typename T > |
T | ISquaresumDiffU15 (const T x[15], const T y[15]) |
|
template<typename T > |
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 > |
T | IL2Norm1 (const T x[1]) |
|
template<typename T > |
T | IL2Norm2 (const T x[2]) |
|
template<typename T > |
T | IL2Norm3 (const T x[3]) |
|
template<typename T > |
T | IL2Norm4 (const T x[4]) |
|
template<typename T > |
T | IL2Norm5 (const T x[5]) |
|
template<typename T > |
T | IL2Norm6 (const T x[6]) |
|
template<typename T > |
T | IL2Norm7 (const T x[7]) |
|
template<typename T > |
T | IL2Norm8 (const T x[8]) |
|
template<typename T > |
T | IL2Norm9 (const T x[9]) |
|
template<typename T > |
T | IL2Norm10 (const T x[10]) |
|
template<typename T > |
T | IL2Norm11 (const T x[11]) |
|
template<typename T > |
T | IL2Norm12 (const T x[12]) |
|
template<typename T > |
T | IL2Norm13 (const T x[13]) |
|
template<typename T > |
T | IL2Norm14 (const T x[14]) |
|
template<typename T > |
T | IL2Norm15 (const T x[15]) |
|
template<typename T > |
T | IL2Norm16 (const T x[16]) |
|
template<typename T > |
T | IL2NormAdv (T a, T b) |
|
template<typename T > |
T | IL2NormAdv (const T x[2]) |
|
template<typename T > |
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 > |
T | IMinElement (const T *a, int n) |
|
template<typename T > |
T | IMaxElement (const T *a, int n) |
|
template<typename T > |
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 > |
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 > |
T | IPlaneToPointDistance (const T *pi, const T *p) |
|
template<typename T > |
T | IPlaneToPointDistance (const T *pi, const T *p, T l2_norm3_pi) |
|
template<typename T > |
T | IPlaneToPointDistanceWUnitNorm (const T *pi, const T *p) |
|
template<typename T > |
T | IPlaneToPointSignedDistanceWUnitNorm (const T *pi, const T *p) |
|
template<typename T > |
T | IPlaneToPointDistanceWNormalizedPlaneNorm (const T *pi, const T *p) |
|
template<typename T > |
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 ¢er_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 ¢er_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 ¢er_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) |
|