plan_server.cpp
Go to the documentation of this file.
00001 /*
00002 * Software License Agreement (BSD License)
00003 *Copyright (c) 2015, micROS Team
00004    http://micros.nudt.edu.cn/
00005 *All rights reserved.
00006 * Copyright (c) 2009, Willow Garage, Inc.
00007 * All rights reserved.
00008 *
00009 * Redistribution and use in source and binary forms, with or without
00010 * modification, are permitted provided that the following conditions
00011 * are met:
00012 *
00013 * * Redistributions of source code must retain the above copyright
00014 * notice, this list of conditions and the following disclaimer.
00015 * * Redistributions in binary form must reproduce the above
00016 * copyright notice, this list of conditions and the following
00017 * disclaimer in the documentation and/or other materials provided
00018 * with the distribution.
00019 * * Neither the name of Willow Garage, Inc. nor the names of its
00020 * contributors may be used to endorse or promote products derived
00021 * from this software without specific prior written permission.
00022 *
00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 * POSSIBILITY OF SUCH DAMAGE.
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     //initialize
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     //save the path
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   //publish the marker in rviz
00104   InitMarkerPublisher();
00105 
00106   //input the threat position
00107   if (!InitThreat()) 
00108         return false; 
00109   //Draw the threat area in the rviz
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   //input the terrain description file
00113   InitTerrain(); 
00114   //draw the terrain in rviz
00115   DrawTerrain(g_MapWidth,g_MapHeight,4,g_Terrain);
00116   
00117   BuildSearchMap();
00118 
00119   ros::spin();
00120 
00121   return 0;
00122 }


micros_hopfield
Author(s): Xiaojia Xiang
autogenerated on Thu Jun 6 2019 21:05:58