31 #ifndef _MTT_CLUSTERING_H_
32 #define _MTT_CLUSTERING_H_
138 void free_lines(vector<t_objectPtr> &objects);
155 extern void _p(
const char*text);
void recursive_IEPF(t_objectPtr &object, t_data &data, int start, int end, t_config &config)
Recursive iterative end point fit. Single step.
void clean_objets(vector< t_objectPtr > &objects)
Frees memory associated with objects.
double ClusteringThreshold(double r1, double t1, double r2, double t2, t_config *config)
void free_lines(vector< t_objectPtr > &objects)
Removes lines from memory.
double point2point_distance(double xi, double yi, double xf, double yf)
Calculates the distante between two points.
int real2print(double x, t_config *config)
double dietmayer_threshold(double r, t_config *config)
Computes dietmayer clustering threshold.
void recursive_line_fitting(t_objectPtr &object, t_cluster &cluster, t_data &data, t_config &config)
Recursive line fitting, complete process.
void calc_cluster_props(t_cluster **clusters, int size, t_data *data, t_config *config)
Calculates cluster properties.
boost::shared_ptr< t_object > t_objectPtr
Global include file that combines all local include files for the mtt algorithm.
void remove_small_clusters(t_cluster **clusters, int *size, int threshold)
Removes clusters based on their size.
Cluster type class, clusters are groups of points in close proximity.
void _p(const char *text)
This structure has all points coordinates.
t_cluster ** clustering(t_data *data, int *count, t_config *config, t_flag *flags)
Performs clustering operation.
bool clusters2objects(vector< t_objectPtr > &objectsPtr, vector< t_clustersPtr > &clusters, t_data &data, t_config &config)
Converts clusters of points into objects using recursive line fitting.
This structure contains global configurations parameters.
void calc_object_props(vector< t_objectPtr > &objects)
Computes object properties, such as centroid and size.
This structure contains global flags parameters.
void FlagCollisionWithOcclusion(t_cluster **clusters, int object_size, t_data *data, t_config *config)
double point2line_distance(double alpha, double ro, double x, double y)
Calculates the line to point distance.
void remove_border_points(t_cluster **clusters, int size, int npoints)
Removes cluster border points.