42 #include <sensor_msgs/LaserScan.h> 43 #include <visualization_msgs/Marker.h> 44 #include <visualization_msgs/MarkerArray.h> 45 #include <geometry_msgs/Point.h> 47 #include <datmo/TrackArray.h> 48 #include <datmo/Track.h> 52 typedef std::pair<double, double>
Point;
68 void callback(
const sensor_msgs::LaserScan::ConstPtr &);
69 void Clustering(
const sensor_msgs::LaserScan::ConstPtr& , vector<pointList> &);
70 void visualiseGroupedPoints(
const vector<pointList> &);
78 sensor_msgs::LaserScan
scan;
86 unsigned long int cg = 1;
87 unsigned long int cclusters= 1;
ros::Publisher pub_marker_array
tf::TransformListener tf_listener
std::pair< double, double > Point
std::vector< double > l_shape
vector< Cluster > clusters
sensor_msgs::LaserScan scan
std::vector< Point > pointList
ros::Publisher pub_tracks_box_kf
std::vector< Point > pointList
double euclidean_distance
std::vector< l_shape > l_shapes