00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #include <mtt/mtt.h>
00033
00034 bool new_data=false;
00035 sensor_msgs::PointCloud2 pointData;
00036
00037 void PointsHandler(const sensor_msgs::PointCloud2& msg)
00038 {
00039 pointData=msg;
00040 new_data=true;
00041 }
00042
00043 void PointCloud2ToData(sensor_msgs::PointCloud2& cloud,t_data& data)
00044 {
00045 pcl::PointCloud<pcl::PointXYZ> PclCloud;
00046
00047 pcl::fromROSMsg(cloud,PclCloud);
00048
00049
00050 double theta;
00051 map<double,pair<uint,double> > grid;
00052 map<double,pair<uint,double> >::iterator it;
00053
00054 double spacing = 1.*M_PI/180.;
00055
00056 double rightBorder;
00057 double leftBorder;
00058
00059 double r;
00060
00061 cout<<"mtt Input size:"<<PclCloud.points.size()<<endl;
00062
00063 for(uint i=0;i<PclCloud.points.size();i++)
00064 {
00065 theta=atan2(PclCloud.points[i].y,PclCloud.points[i].x);
00066 r=sqrt(pow(PclCloud.points[i].x,2)+pow(PclCloud.points[i].y,2));
00067
00068
00069 rightBorder = spacing * ceil(theta/spacing);
00070 leftBorder = rightBorder - spacing;
00071
00072 if(fabs(rightBorder-theta)<fabs(leftBorder-theta))
00073 theta=rightBorder;
00074 else
00075 theta=leftBorder;
00076
00077 if(grid.find(theta)!=grid.end())
00078 {
00079 if(r<grid[theta].second)
00080 {
00081 grid[theta].first=i;
00082 grid[theta].second=r;
00083 }
00084 }else
00085 {
00086 grid[theta].first=i;
00087 grid[theta].second=r;
00088 }
00089 }
00090
00091 uint i=0;
00092 for(it=grid.begin();it!=grid.end();it++)
00093 {
00094
00095 data.x[i]=PclCloud.points[(*it).second.first].x;
00096 data.y[i]=PclCloud.points[(*it).second.first].y;
00097 data.r[i]=sqrt(pow(data.x[i],2)+pow(data.y[i],2));
00098 data.t[i]=atan2(data.y[i],data.x[i]);
00099
00100 i++;
00101 }
00102
00103 data.n_points=grid.size();
00104 cout<<"mtt Size of data:"<<data.n_points<<endl;
00105 }
00106
00107
00108
00109
00110 void CreateMarkers(vector<visualization_msgs::Marker>& marker_vector,mtt::TargetListPC& target_msg,vector<t_listPtr>& list)
00111 {
00112 static map<pair<string,int>, pair<visualization_msgs::Marker,int> > marker_map;
00113 map<pair<string,int>, pair<visualization_msgs::Marker,int> >::iterator it;
00114
00115
00116
00117 marker_vector.clear();
00118
00119 for(it=marker_map.begin();it!=marker_map.end();it++)
00120 it->second.second--;
00121
00122
00123 std_msgs::ColorRGBA color;
00124 class_colormap colormap("hsv",10, 1, false);
00125
00126 visualization_msgs::Marker marker;
00127
00128 marker.header.frame_id = target_msg.header.frame_id;
00129 cout<<"fid:"<<target_msg.header.frame_id<<endl;
00130
00131 marker.header.stamp = ros::Time::now();
00132 marker.ns = "ids";
00133 marker.action = visualization_msgs::Marker::ADD;
00134
00135 marker.pose.position.z=0.3;
00136
00137 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00138
00139 marker.scale.x = 0.2;
00140 marker.scale.y = 0.2;
00141 marker.scale.z = 0.2;
00142
00143 marker.color.r=0;
00144 marker.color.g=0;
00145 marker.color.b=0;
00146 marker.color.a=1;
00147
00148 marker.id=0;
00149
00150 for(uint i=0;i<list.size();i++)
00151 {
00152 if(list[i]->shape.lines.size()!=0)
00153 {
00154 marker.pose.position.x=list[i]->position.estimated_x;
00155 marker.pose.position.y=list[i]->position.estimated_y;
00156
00157 marker.text = boost::lexical_cast<string>(list[i]->id);
00158
00159 marker.id++;
00160
00161 marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);
00162 }
00163 }
00164
00165 marker.pose.position.x=0;
00166 marker.pose.position.y=0;
00167
00168 marker.text = "origin";
00169
00170 marker.id++;
00171
00172 marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);
00173
00174
00175
00176 marker.type = visualization_msgs::Marker::LINE_STRIP;
00177 marker.ns = "objects";
00178
00179 marker.pose.position.x=0;
00180 marker.pose.position.y=0;
00181 marker.pose.position.z=0;
00182
00183 marker.scale.x = 0.02;
00184 marker.scale.y = 0.1;
00185 marker.scale.z = 0.1;
00186
00187 for(uint i=0;i<list.size();i++)
00188 {
00189 marker.color = colormap.color(list[i]->id);
00190
00191 geometry_msgs::Point p;
00192 p.z = 0.1;
00193
00194 marker.points.clear();
00195
00196 uint l;
00197 for(l=0;l<list[i]->shape.lines.size();l++)
00198 {
00199 p.x = list[i]->shape.lines[l]->xi;
00200 p.y = list[i]->shape.lines[l]->yi;
00201
00202 marker.points.push_back(p);
00203 }
00204
00205 p.x = list[i]->shape.lines[l-1]->xf;
00206 p.y = list[i]->shape.lines[l-1]->yf;
00207
00208 marker.points.push_back(p);
00209
00210 marker.id++;
00211
00212 marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);
00213 }
00214
00215
00216
00217
00218 for(it=marker_map.begin();it!=marker_map.end();it++)
00219 {
00220 if( it->second.second==0 )
00221 it->second.first.action = visualization_msgs::Marker::DELETE;
00222 else if(it->second.second<=-1)
00223 {
00228 continue;
00229 }
00230
00231 marker_vector.push_back(it->second.first);
00232 }
00233 }
00234
00235 int main(int argc,char**argv)
00236 {
00237 mtt::TargetListPC targetList;
00238
00239 t_config config;
00240 t_data full_data;
00241 t_flag flags;
00242
00243 vector<t_clustersPtr> clusters;
00244 vector<t_objectPtr> object;
00245 vector<t_listPtr> list;
00246
00247 visualization_msgs::MarkerArray markersMsg;
00248
00249
00250 init(argc,argv,"mtt");
00251
00252 NodeHandle nh("~");
00253
00254 Subscriber subs_points = nh.subscribe("/points", 1000, PointsHandler);
00255 Publisher target_publisher = nh.advertise<mtt::TargetList>("/targets", 1000);
00256 Publisher markers_publisher= nh.advertise<visualization_msgs::MarkerArray>("/markers", 1000);
00257 Publisher marker_publisher= nh.advertise<visualization_msgs::Marker>("/marker", 1000);
00258
00259 init_flags(&flags);
00260 init_config(&config);
00261
00262 cout<<"Start to spin"<<endl;
00263 Rate r(100);
00264 while(ok())
00265 {
00266 spinOnce();
00267 r.sleep();
00268
00269 if(!new_data)
00270 continue;
00271 new_data=false;
00272
00273
00274 PointCloud2ToData(pointData,full_data);
00275
00276
00277 clustering(full_data,clusters,&config,&flags);
00278
00279
00280 calc_cluster_props(clusters,full_data);
00281
00282
00283 clusters2objects(object,clusters,full_data,config);
00284
00285 calc_object_props(object);
00286
00287
00288 AssociateObjects(list,object,config,flags);
00289
00290
00291 MotionModelsIteration(list,config);
00292
00293
00294
00295 clean_objets(object);
00296
00297 targetList.id.clear();
00298 targetList.obstacle_lines.clear();
00299
00300 pcl::PointCloud<pcl::PointXYZ> target_positions;
00301 pcl::PointCloud<pcl::PointXYZ> velocity;
00302
00303 target_positions.header.stamp = ros::Time::now();
00304 target_positions.header.frame_id = pointData.header.frame_id;
00305
00306 velocity.header.stamp = ros::Time::now();
00307 velocity.header.frame_id = pointData.header.frame_id;
00308
00309 targetList.header.frame_id = pointData.header.frame_id;
00310
00311
00312 for(uint i=0;i<list.size();i++)
00313 {
00314 targetList.id.push_back(list[i]->id);
00315
00316 pcl::PointXYZ position;
00317
00318 position.x = list[i]->position.estimated_x;
00319 position.y = list[i]->position.estimated_y;
00320 position.z = 0;
00321
00322 target_positions.points.push_back(position);
00323
00324 pcl::PointXYZ vel;
00325
00326 vel.x=list[i]->velocity.velocity_x;
00327 vel.y=list[i]->velocity.velocity_y;
00328 vel.z=0;
00329
00330 velocity.points.push_back(vel);
00331
00332 pcl::PointCloud<pcl::PointXYZ> shape;
00333 pcl::PointXYZ line_point;
00334
00335 uint j;
00336 for(j=0;j<list[i]->shape.lines.size();j++)
00337 {
00338 line_point.x=list[i]->shape.lines[j]->xi;
00339 line_point.y=list[i]->shape.lines[j]->yi;
00340
00341 shape.points.push_back(line_point);
00342 }
00343
00344 line_point.x=list[i]->shape.lines[j-1]->xf;
00345 line_point.y=list[i]->shape.lines[j-1]->yf;
00346
00347 sensor_msgs::PointCloud2 shape_cloud;
00348 pcl::toROSMsg(shape,shape_cloud);
00349 targetList.obstacle_lines.push_back(shape_cloud);
00350 }
00351
00352 pcl::toROSMsg(target_positions, targetList.position);
00353 pcl::toROSMsg(velocity, targetList.velocity);
00354
00355 target_publisher.publish(targetList);
00356
00357 CreateMarkers(markersMsg.markers,targetList,list);
00358
00359
00360 markers_publisher.publish(markersMsg);
00361
00362 flags.fi=false;
00363 }
00364
00365 return 0;
00366 }