Namespaces | |
namespace | icp |
Classes | |
class | IcpAlign |
struct | node |
struct | timevalg |
struct | timezone |
class | TrajData |
struct | tree |
Typedefs | |
typedef struct icp::node | Node |
typedef struct icp::tree | Tree |
typedef struct icp::timevalg | TV |
typedef struct icp::timezone | TZ |
Functions | |
Tree * | build_kdtree (double *reference, int N, int D, int *index, int L, int offset) |
Node * | build_kdtree_core (double *reference, int N, int D, int *index, int L, int offset) |
double | calcdistance (double *pt1, double *pt2, int Dim) |
void | display_tree (Node *nodeptr, int D) |
void | free_tree (Node *pVertex) |
void | icp (double *trpr, double *ttpr, double *modelz, unsigned int nmodelz, double *dataz, double *qltyz, unsigned int ndataz, unsigned int *randvecz, unsigned int nrandvecz, unsigned int nrandz, unsigned int iimax, icp::Tree *pointer_to_tree) |
void | kdtree_main () |
void | mexFunction (int nlhs, mxArray **plhs, int nrhs, const mxArray **prhs) |
void | multiply (double TR[9], double TT[3], geometry_msgs::Pose &track) |
int | partition (int *a, int p, int r, double *reference, int offset, int D) |
Node * | pointLocation (Node *v, double *pt, int D) |
double | pwr2 (double a) |
void | quicksort (int *ra, int p, int r, double *reference, int offset, int D) |
Node * | rangeQuery (Node *v, double distance, double *pt, int D) |
void | run_queries (Node *pVertex, double *model, int M, int D, double *closest_pt, double *distance, short ReturnType) |
void | run_range_search (Node *pVertex, double *model, int M, int D, double distlim, double **pts_in_range, unsigned int *L, unsigned int **indices) |
Variables | |
int | swap_tmp_int |
typedef struct icp::timevalg icp::TV |
typedef struct icp::timezone icp::TZ |
Tree * icp::build_kdtree | ( | double * | reference, | |
int | N, | |||
int | D, | |||
int * | index, | |||
int | L, | |||
int | offset | |||
) |
Definition at line 21 of file kdtree_common.cc.
Node * icp::build_kdtree_core | ( | double * | reference, | |
int | N, | |||
int | D, | |||
int * | index, | |||
int | L, | |||
int | offset | |||
) |
Definition at line 37 of file kdtree_common.cc.
double icp::calcdistance | ( | double * | pt1, | |
double * | pt2, | |||
int | Dim | |||
) |
Definition at line 146 of file kdtree_common.cc.
void icp::display_tree | ( | Node * | nodeptr, | |
int | D | |||
) |
Definition at line 306 of file kdtree_common.cc.
void icp::free_tree | ( | Node * | pVertex | ) |
Definition at line 130 of file kdtree_common.cc.
void icp::icp | ( | double * | trpr, | |
double * | ttpr, | |||
double * | modelz, | |||
unsigned int | nmodelz, | |||
double * | dataz, | |||
double * | qltyz, | |||
unsigned int | ndataz, | |||
unsigned int * | randvecz, | |||
unsigned int | nrandvecz, | |||
unsigned int | nrandz, | |||
unsigned int | iimax, | |||
icp::Tree * | pointer_to_tree | |||
) |
Definition at line 53 of file icpCpp.cpp.
void icp::mexFunction | ( | int | nlhs, | |
mxArray ** | plhs, | |||
int | nrhs, | |||
const mxArray ** | prhs | |||
) |
void icp::multiply | ( | double | TR[9], | |
double | TT[3], | |||
geometry_msgs::Pose & | track | |||
) | [inline] |
Definition at line 12 of file icp_utils.cpp.
int icp::partition | ( | int * | a, | |
int | p, | |||
int | r, | |||
double * | reference, | |||
int | offset, | |||
int | D | |||
) |
Definition at line 100 of file kdtree_common.cc.
Node * icp::pointLocation | ( | Node * | v, | |
double * | pt, | |||
int | D | |||
) |
Definition at line 155 of file kdtree_common.cc.
double icp::pwr2 | ( | double | a | ) |
Definition at line 49 of file icpCpp.cpp.
void icp::quicksort | ( | int * | ra, | |
int | p, | |||
int | r, | |||
double * | reference, | |||
int | offset, | |||
int | D | |||
) |
Definition at line 115 of file kdtree_common.cc.
Node * icp::rangeQuery | ( | Node * | v, | |
double | distance, | |||
double * | pt, | |||
int | D | |||
) |
Definition at line 178 of file kdtree_common.cc.
void icp::run_queries | ( | Node * | pVertex, | |
double * | model, | |||
int | M, | |||
int | D, | |||
double * | closest_pt, | |||
double * | distance, | |||
short | ReturnType | |||
) |
Definition at line 231 of file kdtree_common.cc.
void icp::run_range_search | ( | Node * | pVertex, | |
double * | model, | |||
int | M, | |||
int | D, | |||
double | distlim, | |||
double ** | pts_in_range, | |||
unsigned int * | L, | |||
unsigned int ** | indices | |||
) |
Definition at line 341 of file kdtree_common.cc.
Definition at line 15 of file kdtree_common.cc.