main.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <iostream>
00003 #include <ros/console.h>
00004 #include <geometry_msgs/PolygonStamped.h>
00005 #include <geometry_msgs/PoseArray.h>
00006 #include <geometry_msgs/Pose.h>
00007 #include <tf/transform_broadcaster.h>
00008 #include <tf/LinearMath/Quaternion.h>
00009 #include <geometry_msgs/PoseStamped.h>
00010 #include <geometry_msgs/PoseArray.h>
00011 #include "nav_msgs/OccupancyGrid.h"
00012 #include "hexagon_map/point.h"
00013 #include "hexagon_map/hexagon_map.h"
00014 #include <fstream>
00015 #include <iomanip>
00016 #include <vector>
00017 #include <deque>
00018 #include <set>
00019 #include <queue>
00020 #include <sensor_msgs/PointCloud.h>
00021 #include <sensor_msgs/PointCloud2.h>
00022 #include <pcl/point_cloud.h>
00023 #include <pcl_ros/point_cloud.h>
00024 #include <pcl_conversions/pcl_conversions.h>
00025 #include <sensor_msgs/LaserScan.h>
00026 
00027 // nav_msgs::OccupancyGrid gridmap;
00028 // int count = 250;
00029 // void drawplogon(const float &C_x,const float &C_y,const float &L)
00030 // {
00031 //     int dx = floor((C_x - gridmap.info.origin.position.x)/gridmap.info.resolution);
00032 //     int dy = floor((C_y - gridmap.info.origin.position.y)/gridmap.info.resolution);
00033     
00034 //     float h = L * cos(30.0/180.0*3.1415926);
00035         
00036 //      int h_index = ceil(h/gridmap.info.resolution);
00037 
00038 
00039 //     for(int i=-h_index;i<=h_index;i++)
00040 //     {
00041 //         float this_h = h - i * gridmap.info.resolution;
00042                 
00043 //         if(i<0)
00044 //         {
00045 //             this_h = h + i * gridmap.info.resolution;
00046 //         }
00047 //         else
00048 //         {
00049 //             this_h = h - i * gridmap.info.resolution;
00050 
00051 //         }
00052 
00053 //         float addlen = this_h * tan(30.0/180.0*3.1415926);
00054                 
00055 //         int addlen_index = ceil(addlen/gridmap.info.resolution);
00056                 
00057 //         int L_index = ceil(L/2/gridmap.info.resolution);
00058                 
00059 //              int half_index = addlen_index + L_index;
00060 
00061 //         for(int j=-half_index;j<=half_index;j++)
00062 //         {
00063 //             int deta_x = dx + j;
00064 //             int deta_y = dy + i;
00065 //             int index = deta_x + deta_y * gridmap.info.width;
00066 //             if(gridmap.data[index]==0)
00067 //             {
00068 //                   gridmap.data[index] = count;
00069 //             }
00070 //         }
00071 //     }
00072 // }
00073 
00074 // std::vector<CPoint2d> Pointset;
00075 
00076 // bool isInpointset(CPoint2d &Checkpoint)
00077 // {
00078 //     for(int i = 0;i<Pointset.size();i++)
00079 //     {
00080 //         CPoint2d tempoint = Pointset[i];
00081 
00082 //         float dis = (tempoint.x - Checkpoint.x) * (tempoint.x - Checkpoint.x) 
00083 //                     + (tempoint.y - Checkpoint.y) * (tempoint.y - Checkpoint.y); 
00084         
00085 //         if(dis<0.0001)
00086 //         {
00087 //             return true;
00088 //         }
00089 //     }
00090 //     return false;
00091 // }
00092 
00093 float R = 7.0;
00094 float resolution = 0.1;
00095 int count = 0;
00096 
00097 hexagon_map* hexagon_map_;
00098 ros::Publisher *g_path1Publisher;
00099 ros::Subscriber Getcloudpointssuber; 
00100 
00101 
00102 void PointcloudCallback(sensor_msgs::PointCloud2 msg)
00103 {
00104         count++;
00105         if(count==2)
00106         {
00107                 hexagon_map_->updateMap(msg);
00108                 std::cout<<"------- "<<std::endl;
00109                 g_path1Publisher->publish(hexagon_map_->gridmap);
00110                 count = 0;
00111         }
00112         
00113 }
00114 
00115 int main(int argc, char** argv)
00116 {
00117     ros::init(argc, argv, "Hexagon_map");
00118     ros::NodeHandle node;
00119         
00120     g_path1Publisher = new ros::Publisher;
00121     *g_path1Publisher = node.advertise<nav_msgs::OccupancyGrid>("Hexagon_map", 20);
00122 
00123     Getcloudpointssuber = node.subscribe("/rslidar_points", 100, &PointcloudCallback);
00124 
00125     hexagon_map_ = new hexagon_map(R,resolution);
00126 
00127     // std::cout<<"input num "<<std::endl;
00128     // float X,Y;
00129     // std::cin>>X;
00130     // std::cin>>Y;
00131     // CPoint2d tempoint;
00132     // tempoint.x = X;
00133     // tempoint.y = Y;
00134 
00135     // CPoint2d Centerp;
00136     // Centerp = hexagon_map_.JudgeHexCenpoint(tempoint);
00137     // std::cout<<"Centerp is "<<Centerp.x<<" "<<Centerp.y<<std::endl;
00138     // int count = 250;
00139     // hexagon_map_.drawplogon(Centerp.x,Centerp.y,hexagon_map_.Resulution_L,count);
00140     
00141  //    gridmap.header.frame_id = "/camera_init";
00142  //    gridmap.header.stamp = ros::Time::now();
00143  //    gridmap.info.resolution = 0.01;
00144  //    gridmap.info.width = 3600;
00145  //    gridmap.info.height = 3600;
00146  //    gridmap.info.origin.position.x = -18.0;
00147  //    gridmap.info.origin.position.y = -18.0;
00148  //    gridmap.info.origin.position.z = 0.0;
00149 
00150  //    gridmap.data.assign(gridmap.info.width*gridmap.info.height,0);
00151 
00152  //    std::vector<int> flagmap;
00153  //    flagmap.assign(gridmap.info.width*gridmap.info.height,0);
00154 
00155  //    float L = 0.2;
00156         // std::cout<<L<<std::endl;
00157         
00158         // CPoint2d Centerpoint;
00159         // Centerpoint.x = 0.0;
00160         // Centerpoint.y = 0.0;
00161         
00162 
00163         // std::queue<CPoint2d> Pointqueue;
00164 
00165  //    int geshu = 0;
00166 
00167  //    std::cout<<"--------Centerpoint--------- "<<Centerpoint.x<<" "<<Centerpoint.y<<std::endl;
00168  //    int d_x = (Centerpoint.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00169  //    int d_y = (Centerpoint.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00170  //    int inde_x = d_x + d_y * gridmap.info.width;
00171  //    std::cout<<"inde_x "<<inde_x<<std::endl;
00172  //    flagmap[inde_x] = 1;
00173  //    geshu++;
00174 
00175  //    Pointset.push_back(Centerpoint);
00176     
00177  //    Pointqueue.push(Centerpoint);
00178 
00179         // while(!Pointqueue.empty())
00180         // {
00181         //      int size = Pointset.size();
00182  //        int size1 = Pointqueue.size();
00183         //      std::cout<<"------------------------ "<<size<<std::endl;
00184  //        std::cout<<"Pointqueue size is "<<size1<<std::endl;
00185  //        std::cout<<"geshu is ........"<<std::endl;        
00186  //        std::cout<<geshu<<std::endl;
00187  //        if(geshu==6163)
00188  //        {
00189  //            break;
00190 
00191  //        }
00192         //      /*if(size==91)
00193         //      {
00194         //              break;
00195         //      }*/
00196 
00197         //      int angle[]={60,120,180,240,300};
00198                 
00199         //      CPoint2d Genepoint;
00200         //      Genepoint = Pointqueue.front();
00201         //      Pointqueue.pop();
00202 
00203         //      std::cout<<"loop begin_________________________Genepoint "<<Genepoint.x<<" "<<Genepoint.y<<std::endl;
00204 
00205         //      CPoint2d tempoint;
00206                 
00207         //      tempoint.x = Genepoint.x + 4.5 * L;
00208         //      tempoint.y = Genepoint.y + -L * tan(60*3.1415926/180)/2;
00209         //      tempoint.pointangle = atan2(-L * tan(60*3.1415926/180)/2, 4.5 * L);
00210         //      float R = sqrt(4.5 * L * 4.5 * L + -L * tan(60*3.1415926/180)/2 * -L * tan(60*3.1415926/180)/2);
00211 
00212         //      int dx_ = (tempoint.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00213  //        int dy_ = (tempoint.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00214  //        int index_ = dx_ + dy_ * gridmap.info.width;
00215         //      std::cout<<"tempoint "<<tempoint.x<<" "<<tempoint.y<<std::endl;
00216  //        std::cout<<" index_ "<<index_<<std::endl;
00217  //        geshu++;
00218 
00219  //        if(flagmap[index_]!=0 || isInpointset(tempoint))
00220  //        {   
00221  //             std::cout<<" chongfu_____ "<<std::endl;
00222  //        }
00223         //     else
00224         //     {
00225  //            Pointset.push_back(tempoint);
00226         //              Pointqueue.push(tempoint);
00227  //            flagmap[index_] = 1;
00228         //     }
00229 
00230 
00231 
00232         //      for(int i=0;i<5;i++)
00233         //      {
00234         //              CPoint2d Othertempoint;
00235         //              Othertempoint.x = Genepoint.x + R * cos((tempoint.pointangle * 180 /3.1415926 + angle[i])*3.1415926/180);
00236         //              Othertempoint.y = Genepoint.y + R * sin((tempoint.pointangle * 180 /3.1415926 + angle[i])*3.1415926/180);
00237                     
00238                     
00239                     
00240         //          int d_x2 = (Othertempoint.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00241         //          int d_y2 = (Othertempoint.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00242         //          int inde_x2 = d_x2 + d_y2 * gridmap.info.width;
00243         //          //flagmap[inde_x2] = 1;
00244         //              std::cout<<"-------first Othertempoint "<<Othertempoint.x<<" "<<Othertempoint.y<<std::endl;
00245         //          std::cout<<"inde_x2 "<<inde_x2<<std::endl;
00246  //            geshu++;
00247 
00248         //              if(flagmap[inde_x2]!=0 || isInpointset(Othertempoint))
00249  //            {
00250  //                std::cout<<"chongfu"<<inde_x2<<std::endl;
00251  //                continue;
00252  //            }
00253  //            else
00254  //            {
00255  //                Pointset.push_back(Othertempoint);
00256         //                      Pointqueue.push(Othertempoint);
00257  //             flagmap[inde_x2] = 1;
00258  //            }
00259         //      }
00260         // }
00261     
00262 
00263 /*      
00264         int angle[]={60,120,180,240,300};
00265         
00266         CPoint2d tempoint;
00267         tempoint.x = 4.5 * L;
00268         tempoint.y = -L * tan(60*3.1415926/180)/2;
00269         tempoint.pointangle = atan2(tempoint.y,tempoint.x); 
00270         float R = sqrt(tempoint.x * tempoint.x + tempoint.y * tempoint.y);
00271 
00272 
00273     std::cout<<"----first tempoint "<<tempoint.x<<" "<<tempoint.y<<std::endl;
00274     int d_x1 = (tempoint.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00275     int d_y1 = (tempoint.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00276     int inde_x1 = d_x1 + d_y1 * gridmap.info.width;
00277     flagmap[inde_x1] = 1;
00278     std::cout<<"inde_x1 "<<inde_x1<<std::endl;
00279 
00280         Pointset.push_back(tempoint);
00281         
00282         for(int i=0;i<5;i++)
00283         {
00284                 CPoint2d Othertempoint;
00285                 Othertempoint.x = Centerpoint.x + R * cos((tempoint.pointangle * 180 /3.1415926 + angle[i])*3.1415926/180);
00286                 Othertempoint.y = Centerpoint.y + R * sin((tempoint.pointangle * 180 /3.1415926 + angle[i])*3.1415926/180);
00287         
00288         
00289         std::cout<<"-------first Othertempoint "<<Othertempoint.x<<" "<<Othertempoint.y<<std::endl;
00290         int d_x2 = (Othertempoint.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00291         int d_y2 = (Othertempoint.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00292         int inde_x2 = d_x2 + d_y2 * gridmap.info.width;
00293         flagmap[inde_x2] = 1;
00294         std::cout<<"inde_x2 "<<inde_x2<<std::endl;
00295 
00296                 Pointset.push_back(Othertempoint);
00297                 
00298         //std::cout<<" Othertempoint "<<Othertempoint.x<<" "<<Othertempoint.y<<std::endl;
00299         }
00300 
00301 
00302     
00303     std::cout<<Pointset.size()<<std::endl;
00304     std::cout<<"----------------------------"<<std::endl;
00305 
00306     std::vector<CPoint2d> PointsetCopy;
00307     PointsetCopy = Pointset;
00308 
00309     for(int i=1;i<Pointset.size();i++)
00310     {
00311         CPoint2d Cpoint;
00312         Cpoint = Pointset[i];
00313         std::cout<<"--------- shengcheng Cpoint------------------------ "<<Cpoint.x<<" "<<Cpoint.y<<std::endl;
00314 
00315         CPoint2d tem;
00316         tem.x = Cpoint.x + 4.5 * L;
00317             tem.y = Cpoint.y + -L * tan(60*3.1415926/180)/2;
00318             tem.pointangle = atan2(-L * tan(60*3.1415926/180)/2, 4.5 * L);
00319         
00320 
00321         std::cout<<"tem "<<tem.x<<" "<<tem.y<<std::endl;
00322         int dx_ = (tem.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00323         int dy_ = (tem.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00324         int index_ = dx_ + dy_ * gridmap.info.width;
00325         std::cout<<" index_ "<<index_<<std::endl;
00326 
00327         if(flagmap[index_]!=0)
00328         {   
00329              std::cout<<" chongfu_____ "<<std::endl;
00330         }
00331             else
00332             {
00333             PointsetCopy.push_back(tem);
00334             flagmap[index_] = 1;
00335             }
00336    
00337 
00338         //PointsetCopy.push_back(tem);
00339         //flagmap[inde_x2] = 1;
00340       
00341 
00342         for(int j=0;j<5;j++)
00343             {
00344 
00345                     CPoint2d Othertempoint1;
00346                     Othertempoint1.x = Cpoint.x + R * cos((tempoint.pointangle * 180 /3.1415926 + angle[j])*3.1415926/180);
00347                     Othertempoint1.y = Cpoint.y + R * sin((tempoint.pointangle * 180 /3.1415926 + angle[j])*3.1415926/180);
00348         
00349 
00350             std::cout<<"Othertempoint1 "<<Othertempoint1.x<<" "<<Othertempoint1.y<<std::endl;
00351             int d_x21 = (Othertempoint1.x - gridmap.info.origin.position.x)/gridmap.info.resolution;
00352             int d_y21 = (Othertempoint1.y - gridmap.info.origin.position.y)/gridmap.info.resolution;
00353             int inde_x21 = d_x21 + d_y21 * gridmap.info.width;
00354             std::cout<<"inde_x21 "<<inde_x21<<std::endl;
00355 
00356 
00357             
00358             if(flagmap[inde_x21]!=0)
00359             {
00360                 std::cout<<"chongfu"<<inde_x21<<std::endl;
00361                 continue;
00362             }
00363             else
00364             {
00365                  PointsetCopy.push_back(Othertempoint1);
00366                  flagmap[inde_x21] = 1;
00367             }
00368     
00369            // PointsetCopy.push_back(Othertempoint1);
00370             }
00371    }
00372 
00373     std::cout<<"-------- "<<PointsetCopy.size()<<std::endl;
00374 
00375     Pointset.clear();
00376     Pointset = PointsetCopy;
00377 */
00378     // std::cout<<"--------------- Pointset.size() "<<Pointset.size()<<std::endl;
00379     // for(int i=0;i<Pointset.size();i++)
00380     // {
00381     //     std::cout<<"Pointset "<<Pointset[i].x<<" "<<Pointset[i].y<<std::endl;
00382     //     drawplogon(Pointset[i].x,Pointset[i].y,L);
00383     // }
00384 
00385  //    int singleangle[]={30,90,150,210,270,330};
00386         // float r1 = L * tan(60*3.1415926/180);
00387         
00388         // for(int i = 0;i<Pointset.size();i++)
00389         // {
00390         //      count = count - 2;
00391         //      drawplogon(Pointset[i].x,Pointset[i].y,L);
00392                 
00393   
00394         //      for(int j=0;j<6;j++)
00395         //      {
00396         //                      CPoint2d temppoint;
00397         //                      temppoint.x = Pointset[i].x + r1 * cos(singleangle[j] * 3.1415926/180);
00398         //                      temppoint.y = Pointset[i].y + r1 * sin(singleangle[j] * 3.1415926/180);
00399         //                      count = count - 2;
00400         //                      drawplogon(temppoint.x,temppoint.y,L);
00401         //      }
00402         // }
00403 
00404 
00405 
00406    /* for(int i = 1;i<Pointset.size();i++)
00407     {
00408         CPoint2d Cpoint;
00409         Cpoint = Pointset[i];
00410 
00411         CPoint2d tempoint;
00412         tempoint.x = Cpoint.x + 4.5 * L;
00413             tempoint.y = Cpoint.y + -L * tan(60*3.1415926/180)/2;
00414             tempoint.pointangle = atan2(-L * tan(60*3.1415926/180)/2, 4.5 * L); 
00415 
00416         Pointset.push_back(tempoint);
00417 
00418         for(int j=0;j<5;j++)
00419             {
00420                     CPoint2d Othertempoint1;
00421                     Othertempoint1.x = Cpoint.x + R * cos((tempoint.pointangle * 180 /3.1415926 + angle[j])*3.1415926/180);
00422                     Othertempoint1.y = Cpoint.y + R * sin((tempoint.pointangle * 180 /3.1415926 + angle[j])*3.1415926/180);
00423                     Pointset.push_back(Othertempoint1);
00424                 
00425             std::cout<<" Othertempoint1 "<<Othertempoint1.x<<" "<<Othertempoint1.y<<std::endl;
00426             }
00427     }*/
00428 
00429 
00430         
00431         
00432         
00433         
00434         /*
00435         for(int i = -4;i<=4;i++)
00436                 //int i = 0;
00437                 for(int j=-5;j<=5;j++)
00438                 {
00439                         if(j%2==0)
00440                         {
00441                                 C_x = 0.0 + j * 3 * L /2;
00442                                 C_y = 0.0 + i * tan(60*3.1415926/180) * L;
00443                         }
00444                         else
00445                         {
00446                                 C_x = 0.0 + j * 3 * L /2;
00447                                 C_y = 0.0 + i * tan(60*3.1415926/180) * L + 
00448                                                         tan(60*3.1415926/180) * L / 2;
00449                         
00450                         }
00451                         //std::cout<<"C_x C_y "<<C_x<<" "<<C_y<<std::endl;
00452                         drawplogon(C_x, C_y,L);
00453                         count = count + 5;
00454                 }*/
00455         
00456     /*L = 0.05;
00457     C_x = 0.0;
00458     C_y = 0.0;
00459     drawplogon(C_x,C_y,L);
00460 
00461 
00462     L = 0.05;
00463     C_x = 0.0 * L;
00464     C_y = -1.7321 * L;
00465     drawplogon(C_x, C_y,L);
00466 
00467     //L = 0.1;
00468     C_x = -1.5 * L;
00469     C_y = -0.866 * L;
00470     drawplogon(C_x, C_y,L);
00471 
00472 
00473     //L = 0.1;
00474     C_x = -1.5 * L;
00475     C_y = 0.866 * L;
00476     drawplogon(C_x, C_y,L);
00477 
00478 
00479     //L = 0.1;
00480     C_x = 0.0 * L;
00481     C_y = 1.7321 * L;
00482     drawplogon(C_x, C_y,L);
00483 
00484     //L = 0.1;
00485     C_x = 1.5 * L;
00486     C_y = 0.866 * L;
00487     drawplogon(C_x, C_y,L);
00488 
00489     
00490     //L = 0.1;
00491     C_x = 1.5 * L;
00492     C_y = -0.866 * L;
00493     drawplogon(C_x, C_y,L);*/
00494 
00495         // ros::Rate r(30);
00496         // while(ros::ok())
00497         // {
00498                 
00499         //      g_path1Publisher->publish(hexagon_map_.gridmap);
00500         //       r.sleep();
00501 
00502         // }
00503    
00504      ros::spin();
00505 
00506      delete hexagon_map_;
00507 
00508 }


hexagon_map
Author(s):
autogenerated on Thu Jun 6 2019 18:38:28