Go to the documentation of this file.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 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #include "ros/ros.h"
00037 
00038 #include "micros_hopfield/plan.h"
00039 
00040 #include "plan_visualization.h"
00041 
00042 
00043 #include "hopfield_algo.h"
00044 
00045 bool plan(micros_hopfield::plan::Request  &req,micros_hopfield::plan::Response &res )
00046 {
00047     
00048     
00049     g_Sx=req.sx;
00050     g_Sy=req.sy;
00051     g_Ex=req.ex;
00052     g_Ey=req.ey;
00053 
00054     if (g_SearchMap[g_Ey][g_Ex]<0) 
00055     {
00056              res.Route_Points=0;
00057         return true;
00058     }
00059 
00060     bool bInitDataRet=InitData();
00061     if (bInitDataRet)
00062         cout<<"Data Inited OK!"<<endl;
00063     else
00064         cout<<"Data Inited Error!"<<endl;
00065 
00066     if (Search())
00067         cout<<"search finish!"<<endl;
00068     else
00069     {
00070         cout<<"I can't find the path!"<<endl;
00071               res.Route_Points=0;
00072         return true;
00073     }
00074 
00075     
00076     POINT* m_Step;                              
00077     int m_nStep=GetRoad(&m_Step);
00078     if (m_nStep>0)
00079     {
00080         res.Route_X.clear();
00081         res.Route_Y.clear();
00082         for (int i=0;i<m_nStep;i++)
00083         {
00084            res.Route_X.push_back(m_Step[i].x);
00085            res.Route_Y.push_back(m_Step[i].y);
00086         }
00087         res.Route_Points=m_nStep;
00088         
00089         delete [] m_Step;
00090     }
00091         
00092     return true;
00093 }
00094 
00095 int main(int argc, char **argv)
00096 {
00097   ros::init(argc, argv, "Plan_server");
00098 
00099   ros::NodeHandle n;
00100   ros::ServiceServer service = n.advertiseService("Planner", plan);
00101   ROS_INFO("Ready to Plan.");
00102 
00103   
00104   InitMarkerPublisher();
00105 
00106   
00107   if (!InitThreat()) 
00108         return false; 
00109   
00110   for (int j=0;j<g_ThreatsCount;j++)
00111         Draw_Cylinder( 3+j,g_Threats[j].center.x,g_Threats[j].center.y,25,g_Threats[j].range,50,0.0,1.0,1.0,1.0);
00112   
00113   InitTerrain(); 
00114   
00115   DrawTerrain(g_MapWidth,g_MapHeight,4,g_Terrain);
00116   
00117   BuildSearchMap();
00118 
00119   ros::spin();
00120 
00121   return 0;
00122 }