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::TargetList& 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 = pointData.header.frame_id;
00129 
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 
00219 
00220 
00221 
00222 
00223 
00224 
00225 
00226 
00227 
00228 
00229 
00230 
00231 
00232 
00233 
00234 
00235 
00236 
00237 
00238 
00239 
00240 
00241 
00242 
00243 
00244 
00245 
00246 
00247 
00248 
00249 
00250 
00251 
00252 
00253 
00254 
00255 
00256 
00257 
00258 
00259 
00260 
00261 
00262 
00263 
00264 
00265 
00266 
00267 
00268 
00269 
00270 
00271 
00272 
00273 
00274 
00275 
00276         
00277         
00278         
00279         
00280         for(it=marker_map.begin();it!=marker_map.end();it++)
00281         {
00282                 if( it->second.second==0 )
00283                         it->second.first.action = visualization_msgs::Marker::DELETE;
00284                 else if(it->second.second<=-1)
00285                 {
00290                         continue;
00291                 }
00292                 
00293                 marker_vector.push_back(it->second.first);
00294         }
00295 }
00296 
00297 int main(int argc,char**argv)
00298 {
00299         
00300         mtt::TargetList targetList;
00301         
00302         t_config        config; 
00303         t_data          full_data;
00304         t_flag          flags;
00305         
00306         vector<t_clustersPtr> clusters;
00307         vector<t_objectPtr> object;
00308         vector<t_listPtr> list;
00309         
00310         visualization_msgs::MarkerArray markersMsg;
00311         
00312         
00313         init(argc,argv,"mtt");
00314         
00315         NodeHandle nh("~");
00316         
00317         Subscriber subs_points = nh.subscribe("/points", 1000, PointsHandler);
00318         Publisher target_publisher = nh.advertise<mtt::TargetList>("/targets", 1000);
00319         Publisher markers_publisher= nh.advertise<visualization_msgs::MarkerArray>("/markers", 1000);
00320         Publisher arrow_publisher= nh.advertise<visualization_msgs::MarkerArray>("/arrows", 1000);
00321 
00322         
00323         init_flags(&flags);             
00324         init_config(&config);   
00325         
00326         cout<<"Start to spin"<<endl;
00327         Rate r(100);
00328         while(ok())
00329         {
00330                 spinOnce();
00331                 r.sleep();
00332                 
00333                 if(!new_data)
00334                         continue;
00335                 new_data=false;
00336                 
00337                 
00338                 PointCloud2ToData(pointData,full_data);
00339                 
00340                 
00341                 clustering(full_data,clusters,&config,&flags);
00342                 
00343                 
00344                 calc_cluster_props(clusters,full_data);
00345                 
00346                 
00347                 clusters2objects(object,clusters,full_data,config);
00348                 
00349                 calc_object_props(object);
00350                 
00351                 
00352                 AssociateObjects(list,object,config,flags);
00353                 
00354                 
00355                 MotionModelsIteration(list,config);
00356 
00357 
00358                 
00359                 clean_objets(object);
00360                 
00361                 
00362                 targetList.Targets.clear();
00363                 
00364                 
00365                 mtt::Target target;
00366 
00367                 
00368                 target.header.stamp = ros::Time::now();
00369                 target.header.frame_id = pointData.header.frame_id;
00370                 
00371                 
00372                 
00373                 visualization_msgs::MarkerArray arrow_arrray;
00374                 
00375                 for(uint i=0;i<list.size();i++)
00376                 {
00377                   geometry_msgs::Pose pose;
00378                   geometry_msgs::Twist vel;
00379                   
00380                   
00381                   target.header.seq = list[i]->id;
00382                   target.id = list[i]->id;
00383                   
00384                   
00385                   vel.linear.x=list[i]->velocity.velocity_x;
00386                   vel.linear.y=list[i]->velocity.velocity_y;
00387                   vel.linear.z=0;
00388                   target.velocity = vel;
00389             
00390                   
00391                   double theta = atan2(vel.linear.y,vel.linear.x);
00392                   geometry_msgs::Quaternion target_orientation = 
00393                     tf::createQuaternionMsgFromYaw(theta);
00394                          
00395                   
00396                   pose.position.x = list[i]->position.estimated_x;
00397                   pose.position.y = list[i]->position.estimated_y;
00398                   pose.position.z = 0;
00399                   pose.orientation = target_orientation;
00400                   target.pose = pose;
00401                       
00402                   
00403                   
00404                   double velocity = sqrt(pow(vel.linear.x,2)+
00405                                          pow(vel.linear.y,2));
00406                   
00407                   if( velocity < 3.0)
00408                   targetList.Targets.push_back(target);
00409                   
00410                   
00412                   
00413                   
00414                   if(list[i]->velocity.velocity_module > 0.2 &&
00415                      list[i]->velocity.velocity_module < 5.0){
00416                     
00417                     visualization_msgs::Marker arrow_marker;
00418                     
00419                     arrow_marker.type = visualization_msgs::Marker::ARROW;
00420                     arrow_marker.action = visualization_msgs::Marker::ADD;
00421                     
00422                     
00423                     arrow_marker.header.frame_id = pointData.header.frame_id;
00424                     arrow_marker.header.stamp = ros::Time::now();
00425                                 
00426                     arrow_marker.color.r = 0;
00427                     arrow_marker.color.g = 1;
00428                     arrow_marker.color.b = 0;
00429                     arrow_marker.color.a = 1;
00430                     
00431 
00432                     arrow_marker.scale.x = 2; 
00433                     arrow_marker.scale.y = 5; 
00434                     arrow_marker.scale.z = list[i]->velocity.velocity_module; 
00435 
00436                     arrow_marker.lifetime = ros::Duration(1.0);
00437                     arrow_marker.id = list[i]->id;
00438 
00439                     
00440                     arrow_marker.pose = pose;
00441                     
00442                     arrow_arrray.markers.push_back(arrow_marker);
00444                   }
00445                 }
00446 
00447                 target_publisher.publish(targetList);
00448                 
00449                 CreateMarkers(markersMsg.markers,targetList,list);
00450                 markers_publisher.publish(markersMsg);
00451                 arrow_publisher.publish(arrow_arrray);
00452                 
00453                 flags.fi=false;
00454         }
00455         
00456         return 0;
00457 }