datmo.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, Robobrain.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Konstantinos Konstantinidis */
31 
32 #include <ros/ros.h>
33 #include <math.h> /* atan */
34 #include <omp.h> //Multi-threading
35 #include <vector>
36 #include <random>
37 #include <algorithm> // for sort(), min()
38 #include <chrono>
39 #include <iostream>
40 #include <fstream>
41 
42 #include <sensor_msgs/LaserScan.h>
43 #include <visualization_msgs/Marker.h>
44 #include <visualization_msgs/MarkerArray.h>
45 #include <geometry_msgs/Point.h>
46 #include <tf/tf.h>
47 #include <datmo/TrackArray.h>
48 #include <datmo/Track.h>
49 
50 #include "cluster.hpp"
51 
52 typedef std::pair<double, double> Point;
53 typedef std::vector<double> l_shape;
54 typedef std::vector<l_shape> l_shapes;
55 typedef std::vector<Point> pointList;
56 
57 
58 using namespace std;
59 // This node segments the point cloud based on the break-point detector algorithm.
60 // This algorithm is based on "L-Shape Model Switching-Based Precise Motion Tracking
61 // of Moving Vehicles Using Laser Scanners.
62 class Datmo
63 {
64 public:
65  Datmo();
66  ~Datmo();
67 
68  void callback(const sensor_msgs::LaserScan::ConstPtr &);
69  void Clustering(const sensor_msgs::LaserScan::ConstPtr& , vector<pointList> &);
70  void visualiseGroupedPoints(const vector<pointList> &);
71  void transformPointList(const pointList& , pointList& );
72 
74 private:
78  sensor_msgs::LaserScan scan;
79  vector<Cluster> clusters;
80 
81  //Tuning Parameteres
82  double dt;
84 
85  //initialised as one, because 0 index take the msgs that fail to be initialized
86  unsigned long int cg = 1;//group counter to be used as id of the clusters
87  unsigned long int cclusters= 1;//counter for the cluster objects to be used as id for the markers
88 
89  //Parameters
90  double dth;
95  string lidar_frame;
96  string world_frame;
97 
98 };
ros::Publisher pub_marker_array
Definition: datmo.hpp:75
tf::TransformListener tf_listener
Definition: datmo.hpp:73
std::pair< double, double > Point
Definition: datmo.hpp:52
std::vector< double > l_shape
Definition: datmo.hpp:53
int max_cluster_size
Definition: datmo.hpp:92
double dth
Definition: datmo.hpp:90
vector< Cluster > clusters
Definition: datmo.hpp:79
bool p_marker_pub
Definition: datmo.hpp:93
sensor_msgs::LaserScan scan
Definition: datmo.hpp:78
string world_frame
Definition: datmo.hpp:96
string lidar_frame
Definition: datmo.hpp:95
std::vector< Point > pointList
Definition: cluster.hpp:46
ros::Publisher pub_tracks_box_kf
Definition: datmo.hpp:76
std::vector< Point > pointList
Definition: datmo.hpp:55
double euclidean_distance
Definition: datmo.hpp:91
double dt
Definition: datmo.hpp:82
ros::Subscriber sub_scan
Definition: datmo.hpp:77
bool w_exec_times
Definition: datmo.hpp:94
ros::Time time
Definition: datmo.hpp:83
std::vector< l_shape > l_shapes
Definition: datmo.hpp:54
Definition: datmo.hpp:62


datmo
Author(s): Kostas Konstantinidis
autogenerated on Tue May 2 2023 02:58:06