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 <ros/ros.h>
00033 
00034 #include <visualization_msgs/Marker.h>
00035 #include <visualization_msgs/MarkerArray.h>
00036 
00037 #include <mtt/TargetListPC.h>
00038 
00039 #include <tf/transform_listener.h>
00040 #include <laser_geometry/laser_geometry.h>
00041 #include <iostream>
00042 
00043 #include <pcl/point_types.h>
00044 #include <pcl/io/pcd_io.h>
00045 #include <pcl/kdtree/kdtree_flann.h>
00046 #include <pcl/surface/mls.h>
00047 
00048 #include <mtt/mtt_common.h>
00049 
00050 using namespace std;
00051 
00052 ros::Publisher target_publisher;
00053 ros::Publisher markers_publisher;
00054 string frame_id;
00055 ros::Time message_stamp;
00056 map<pair<string,int>, pair<visualization_msgs::Marker,int> > marker_map;
00057 int marker_id=0;
00058 double max_mean_variance=0.03;
00059 double clustering_threshold=0.3;
00060 double angular_resolution=3*M_PI/180.;
00061 
00062 double point2point_distance(double xi,double yi,double xf,double yf)
00063 {       return sqrt((xi-xf)*(xi-xf)+(yi-yf)*(yi-yf));}
00064 
00065 double point2line_distance(double alpha,double ro,double x,double y)
00066 {       return ro-x*cos(alpha)-y*sin(alpha);}
00067 
00068 void free_lines(vector<t_objectPtr> &objects)
00069 {       
00070         for(uint i=0;i<objects.size();i++)
00071                 objects[i]->lines.clear();
00072 }
00073 
00074 void cleanObjets(vector<t_objectPtr> &objects)
00075 {
00076         free_lines(objects);
00077 }
00078 
00079 void calcObjectProps(vector<t_objectPtr> &objects)
00080 {
00081         uint e;
00082         double r,t;
00083         double xi,yi,xf,yf;
00084         double rmin;
00085         
00086         for(uint i=0;i<objects.size();i++)
00087         {
00088                 t=objects[i]->tm;
00089                 
00090                 rmin=1e12;
00091                 
00092                 for(e=0;e<objects[i]->lines.size();e++)
00093                 {
00094                         r=sqrt(pow(objects[i]->lines[e]->xi,2)+pow(objects[i]->lines[e]->yi,2));
00095                         
00096                         if(r<rmin)
00097                                 rmin=r;
00098                 }
00099                 
00100                 r=sqrt(pow(objects[i]->lines[objects[i]->lines.size()-1]->xf,2)+pow(objects[i]->lines[objects[i]->lines.size()-1]->yf,2));
00101                 if(r<rmin)
00102                         rmin=r;
00103                 
00104                 r=rmin;
00105                 
00106                 objects[i]->cx=r*cos(t);
00107                 objects[i]->cy=r*sin(t);
00108                 
00109                 xi=objects[i]->lines[0]->xi;
00110                 yi=objects[i]->lines[0]->yi;
00111                 
00112                 xf=objects[i]->lines[objects[i]->lines.size()-1]->xf;
00113                 yf=objects[i]->lines[objects[i]->lines.size()-1]->yf;
00114                 
00115                 objects[i]->size=point2point_distance(xi,yi,xf,yf);
00116         }
00117 }
00118 
00119 void recursive_IEPF(t_objectPtr& object,t_data& data,int start,int end)
00120 {
00123         int i,index=0;
00124         double mean_variance,max_variance,current_variance;
00125         
00126         t_linePtr line(new t_line);
00127         
00128         line->alpha=atan2(data.x[start]-data.x[end],data.y[end]-data.y[start])+M_PI;
00129         line->ro=data.x[start]*cos(line->alpha)+data.y[start]*sin(line->alpha);
00130         line->xi=data.x[start];
00131         line->yi=data.y[start];
00132         line->xf=data.x[end];
00133         line->yf=data.y[end];
00134         
00135         mean_variance=0;
00136         max_variance=0;
00137         for(i=start;i<end;i++)
00138         {
00139                 current_variance=pow(point2line_distance(line->alpha,line->ro,data.x[i],data.y[i]),2);
00140                 mean_variance+=current_variance;
00141                 
00142                 if(current_variance>max_variance)
00143                 {
00144                         max_variance=current_variance;
00145                         index=i;
00146                 }               
00147         }
00148         
00149         mean_variance/=end-start;
00150         mean_variance=sqrt(mean_variance);
00151         
00152         if(mean_variance>max_mean_variance)
00153 
00154         {
00155                 recursive_IEPF(object,data,start,index);
00156                 recursive_IEPF(object,data,index,end);
00157                 return; 
00158         }
00159         
00160         object->lines.push_back(line);
00161         return;
00162 }
00163 
00164 void recursive_line_fitting(t_objectPtr& object,t_cluster& cluster,t_data& data)
00165 {       
00166         if(!data.n_points)
00167                 return;
00168         
00169         recursive_IEPF(object,data,cluster.stp,cluster.enp);
00170 }
00171 
00172 bool clustersToObjects(vector<t_clustersPtr> &clusters,t_data& data,vector<t_objectPtr> &objectsPtr)
00173 {
00174         t_objectPtr object(new t_object);
00175         
00176         objectsPtr.clear();
00177 
00178         for(uint i=0;i<clusters.size();i++)
00179         {
00180                 object->rmin=clusters[i]->rmin;
00181                 object->tm=clusters[i]->tm;
00182                 object->object_found=false;
00183                 
00184                 object->partialy_occluded=clusters[i]->partialy_occluded;
00185                 
00186                 recursive_line_fitting(object,*clusters[i],data);
00187                 
00188                 objectsPtr.push_back(object);
00189                 object.reset(new t_object);
00190         }
00191         
00192         return true;
00193 }
00194 
00195 void calcClusterProps(vector<t_clustersPtr> &clusters,t_data& data)
00196 {
00197         double rmin;
00198         int e;
00199         
00200         for(uint i=0;i<clusters.size();i++)
00201         {
00202                 rmin=1e12;
00203                 clusters[i]->lenght=0;
00204                 for(e=clusters[i]->stp;e<clusters[i]->enp;e++)
00205                 {
00206                         if(e<clusters[i]->enp-1)
00207                                 clusters[i]->lenght+=point2point_distance(data.x[e],data.y[e],data.x[e+1],data.y[e+1]);
00208                         
00209                         if(data.r[e]<rmin)
00210                                 rmin=data.r[e];
00211                 }
00212                 
00213                 
00214                 clusters[i]->rmin=rmin;
00215                 clusters[i]->tm=(data.t[clusters[i]->stp]+data.t[clusters[i]->enp])/2;
00216         }
00217 }
00218 
00219 bool clustering(t_data& data,vector<t_clustersPtr> &clusters)
00220 {
00221         double x,y,xold=0,yold=0;
00222         double dist,threshold;
00223         
00224         t_clustersPtr cluster(new t_cluster);
00225         
00226         clusters.clear();
00227         
00228         cluster->id=clusters.size();
00229         
00230         for(int i=0;i<data.n_points;i++)
00231         {
00232                 x=data.x[i];
00233                 y=data.y[i];
00234                 
00235                 if(i>0 && i<data.n_points-1)
00236                 {
00237                         dist = sqrt( pow(x-xold,2) + pow(y-yold,2));            
00238                         
00239                         threshold=clustering_threshold;
00240                         
00241                         if(dist>threshold)
00242                         {
00243                                 cluster->enp=i-1;               
00244                                 cluster->n_points=cluster->enp-cluster->stp;    
00245                                 cluster->partialy_occluded=false;
00246                                 clusters.push_back(cluster);
00247                                 
00248                                 cluster.reset(new t_cluster);
00249                                 
00250                                 cluster->id=clusters.size();
00251                                 cluster->stp=i;                                                                                 
00252                                 cluster->lenght=0;
00253                         }
00254                         
00255                         if(i==(data.n_points-1))
00256                         {
00257                                 
00258                                 cluster->enp=i;
00259                                 cluster->n_points=cluster->enp-cluster->stp;    
00260                         }
00261                         
00262                 }else if(i==data.n_points-1)
00263                 {
00264                         cluster->enp=i;         
00265                         cluster->n_points=cluster->enp-cluster->stp;    
00266                         cluster->partialy_occluded=false;
00267                         clusters.push_back(cluster);
00268                 
00269                 }else if(i==0)
00270                 {
00271                         cluster->stp=0;
00272                         cluster->enp=0;
00273                         cluster->lenght=0;
00274                 }
00275                 
00276                 xold=x;
00277                 yold=y;
00278         }
00279         
00280         return true;
00281 }
00282 
00283 void pointCloud2ToData(const sensor_msgs::PointCloud2& cloud,t_data& data)
00284 {
00285         pcl::PointCloud<pcl::PointXYZ> PclCloud;
00286         
00287         pcl::fromROSMsg(cloud,PclCloud);
00288         
00289         double theta;
00290         
00291         
00292         map<double,pair<uint,double> > grid;
00293         map<double,pair<uint,double> >::iterator it;
00294         
00295         double spacing = angular_resolution;
00296         
00297         double rightBorder;
00298         double leftBorder;
00299         
00300         double r;
00301         
00302         
00303         for(uint i=0;i<PclCloud.points.size();i++)
00304         {
00305                 theta=atan2(PclCloud.points[i].y,PclCloud.points[i].x);
00306                 r=sqrt(pow(PclCloud.points[i].x,2)+pow(PclCloud.points[i].y,2));
00307                 
00308                 
00309                 rightBorder = spacing * ceil(theta/spacing);
00310                 leftBorder = rightBorder - spacing;
00311 
00312                 if(fabs(rightBorder-theta)<fabs(leftBorder-theta))
00313                         theta=rightBorder;
00314                 else
00315                         theta=leftBorder;
00316                 
00317                 if(grid.find(theta)!=grid.end())
00318                 {
00319                         if(r<grid[theta].second)
00320                         {
00321                                 grid[theta].first=i;
00322                                 grid[theta].second=r;
00323                         }
00324                 }else
00325                 {
00326                         grid[theta].first=i;
00327                         grid[theta].second=r;
00328                 }
00329         }
00330         
00331         uint i=0;
00332         for(it=grid.begin();it!=grid.end();it++)
00333         {
00334                 
00335                 data.x[i]=PclCloud.points[(*it).second.first].x;
00336                 data.y[i]=PclCloud.points[(*it).second.first].y;
00337                 data.r[i]=sqrt(pow(data.x[i],2)+pow(data.y[i],2));
00338                 data.t[i]=atan2(data.y[i],data.x[i]);
00339                 
00340                 i++;
00341         }
00342         
00343         data.n_points=grid.size();
00344 }
00345 
00346 void convertObjectsToTargetListPC(vector<t_objectPtr> &objects,mtt::TargetListPC& targets)
00347 {
00348         
00349         
00350         pcl::PointCloud<pcl::PointXYZ> target_positions;
00351         pcl::PointCloud<pcl::PointXYZ> velocity;
00352                         
00353         targets.header.stamp = ros::Time::now();
00354         targets.header.frame_id = frame_id;
00355 
00356         for(uint i=0;i<objects.size();i++)
00357         {
00358                 
00359                 
00360                 targets.id.push_back(i);
00361                 
00362                 pcl::PointXYZ position;
00363                 
00364                 position.x = objects[i]->cx;
00365                 position.y = objects[i]->cy;
00366                 position.z = 0;
00367                 
00368                 target_positions.points.push_back(position);
00369                 
00370                 pcl::PointXYZ vel;
00371                 
00372                 vel.x=0;
00373                 vel.y=0;
00374                 vel.z=0;
00375 
00376                 velocity.points.push_back(vel);
00377                 
00378                 
00379                 pcl::PointCloud<pcl::PointXYZ> shape;
00380                 pcl::PointXYZ line_point;
00381                 
00382                 line_point.z=0;
00383                 
00384                 uint j;
00385                 for(j=0;j<objects[i]->lines.size();j++)
00386                 {
00387                         line_point.x=objects[i]->lines[j]->xi;
00388                         line_point.y=objects[i]->lines[j]->yi;
00389                         
00390                         shape.points.push_back(line_point);
00391                 }
00392                 
00393                 line_point.x=objects[i]->lines[j-1]->xf;
00394                 line_point.y=objects[i]->lines[j-1]->yf;
00395                 
00396                 shape.points.push_back(line_point);
00397                 
00398                 sensor_msgs::PointCloud2 shape_cloud;
00399                 pcl::toROSMsg(shape,shape_cloud);
00400                 
00401                 shape_cloud.header.stamp=message_stamp;
00402                 shape_cloud.header.frame_id=frame_id;
00403                 
00404                 targets.obstacle_lines.push_back(shape_cloud);
00405         }
00406         
00407         pcl::toROSMsg(target_positions, targets.position);
00408         
00409         targets.position.header.stamp=message_stamp;
00410         targets.position.header.frame_id=frame_id;
00411                 
00412         pcl::toROSMsg(velocity, targets.velocity);
00413         
00414         targets.velocity.header.stamp=message_stamp;
00415         targets.velocity.header.frame_id=frame_id;
00416 }
00417 
00418 void cleanMarkers(void)
00419 {
00420         map<pair<string,int>, pair<visualization_msgs::Marker,int> >::iterator it;      
00421         
00422         
00423         for(it=marker_map.begin();it!=marker_map.end();it++)
00424                 it->second.second--;
00425         
00426         marker_id=0;
00427 }
00428 
00429 void maintenanceMarkers(vector<visualization_msgs::Marker>& markers)
00430 {
00431         map<pair<string,int>, pair<visualization_msgs::Marker,int> >::iterator it;      
00432         
00433         for(it=marker_map.begin();it!=marker_map.end();it++)
00434         {
00435                 if( it->second.second==0 )
00436                         it->second.first.action = visualization_msgs::Marker::DELETE;
00437                 else if(it->second.second<=-1)
00438                 {
00443                         continue;
00444                 }
00445                 
00446                 markers.push_back(it->second.first);
00447         }
00448 }
00449 
00450 void createMarkers(mtt::TargetListPC& targets)
00451 {
00452         std_msgs::ColorRGBA color;
00453         class_colormap colormap("hsv",10, 1, false);
00454         
00455         visualization_msgs::Marker marker;
00456         
00457         marker.header.frame_id = frame_id;
00458         marker.header.stamp = ros::Time::now();
00459         marker.action = visualization_msgs::Marker::ADD;
00460         
00461         marker.ns = "ids";
00462         marker.pose.position.z=0.3;
00463         marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00464         
00465         marker.scale.x = 0.2; 
00466         marker.scale.y = 0.2; 
00467         marker.scale.z = 0.2; 
00468 
00469         marker.color.r=0;
00470         marker.color.g=0;
00471         marker.color.b=0;
00472         marker.color.a=1;
00473         
00474         pcl::PointCloud<pcl::PointXYZ> positions;
00475         pcl::fromROSMsg(targets.position,positions);
00476         
00477         for(uint i=0;i<positions.points.size();i++)
00478         {
00479                 marker.pose.position.x=positions.points[i].x;
00480                 marker.pose.position.y=positions.points[i].y;
00481                 
00482                 marker.text = boost::lexical_cast<string>(targets.id[i]);
00483 
00484                 marker.id=marker_id++;
00485                 marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);
00486         }
00487         
00488         
00489         marker.type = visualization_msgs::Marker::LINE_STRIP;
00490         marker.ns = "objects";
00491         
00492         marker.pose.position.x=0;
00493         marker.pose.position.y=0;
00494         marker.pose.position.z=0;
00495         
00496         marker.scale.x = 0.02; 
00497         marker.scale.y = 0.1; 
00498         marker.scale.z = 0.1; 
00499         
00500         for(uint i=0;i<targets.obstacle_lines.size();i++)
00501         {
00502                 marker.color = colormap.color(i);
00503 
00504                 geometry_msgs::Point p;
00505                 p.z = 0.1;
00506         
00507                 marker.points.clear();
00508         
00509                 uint l;
00510                 
00511                 pcl::PointCloud<pcl::PointXYZ> shape;
00512                 pcl::fromROSMsg(targets.obstacle_lines[i],shape);
00513         
00514                 for(l=0;l<shape.points.size();l++)
00515                 {
00516                         p.x = shape.points[l].x;
00517                         p.y = shape.points[l].y;
00518                         p.z = 0;
00519                         
00520                         marker.points.push_back(p);
00521                 }
00522                 
00523                 marker.id=marker_id++;
00524                 marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);
00525         }
00526 }
00527 
00528 void markersFromData(t_data& data)
00529 {
00530         visualization_msgs::Marker marker;
00531         
00532         marker.header.frame_id = frame_id;
00533         marker.header.stamp = ros::Time::now();
00534         marker.action = visualization_msgs::Marker::ADD;
00535         
00536         marker.ns = "data";
00537         marker.pose.position.z=0.0;
00538         marker.type = visualization_msgs::Marker::POINTS;
00539         
00540         marker.scale.x = 0.02;
00541         marker.scale.y = 0.02;
00542         marker.scale.z = 0.02;
00543 
00544         marker.color.r=0;
00545         marker.color.g=0;
00546         marker.color.b=1;
00547         marker.color.a=1;
00548         
00549         for(int i=0;i<data.n_points;i++)
00550         {
00551                 geometry_msgs::Point p;
00552                 
00553                 p.x=data.x[i];
00554                 p.y=data.y[i];
00555                 p.z=0;
00556                 
00557                 marker.points.push_back(p);
00558         }
00559         
00560         marker.id=marker_id++;
00561         marker_map[make_pair(marker.ns,marker.id) ] = make_pair(marker,1);
00562 }
00563 
00564 void pointsHandler(const sensor_msgs::PointCloud2& points)
00565 {
00566         t_data data;
00567         vector<t_clustersPtr> clusters;
00568         vector<t_objectPtr> objects;
00569         mtt::TargetListPC targets;
00570         visualization_msgs::MarkerArray markers;
00571         
00572         
00573         frame_id=points.header.frame_id;
00574         message_stamp=points.header.stamp;
00575         
00576         
00577         pointCloud2ToData(points,data);
00578         
00579         
00580         clustering(data,clusters);
00581         
00582         
00583         calcClusterProps(clusters,data);
00584         
00585         
00586         clustersToObjects(clusters,data,objects);
00587         
00588         
00589         calcObjectProps(objects);
00590         
00591         
00592         convertObjectsToTargetListPC(objects,targets);
00593         
00594         
00595         cleanMarkers();
00596         
00597         
00598         createMarkers(targets);
00599         
00600         
00601         markersFromData(data);
00602         
00603         
00604         maintenanceMarkers(markers.markers);
00605         
00606         
00607         target_publisher.publish(targets);
00608         
00609         
00610         markers_publisher.publish(markers);
00611         
00612         
00613         cleanObjets(objects);
00614 }
00615 
00616 int main(int argc,char**argv)
00617 {
00618         
00619         ros::init(argc,argv,"mtt");
00620         
00621         ros::NodeHandle nh("~");
00622         
00623         ros::Subscriber subs_points = nh.subscribe("/points", 1000, pointsHandler);
00624         target_publisher =  nh.advertise<mtt::TargetListPC>("/targets", 1000);
00625         markers_publisher = nh.advertise<visualization_msgs::MarkerArray>("/markers", 1000);
00626         
00627         visualization_msgs::MarkerArray markersMsg;
00628         
00629         ros::spin();
00630         
00631         return 0;
00632 }