mtt.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary fomr must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <mtt/mtt.h>
33 
34 bool new_data=false;
35 sensor_msgs::PointCloud2 pointData;
36 
37 void PointsHandler(const sensor_msgs::PointCloud2& msg)
38 {
39  pointData=msg;
40  new_data=true;
41 }
42 
43 void PointCloud2ToData(sensor_msgs::PointCloud2& cloud,t_data& data)//this function will convert the point cloud data into a laser scan type structure
44 {
45  pcl::PointCloud<pcl::PointXYZ> PclCloud;
46  pcl::PCLPointCloud2 pcl_pc;
47  pcl_conversions::toPCL(cloud, pcl_pc);
48  pcl::fromPCLPointCloud2(pcl_pc, PclCloud);
49 
50 
51  double theta;
52  map<double,pair<uint,double> > grid;
53  map<double,pair<uint,double> >::iterator it;
54 
55  double spacing = 1.*M_PI/180.;
56 
57  double rightBorder;
58  double leftBorder;
59 
60  double r;
61 
62  cout<<"mtt Input size:"<<PclCloud.points.size()<<endl;
63  //get points into grid to reorder them
64  for(uint i=0;i<PclCloud.points.size();i++)
65  {
66  theta=atan2(PclCloud.points[i].y,PclCloud.points[i].x);
67  r=sqrt(pow(PclCloud.points[i].x,2)+pow(PclCloud.points[i].y,2));
68 
69  //get closest theta, given a predefined precision
70  rightBorder = spacing * ceil(theta/spacing);
71  leftBorder = rightBorder - spacing;
72 
73  if(fabs(rightBorder-theta)<fabs(leftBorder-theta))
74  theta=rightBorder;
75  else
76  theta=leftBorder;
77 
78  if(grid.find(theta)!=grid.end())
79  {
80  if(r<grid[theta].second)//using closest measurement
81  {
82  grid[theta].first=i;
83  grid[theta].second=r;
84  }
85  }else
86  {
87  grid[theta].first=i;
88  grid[theta].second=r;
89  }
90  }
91 
92  uint i=0;
93  for(it=grid.begin();it!=grid.end();it++)
94  {
95  //the map auto orders the theta values
96  data.x[i]=PclCloud.points[(*it).second.first].x;
97  data.y[i]=PclCloud.points[(*it).second.first].y;
98  data.r[i]=sqrt(pow(data.x[i],2)+pow(data.y[i],2));
99  data.t[i]=atan2(data.y[i],data.x[i]);
100 
101  i++;
102  }
103 
104  data.n_points=grid.size();
105  cout<<"mtt Size of data:"<<data.n_points<<endl;
106 }
107 
108 
109 
110 
111 void CreateMarkers(vector<visualization_msgs::Marker>& marker_vector,mtt::TargetListPC& target_msg,vector<t_listPtr>& list)
112 {
113  static map<pair<string,int>, pair<visualization_msgs::Marker,int> > marker_map;
114  map<pair<string,int>, pair<visualization_msgs::Marker,int> >::iterator it;
115 
116 
117  //limpar o vector todo
118  marker_vector.clear();
119  //colocar todos os elementos em processo de elemincação
120  for(it=marker_map.begin();it!=marker_map.end();it++)
121  it->second.second--;
122 
123 
124  std_msgs::ColorRGBA color;
125  class_colormap colormap("hsv",10, 1, false);
126 
127  visualization_msgs::Marker marker;
128 
129  marker.header.frame_id = target_msg.header.frame_id;
130  cout<<"fid:"<<target_msg.header.frame_id<<endl;
131 
132  marker.header.stamp = ros::Time::now();
133  marker.ns = "ids";
134  marker.action = visualization_msgs::Marker::ADD;
135 
136  marker.pose.position.z=0.3;
137 
138  marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
139 
140  marker.scale.x = 0.2;
141  marker.scale.y = 0.2;
142  marker.scale.z = 0.2;
143 
144  marker.color.r=0;
145  marker.color.g=0;
146  marker.color.b=0;
147  marker.color.a=1;
148 
149  marker.id=0;
150 
151  for(uint i=0;i<list.size();i++)
152  {
153  if(list[i]->shape.lines.size()!=0)
154  {
155  marker.pose.position.x=list[i]->position.estimated_x;
156  marker.pose.position.y=list[i]->position.estimated_y;
157 
158  marker.text = boost::lexical_cast<string>(list[i]->id);
159 
160  marker.id++;
161 
162  marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);//isto substitui ou cria o novo marker no map
163  }
164  }
165 
166  marker.pose.position.x=0;
167  marker.pose.position.y=0;
168 
169  marker.text = "origin";
170 
171  marker.id++;
172 
173  marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);//isto substitui ou cria o novo marker no map
174 
175 
176  // Markers for Line objects
177  marker.type = visualization_msgs::Marker::LINE_STRIP;
178  marker.ns = "objects";
179 
180  marker.pose.position.x=0;
181  marker.pose.position.y=0;
182  marker.pose.position.z=0;
183 
184  marker.scale.x = 0.02;
185  marker.scale.y = 0.1;
186  marker.scale.z = 0.1;
187 
188  for(uint i=0;i<list.size();i++)
189  {
190  marker.color = colormap.color(list[i]->id);
191 
192  geometry_msgs::Point p;
193  p.z = 0.1;
194 
195  marker.points.clear();
196 
197  uint l;
198  for(l=0;l<list[i]->shape.lines.size();l++)
199  {
200  p.x = list[i]->shape.lines[l]->xi;
201  p.y = list[i]->shape.lines[l]->yi;
202 
203  marker.points.push_back(p);
204  }
205 
206  p.x = list[i]->shape.lines[l-1]->xf;
207  p.y = list[i]->shape.lines[l-1]->yf;
208 
209  marker.points.push_back(p);
210 
211  marker.id++;
212 
213  marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);//isto substitui ou cria o novo marker no map
214  }
215 
216 
217  //para o map todo envio tudo, e meto tudo a false
218  //envio todo e tudo o que ainda estiver a false vai com operaração de delete
219  for(it=marker_map.begin();it!=marker_map.end();it++)
220  {
221  if( it->second.second==0 )//se for falso é para apagar
222  it->second.first.action = visualization_msgs::Marker::DELETE;
223  else if(it->second.second<=-1)//já foi apagado
224  {
229  continue;
230  }
231 
232  marker_vector.push_back(it->second.first);
233  }
234 }
235 
236 int main(int argc,char**argv)
237 {
238  mtt::TargetListPC targetList;
239 
240  t_config config;
241  t_data full_data;
242  t_flag flags;
243 
244  vector<t_clustersPtr> clusters;
245  vector<t_objectPtr> object;
246  vector<t_listPtr> list;
247 
248  visualization_msgs::MarkerArray markersMsg;
249 
250  // Initialize ROS
251  init(argc,argv,"mtt");
252 
253  NodeHandle nh("~");
254 
255  Subscriber subs_points = nh.subscribe("/points", 1000, PointsHandler);
256  Publisher target_publisher = nh.advertise<mtt::TargetList>("/targets", 1000);
257  Publisher markers_publisher= nh.advertise<visualization_msgs::MarkerArray>("/markers", 1000);
258  Publisher marker_publisher= nh.advertise<visualization_msgs::Marker>("/marker", 1000);
259 
260  init_flags(&flags); //Inits flags values
261  init_config(&config); //Inits configuration values
262 
263  cout<<"Start to spin"<<endl;
264  Rate r(100);
265  while(ok())
266  {
267  spinOnce();
268  r.sleep();
269 
270  if(!new_data)
271  continue;
272  new_data=false;
273 
274  //Get data from PointCloud2 to full_data
275  PointCloud2ToData(pointData,full_data);
276 
277  //clustering
278  clustering(full_data,clusters,&config,&flags);
279 
280  //calc_cluster_props
281  calc_cluster_props(clusters,full_data);
282 
283  //clusters2objects
284  clusters2objects(object,clusters,full_data,config);
285 
286  calc_object_props(object);
287 
288  //AssociateObjects
289  AssociateObjects(list,object,config,flags);
290 
291  //MotionModelsIteration
292  MotionModelsIteration(list,config);
293 
294 // cout<<"Number of targets "<<list.size()<<endl;
295 
296  clean_objets(object);//clean current objects
297 
298  targetList.id.clear();
299  targetList.obstacle_lines.clear();//clear all lines
300 
301  pcl::PointCloud<pcl::PointXYZ> target_positions;
302  pcl::PointCloud<pcl::PointXYZ> velocity;
303 
304  target_positions.header.frame_id = pointData.header.frame_id;
305 
306  velocity.header.frame_id = pointData.header.frame_id;
307 
308  targetList.header.stamp = ros::Time::now();
309  targetList.header.frame_id = pointData.header.frame_id;
310 
311 
312  for(uint i=0;i<list.size();i++)
313  {
314  targetList.id.push_back(list[i]->id);
315 
316  pcl::PointXYZ position;
317 
318  position.x = list[i]->position.estimated_x;
319  position.y = list[i]->position.estimated_y;
320  position.z = 0;
321 
322  target_positions.points.push_back(position);
323 
324  pcl::PointXYZ vel;
325 
326  vel.x=list[i]->velocity.velocity_x;
327  vel.y=list[i]->velocity.velocity_y;
328  vel.z=0;
329 
330  velocity.points.push_back(vel);
331 
332  pcl::PointCloud<pcl::PointXYZ> shape;
333  pcl::PointXYZ line_point;
334 
335  uint j;
336  for(j=0;j<list[i]->shape.lines.size();j++)
337  {
338  line_point.x=list[i]->shape.lines[j]->xi;
339  line_point.y=list[i]->shape.lines[j]->yi;
340 
341  shape.points.push_back(line_point);
342  }
343 
344  line_point.x=list[i]->shape.lines[j-1]->xf;
345  line_point.y=list[i]->shape.lines[j-1]->yf;
346 
347  sensor_msgs::PointCloud2 shape_cloud;
348  pcl::toROSMsg(shape,shape_cloud);
349  targetList.obstacle_lines.push_back(shape_cloud);
350  }
351 
352  pcl::toROSMsg(target_positions, targetList.position);
353  pcl::toROSMsg(velocity, targetList.velocity);
354 
355  target_publisher.publish(targetList);
356 
357  CreateMarkers(markersMsg.markers,targetList,list);
358  //markersMsg.header.frame_id=targetList.header.frame_id;
359 
360  markers_publisher.publish(markersMsg);
361 
362  flags.fi=false;
363  }
364 
365  return 0;
366 }
void clean_objets(vector< t_objectPtr > &objects)
Frees memory associated with objects.
int main(int argc, char **argv)
Definition: mtt.cpp:236
void PointsHandler(const sensor_msgs::PointCloud2 &msg)
Definition: mtt.cpp:37
bool fi
Definition: mtt_common.h:372
double r[2160]
Definition: mtt_common.h:118
double t[2160]
Definition: mtt_common.h:118
double y[2160]
Definition: mtt_common.h:117
void init_flags(t_flag *flags)
Init flags.
double vel
void PointCloud2ToData(sensor_msgs::PointCloud2 &cloud, t_data &data)
Definition: mtt.cpp:43
bool new_data
Definition: mtt.cpp:34
void calc_cluster_props(t_cluster **clusters, int size, t_data *data, t_config *config)
Calculates cluster properties.
void AssociateObjects(vector< t_listPtr > &list, vector< t_objectPtr > &objects, t_config &config, t_flag &flags)
Global include file that combines all local include files for the mtt algorithm.
int n_points
Definition: mtt_common.h:122
sensor_msgs::PointCloud2 pointData
Definition: mtt.cpp:35
void MotionModelsIteration(vector< t_listPtr > &list, t_config &config)
Definition: mtt_kalman.cpp:64
double theta
map< pair< string, int >, pair< visualization_msgs::Marker, int > > marker_map
void CreateMarkers(vector< visualization_msgs::Marker > &marker_vector, mtt::TargetListPC &target_msg, vector< t_listPtr > &list)
Definition: mtt.cpp:111
This structure has all points coordinates.
Definition: mtt_common.h:115
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.
Definition: mtt_common.h:137
double x[2160]
Definition: mtt_common.h:117
void init_config(t_config *config)
Init configuration.
void calc_object_props(vector< t_objectPtr > &objects)
Computes object properties, such as centroid and size.
ros::Publisher target_publisher
ros::Publisher markers_publisher
This structure contains global flags parameters.
Definition: mtt_common.h:369


mtt
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:18