Cyclic.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2011, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: David Portugal, 2011
00036 *********************************************************************/
00037 
00038 #include <ros/ros.h>
00039 #include <move_base_msgs/MoveBaseAction.h>
00040 #include <actionlib/client/simple_action_client.h>
00041 #include <tf/transform_broadcaster.h>
00042 #include <nav_msgs/Odometry.h>
00043 
00044 #include "getgraph.h"
00045 #include "algorithms.h"
00046 
00047 #define NUM_MAX_ROBOTS 32
00048 
00049 typedef unsigned int uint;
00050 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00051 
00052 bool ResendGoal; //Send the same goal again (if goal failed...)
00053 bool interference;
00054 bool goal_complete;
00055 bool initialize = true;
00056 bool end_simulation = false;
00057 uint goalvertex;
00058 uint backUpCounter;
00059 
00060 int TEAMSIZE;
00061 int ID_ROBOT;
00062 
00063 double xPos[NUM_MAX_ROBOTS]; //tabelas de posições (atençao ao index pro caso de 1 so robot)
00064 double yPos[NUM_MAX_ROBOTS]; //tabelas de posições (atençao ao index pro caso de 1 so robot)
00065 
00066 ros::Subscriber odom_sub;
00067 ros::Publisher odom_pub;
00068 ros::Subscriber results_sub;
00069 ros::Publisher results_pub;
00070 ros::Publisher cmd_vel_pub;
00071 
00072 
00073 void send_goal_result (uint gvertex){
00074   /*
00075   string frame_id       //robot ID
00076     float64 x           //Goal (X=vertex,0,0)  
00077 */      
00078         printf("Send Vertex %u [Goal] to Results: Robot %d\n",gvertex,ID_ROBOT);        
00079         
00080         geometry_msgs::PointStamped msg;        
00081         char id_robot_str[3];
00082         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00083                 
00084         msg.header.frame_id = id_robot_str;
00085         msg.point.x = float (goalvertex);
00086         msg.point.y = 0.0; 
00087         msg.point.z = 0.0;
00088 
00089         results_pub.publish(msg);
00090         ros::spinOnce();
00091 }
00092 
00093 void backup(){
00094         
00095         while (backUpCounter<=100){
00096         
00097         if(backUpCounter==0){
00098                 ROS_INFO("The wall is too close! I need to do some backing up...");
00099                 // Move the robot back...
00100                 geometry_msgs::Twist cmd_vel;
00101                 cmd_vel.linear.x = -0.1;
00102                 cmd_vel.angular.z = 0.0;
00103                 cmd_vel_pub.publish(cmd_vel);
00104         }
00105                         
00106         if(backUpCounter==40){
00107                 // Turn the robot around...
00108                 geometry_msgs::Twist cmd_vel;
00109                 cmd_vel.linear.x = 0.0;
00110                 cmd_vel.angular.z = 0.5;
00111                 cmd_vel_pub.publish(cmd_vel);
00112         }
00113                         
00114         if(backUpCounter==100){
00115                 // Stop the robot...
00116                 geometry_msgs::Twist cmd_vel;
00117                 cmd_vel.linear.x = 0.0;
00118                 cmd_vel.angular.z = 0.0;
00119                 cmd_vel_pub.publish(cmd_vel);
00120                         
00121                 ROS_INFO("Done backing up, now on with my life!");              
00122         }
00123 
00124         backUpCounter++;
00125         }
00126         
00127 }
00128 
00129 void goalDoneCallback(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result){ //goal terminado (completo ou cancelado)
00130 //      ROS_INFO("Goal is complete (suceeded, aborted or cancelled).");
00131         // If the goal succeeded send a new one!
00132         //if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED) sendNewGoal = true;
00133         // If it was aborted time to back up!
00134         //if(state.state_ == actionlib::SimpleClientGoalState::ABORTED) needToBackUp = true;    
00135         
00136         if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED){
00137                 ROS_INFO("SUCCESS");
00138                 goal_complete = true;
00139                 send_goal_result (goalvertex);
00140 //              printf("goal complete = %d\n",goal_complete);
00141         }else{
00142                 ROS_INFO("CANCELLED or ABORTED...Resend Goal!");        //tentar voltar a enviar goal...
00143                 backUpCounter = 0;
00144                 backup();               
00145                 ResendGoal = true;
00146         }
00147 }
00148 
00149 void goalActiveCallback(){      //enquanto o robot esta a andar para o goal...
00150         goal_complete = false;
00151 //      ROS_INFO("Goal is active.");
00152 }
00153 
00154 void odomCB(const nav_msgs::Odometry::ConstPtr& msg) { //colocar propria posicao na tabela
00155         
00156 //      printf("Colocar Propria posição na tabela, ID_ROBOT = %d\n",ID_ROBOT);
00157         int idx = ID_ROBOT;
00158         
00159         if (ID_ROBOT<=-1){
00160                 idx = 0;
00161         }
00162         
00163         xPos[idx]=msg->pose.pose.position.x;
00164         yPos[idx]=msg->pose.pose.position.y;
00165         
00166 //      printf("Posicao colocada em Pos[%d]\n",idx);
00167 }
00168 
00169 void positionsCB(const nav_msgs::Odometry::ConstPtr& msg) {     //construir tabelas de posições
00170         
00171 //     printf("Construir tabela de posicoes (receber posicoes), ID_ROBOT = %d\n",ID_ROBOT);    
00172         
00173     char id[20]; //identificador do robot q enviou a msg d posição...
00174     strcpy( id, msg->header.frame_id.c_str() );
00175     //int stamp = msg->header.seq;
00176 //     printf("robot q mandou msg = %s\n", id);
00177     
00178     // Build Positions Table
00179     
00180     if (ID_ROBOT>-1){
00181         //verify id "XX" of robot: (string: "robot_XX/odom")
00182         
00183         char str_idx[4];
00184         uint i;
00185         
00186         for (i=6; i<10; i++){
00187                 if (id[i]=='/'){
00188                         str_idx[i-6] = '\0';
00189                         break;
00190                 }else{
00191                         str_idx[i-6] = id[i];
00192                 }
00193         }
00194         
00195         int idx = atoi (str_idx);
00196 //      printf("id robot q mandou msg = %d\n",idx);
00197         
00198         if (idx >= TEAMSIZE && TEAMSIZE <= NUM_MAX_ROBOTS){
00199                 //update teamsize:
00200                 TEAMSIZE = idx+1;
00201         }
00202         
00203         if (ID_ROBOT != idx){  //Ignore own positions   
00204                 xPos[idx]=msg->pose.pose.position.x;
00205                 yPos[idx]=msg->pose.pose.position.y;            
00206         }       
00207 //      printf ("Position Table:\n frame.id = %s\n id_robot = %d\n xPos[%d] = %f\n yPos[%d] = %f\n\n", id, idx, idx, xPos[idx], idx, yPos[idx] );           
00208     }
00209 }
00210 
00211 
00212 void resultsCB(const geometry_msgs::PointStamped::ConstPtr& msg) { //
00213         
00214         if(initialize){ //em espera que o monitor a desbloquei e passe initialize para false
00215                 
00216 //              printf("Is it the monitor? frame_id = %s (%f,%f,%f)\n",msg->header.frame_id.c_str(),msg->point.x,msg->point.y,msg->point.z);
00217                 
00218                 if (msg->header.frame_id == "monitor"){
00219                         printf("Let's Patrol!\n");
00220                         initialize = false;
00221                 }
00222         }else {
00223                 if (msg->header.frame_id == "monitor" && msg->point.x == 1.0 && msg->point.y == 1.0 && msg->point.z == 1.0){
00224                         printf("The simulation is over. Let's leave\n");
00225                         end_simulation = true;
00226                 }               
00227         }
00228 }
00229 
00230 void initialize_node (){
00231   /*
00232   string frame_id       //robot ID
00233     float64 z           //initialization (0,0,Z=ID)  
00234 */      
00235         printf("Initialize Node: Robot %d\n",ID_ROBOT); 
00236         ros::Rate loop_rate(1); //1 segundo
00237         
00238         geometry_msgs::PointStamped msg;        
00239         
00240         char id_robot_str[3];
00241         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00242                 
00243         msg.header.frame_id = id_robot_str;
00244         msg.point.x = 0.0;
00245         msg.point.y = 0.0; 
00246         msg.point.z = (float) ID_ROBOT; //Z = ID
00247         
00248         int count = 0;
00249         while (count<2){
00250                 results_pub.publish(msg);
00251                 ros::spinOnce();
00252                 //printf("publiquei msg.\n");
00253                 loop_rate.sleep();
00254                 count++;
00255         }       
00256 }
00257 
00258 void send_interference(){
00259   /*
00260   string frame_id       //robot ID
00261     float64 y           //Interference (0,Y=1,0)  
00262 */      
00263         printf("Send Interference: Robot %d\n",ID_ROBOT);       
00264         //ros::Rate loop_rate(1); //1 segundo
00265         
00266         geometry_msgs::PointStamped msg;        
00267         char id_robot_str[3];
00268         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00269                 
00270         msg.header.frame_id = id_robot_str;
00271         msg.point.x = 0.0;
00272         msg.point.y = 1.0; 
00273         msg.point.z = 0.0;
00274 
00275         results_pub.publish(msg);
00276         ros::spinOnce();
00277 }
00278 
00279 
00280 bool check_interference (void){ //verificar se os robots estao proximos
00281         
00282         int i;
00283         double dist_quad;
00284         
00285         /* Poderei usar TEAMSIZE para afinar */
00286         for (i=0; i<ID_ROBOT; i++){     //percorrer vizinhos (assim asseguro q cada interferencia é so encontrada 1 vez)
00287                 
00288                 dist_quad = (xPos[i] - xPos[ID_ROBOT])*(xPos[i] - xPos[ID_ROBOT]) + (yPos[i] - yPos[ID_ROBOT])*(yPos[i] - yPos[ID_ROBOT]);
00289                 
00290                 if (dist_quad <= /*sqrt*/4){    //robots are 2 meter or less apart
00291 //                      ROS_INFO("Feedback: Robots are very close. INTERFERENCE! Dist_Quad = %f", dist_quad);
00292                         interference = true;
00293                         return interference;
00294                 }               
00295         }
00296         
00297         interference = false;
00298         return interference;
00299         
00300 }
00301 
00302 void goalFeedbackCallback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback){    //publicar posições
00303 
00304 //      printf("ID_ROBOT = %d [feedback callback]\n", ID_ROBOT);
00305         
00306         //Publish Position to common node:
00307         nav_msgs::Odometry msg; 
00308         
00309         int idx = ID_ROBOT;
00310                 
00311         if (ID_ROBOT <= -1){
00312                 msg.header.frame_id = "odom";    //identificador do robot q publicou
00313                 idx = 0;
00314         }else{
00315                 char string[20];
00316                 strcpy (string,"robot_"); 
00317                 char id[3];
00318                 itoa(ID_ROBOT, id, 10);  
00319                 strcat(string,id);
00320                 strcat(string,"/odom"); //string = "robot_X/odom"       
00321                 //strcpy( msg.header.frame_id, string );
00322                 msg.header.frame_id = string;
00323         }
00324         
00325         msg.pose.pose.position.x = xPos[idx]; //send odometry.x
00326         msg.pose.pose.position.y = yPos[idx]; //send odometry.y
00327         
00328         odom_pub.publish(msg);
00329         ros::spinOnce();
00330         
00331         //ROS_INFO("[POSITION PUBLISHED]: ID = %s, X = %f, Y = %f", msg.header.frame_id.c_str(), xPos[idx], yPos[idx]);
00332 //      printf("ID_ROBOT = %d\n", ID_ROBOT);
00333 //      printf("TEAMSIZE = %d\n", TEAMSIZE);    
00334         check_interference();   
00335 }
00336 
00337 int main(int argc, char** argv){        //pass the .graph file to open
00338   /*
00339   argc=3
00340   argv[0]=/.../patrolling_sim/bin/Cyclic
00341   argv[1]=__name:=XXXXXX
00342   argv[2]=maps/1r-5-map.graph
00343   argv[3]=ID_ROBOT
00344   */
00345   
00346   //More than One robot (ID between 0 and 99)
00347   if ( atoi(argv[3])>NUM_MAX_ROBOTS || atoi(argv[3])<-1 ){
00348     ROS_INFO("The Robot's ID must be an integer number between 0 an 99"); //max 100 robots 
00349     return 0;
00350   }else{
00351     ID_ROBOT = atoi(argv[3]); 
00352     //printf("ID_ROBOT = %d\n",ID_ROBOT); //-1 in the case there is only 1 robot.
00353   }
00354 
00355   uint i = strlen( argv[2] );
00356   char graph_file[i];
00357   strcpy (graph_file,argv[2]);
00358   
00359   //Check Graph Dimension:
00360   uint dimension = GetGraphDimension(graph_file);
00361   
00362   //Create Structure to save the Graph Info;
00363   vertex vertex_web[dimension];
00364   
00365   //Get the Graph info from the Graph File
00366   GetGraphInfo(vertex_web, dimension, graph_file);
00367   
00368   uint j;
00369   
00370   
00371   
00372   /* Output Graph Data */
00373   for (i=0;i<dimension;i++){
00374     printf ("ID= %u\n", vertex_web[i].id);
00375     printf ("X= %f, Y= %f\n", vertex_web[i].x, vertex_web[i].y);
00376     printf ("#Neigh= %u\n", vertex_web[i].num_neigh);
00377         
00378     for (j=0;j<vertex_web[i].num_neigh; j++){
00379       printf("\tID = %u, DIR = %s, COST = %u\n", vertex_web[i].id_neigh[j], vertex_web[i].dir[j], vertex_web[i].cost[j]);
00380     }
00381     
00382     printf("\n");       
00383   }
00384   
00385   
00386   
00387   /* Define Starting Vertex/Position (Launch File Parameters) */
00388 
00389   ros::init(argc, argv, "cyclic");
00390   ros::NodeHandle nh;
00391   double initial_x, initial_y;
00392   
00393   XmlRpc::XmlRpcValue list;
00394   nh.getParam("initial_pos", list);
00395   ROS_ASSERT(list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00396   
00397   int value = ID_ROBOT;
00398   if (value == -1){value = 0;}
00399   
00400   ROS_ASSERT(list[2*value].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00401   initial_x = static_cast<double>(list[2*value]);
00402   
00403   ROS_ASSERT(list[2*value+1].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00404   initial_y = static_cast<double>(list[2*value+1]);
00405  
00406 //    printf("initial position: x = %f, y = %f\n", initial_x, initial_y);
00407   uint current_vertex = IdentifyVertex(vertex_web, dimension, initial_x, initial_y);
00408 //    printf("initial vertex = %d\n\n",current_vertex);
00409 
00410   //Publicar dados de "odom" para nó de posições
00411   odom_pub = nh.advertise<nav_msgs::Odometry>("positions", 1); //only concerned about the most recent
00412         
00413   //Subscrever posições de outros robots
00414   odom_sub = nh.subscribe("positions", 10, positionsCB);  
00415   
00416   char string[20];
00417   char string2[20];
00418   
00419   if(ID_ROBOT==-1){ 
00420     strcpy (string,"odom"); //string = "odom"
00421     strcpy (string2,"cmd_vel"); //string = "cmd_vel"
00422     TEAMSIZE = 1;
00423   }else{ 
00424     strcpy (string,"robot_"); 
00425     strcpy (string2,"robot_"); 
00426     char id[3];
00427     itoa(ID_ROBOT, id, 10);  
00428     strcat(string,id);
00429     strcat(string2,id);
00430     strcat(string,"/odom"); //string = "robot_X/odom"  
00431     strcat(string2,"/cmd_vel"); //string = "robot_X/cmd_vel"
00432     TEAMSIZE = ID_ROBOT + 1;
00433   }         
00434   
00435 //   printf("string de publicação da odometria: %s\n",string);
00436   
00437    //Cmd_vel to backup:
00438    cmd_vel_pub  = nh.advertise<geometry_msgs::Twist>(string2, 1);    
00439   
00440   //Subscrever para obter dados de "odom" do robot corrente
00441   ros::Subscriber sub;
00442   sub = nh.subscribe(string, 1, odomCB); //size of the buffer = 1 (?)
00443   ros::spinOnce();    
00444     
00445   
00446   /* Define Goal */    
00447   
00448   if(ID_ROBOT==-1){ 
00449     strcpy (string,"move_base"); //string = "move_base"  (Single Robot in Simulation)
00450   }else{ 
00451     strcpy (string,"robot_"); 
00452     char id[3];
00453     itoa(ID_ROBOT, id, 10);  
00454     strcat(string,id);
00455     strcat(string,"/move_base"); //string = "robot_X/move_base"  (Multi-Robot Simulation)
00456   }
00457   
00458   //printf("string = %s\n",string);
00459   MoveBaseClient ac(string, true); 
00460   
00461   //wait for the action server to come up
00462   while(!ac.waitForServer(ros::Duration(5.0))){
00463      ROS_INFO("Waiting for the move_base action server to come up");
00464   }  
00465 
00466   //Define Goal:
00467   move_base_msgs::MoveBaseGoal goal;
00468     
00469    //Publicar dados para "results"
00470   results_pub = nh.advertise<geometry_msgs::PointStamped>("results", 1); //only concerned about the most recent
00471   results_sub = nh.subscribe("results", 10, resultsCB); //Subscrever "results" vindo dos robots
00472   
00473   initialize_node(); //dizer q está vivo
00474   ros::Rate loop_rate(1); //1 segundo
00475   
00476   /* Wait until all nodes are ready.. */
00477   while(initialize){
00478         ros::spinOnce();
00479         loop_rate.sleep();
00480   }   
00481   
00482   /* Run Algorithm */
00483   
00484   //Already have current_vertex;
00485   uint next_vertex;
00486   
00487   //robot's cyclic path:
00488   int path [4*dimension];
00489   
00490   //get cyclic path:
00491   int path_elements = cyclic(dimension, vertex_web, path);
00492   
00493   //Shift the cyclic path to start at the current vertex:
00494   shift_cyclic_path (current_vertex, path, path_elements);
00495 
00496   
00497   printf("\nFinal Path: ");
00498   for(i=0; i<path_elements; i++){
00499         if(i==path_elements-1){ printf("%i\n", path[i]); }else{ printf("%i, ", path[i]); }
00500   }
00501   printf("Number of elements = %i\n", path_elements);
00502   
00503   if(path_elements>1){ i=1; next_vertex = path[i]; }
00504   
00505   interference = false;
00506   ResendGoal = false;
00507   goal_complete = true;
00508   
00509   while(1){
00510     
00511     if(goal_complete){  
00512         //printf("Move Robot to Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00513         
00514         //Send the goal to the robot (Global Map)
00515         geometry_msgs::Quaternion angle_quat = tf::createQuaternionMsgFromYaw(0.0);
00516         goal.target_pose.header.frame_id = "map"; 
00517         goal.target_pose.header.stamp = ros::Time::now();    
00518         goal.target_pose.pose.position.x = vertex_web[next_vertex].x;
00519         goal.target_pose.pose.position.y = vertex_web[next_vertex].y;  
00520         goal.target_pose.pose.orientation = angle_quat;
00521         ROS_INFO("Sending goal - Vertex %d (%f,%f)", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00522         goalvertex = next_vertex;
00523         ac.sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00524         //ac.waitForResult();
00525         
00526         current_vertex = next_vertex;
00527         i++;
00528         if ( i>=path_elements ){ i=1;}
00529         next_vertex = path[i];    
00530         goal_complete = false; //so volta a entrar aqui quando chegar ao goal...
00531     
00532     }else{
00533         if (interference){
00534                                                 
00535                 // Stop the robot..                     
00536                 ROS_INFO("Interference detected!\n");   
00537                 send_interference();
00538 
00539                 //get own "odom" positions...
00540                 ros::spinOnce();                
00541                                         
00542                 //Waiting until conflict is solved...
00543                 while(interference){
00544                         interference = check_interference();
00545                         if (goal_complete || ResendGoal){
00546                                 interference = false;
00547                         }
00548                 }
00549                 // se saiu é pq interference = false                   
00550         }           
00551             
00552         if(ResendGoal){
00553                 //Send the goal to the robot (Global Map)
00554                 geometry_msgs::Quaternion angle_quat = tf::createQuaternionMsgFromYaw(0.0);         
00555                 goal.target_pose.header.frame_id = "map"; 
00556                 goal.target_pose.header.stamp = ros::Time::now();    
00557                 goal.target_pose.pose.position.x = vertex_web[current_vertex].x;
00558                 goal.target_pose.pose.position.y = vertex_web[current_vertex].y;  
00559                 goal.target_pose.pose.orientation = angle_quat; //alpha -> orientação  (queria optimizar este parametro -> através da direcção do vizinho!)
00560                 ROS_INFO("Sending goal - Vertex %d (%f,%f)\n", current_vertex, vertex_web[current_vertex].x, vertex_web[current_vertex].y);
00561 //              printf("ID_ROBOT = %d\n", ID_ROBOT);
00562                 goalvertex = current_vertex;
00563                 ac.sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00564                 ResendGoal = false; //para nao voltar a entrar (envia goal so uma vez)
00565         }
00566                 
00567         if(end_simulation){
00568                 return 0;
00569         }               
00570             
00571     }
00572     
00573   }
00574   
00575   return 0; 
00576 }


patrolling_sim
Author(s): David Portugal
autogenerated on Mon Jan 6 2014 11:26:29