SEBS.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 int next_vertex = -1;
00058 uint backUpCounter;
00059 
00060 //To calculate global idleness:
00061 bool arrived = false;
00062 uint vertex_arrived;
00063 int robot_arrived;
00064 
00065 //To calculate robot's state:
00066 bool intention = false;
00067 uint vertex_intention;
00068 int robot_intention;
00069 
00070 int TEAMSIZE;
00071 int ID_ROBOT;
00072 
00073 double xPos[NUM_MAX_ROBOTS]; //tabelas de posições (atençao ao index pro caso de 1 so robot)
00074 double yPos[NUM_MAX_ROBOTS]; //tabelas de posições (atençao ao index pro caso de 1 so robot)
00075 
00076 ros::Subscriber odom_sub;
00077 ros::Publisher odom_pub;
00078 ros::Subscriber results_sub;
00079 ros::Publisher results_pub;
00080 ros::Publisher cmd_vel_pub;
00081 
00082 void send_goal_result (uint vertex){
00083   /*
00084   string frame_id       //robot ID
00085     float64 x           //Goal (X=vertex,0,0)  
00086 */      
00087         printf("Send Vertex %u [Goal] to Results: Robot %d\n",vertex,ID_ROBOT); 
00088         
00089         geometry_msgs::PointStamped msg;        
00090         char id_robot_str[3];
00091         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00092                 
00093         msg.header.frame_id = id_robot_str;
00094         msg.point.x = float (vertex);
00095         msg.point.y = 0.0; 
00096         msg.point.z = 0.0;
00097 
00098         results_pub.publish(msg);
00099         ros::spinOnce();
00100 }
00101 
00102 void send_intention (uint vertex){
00103   /*
00104   string frame_id       //robot ID
00105     float64 x           //Goal (X=vertex,0,0)  
00106 */      
00107         //printf("Send Intention %u [Vertex] to other robots: Robot %d\n",vertex,ID_ROBOT);     
00108         
00109         geometry_msgs::PointStamped msg;        
00110         char id_robot_str[3];
00111         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00112                 
00113         msg.header.frame_id = id_robot_str;
00114         msg.point.x = float (vertex);
00115         msg.point.y = 2.0;              //interf=2.0 identifies intention
00116         msg.point.z = 0.0;
00117 
00118         results_pub.publish(msg);
00119         ros::spinOnce();
00120 }
00121 
00122 void backup(){
00123         
00124         while (backUpCounter<=100){
00125         
00126         if(backUpCounter==0){
00127                 ROS_INFO("The wall is too close! I need to do some backing up...");
00128                 // Move the robot back...
00129                 geometry_msgs::Twist cmd_vel;
00130                 cmd_vel.linear.x = -0.1;
00131                 cmd_vel.angular.z = 0.0;
00132                 cmd_vel_pub.publish(cmd_vel);
00133         }
00134                         
00135         if(backUpCounter==40){
00136                 // Turn the robot around...
00137                 geometry_msgs::Twist cmd_vel;
00138                 cmd_vel.linear.x = 0.0;
00139                 cmd_vel.angular.z = 0.5;
00140                 cmd_vel_pub.publish(cmd_vel);
00141         }
00142                         
00143         if(backUpCounter==100){
00144                 // Stop the robot...
00145                 geometry_msgs::Twist cmd_vel;
00146                 cmd_vel.linear.x = 0.0;
00147                 cmd_vel.angular.z = 0.0;
00148                 cmd_vel_pub.publish(cmd_vel);
00149                         
00150                 ROS_INFO("Done backing up, now on with my life!");              
00151         }
00152 
00153         backUpCounter++;
00154         }
00155         
00156 }
00157 
00158 void goalDoneCallback(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result){ //goal terminado (completo ou cancelado)
00159 //      ROS_INFO("Goal is complete (suceeded, aborted or cancelled).");
00160         // If the goal succeeded send a new one!
00161         //if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED) sendNewGoal = true;
00162         // If it was aborted time to back up!
00163         //if(state.state_ == actionlib::SimpleClientGoalState::ABORTED) needToBackUp = true;    
00164         
00165         if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED){
00166                 ROS_INFO("SUCCESS");
00167                 goal_complete = true;
00168                 send_goal_result (next_vertex);
00169                 
00170         }else{
00171                 ROS_INFO("CANCELLED or ABORTED...BACKUP & Resend Goal!");       //tentar voltar a enviar goal..
00172                 backUpCounter = 0;
00173                 backup();
00174                 ResendGoal = true;
00175         }
00176 }
00177 
00178 void goalActiveCallback(){      //enquanto o robot esta a andar para o goal...
00179         goal_complete = false;
00180 //      ROS_INFO("Goal is active.");
00181 }
00182 
00183 void odomCB(const nav_msgs::Odometry::ConstPtr& msg) { //colocar propria posicao na tabela
00184         
00185 //      printf("Colocar Propria posição na tabela, ID_ROBOT = %d\n",ID_ROBOT);
00186         int idx = ID_ROBOT;
00187         
00188         if (ID_ROBOT<=-1){
00189                 idx = 0;
00190         }
00191         
00192         xPos[idx]=msg->pose.pose.position.x;
00193         yPos[idx]=msg->pose.pose.position.y;
00194         
00195 //      printf("Posicao colocada em Pos[%d]\n",idx);
00196 }
00197 
00198 void positionsCB(const nav_msgs::Odometry::ConstPtr& msg) {     //construir tabelas de posições
00199         
00200 //     printf("Construir tabela de posicoes (receber posicoes), ID_ROBOT = %d\n",ID_ROBOT);    
00201         
00202     char id[20]; //identificador do robot q enviou a msg d posição...
00203     strcpy( id, msg->header.frame_id.c_str() );
00204     //int stamp = msg->header.seq;
00205 //     printf("robot q mandou msg = %s\n", id);
00206     
00207     // Build Positions Table
00208     
00209     if (ID_ROBOT>-1){
00210         //verify id "XX" of robot: (string: "robot_XX/odom")
00211         
00212         char str_idx[4];
00213         uint i;
00214         
00215         for (i=6; i<10; i++){
00216                 if (id[i]=='/'){
00217                         str_idx[i-6] = '\0';
00218                         break;
00219                 }else{
00220                         str_idx[i-6] = id[i];
00221                 }
00222         }
00223         
00224         int idx = atoi (str_idx);
00225 //      printf("id robot q mandou msg = %d\n",idx);
00226         
00227         if (idx >= TEAMSIZE && TEAMSIZE <= NUM_MAX_ROBOTS){
00228                 //update teamsize:
00229                 TEAMSIZE = idx+1;
00230         }
00231         
00232         if (ID_ROBOT != idx){  //Ignore own positions   
00233                 xPos[idx]=msg->pose.pose.position.x;
00234                 yPos[idx]=msg->pose.pose.position.y;            
00235         }       
00236 //      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] );           
00237     }
00238 }
00239 
00240 void resultsCB(const geometry_msgs::PointStamped::ConstPtr& msg) {
00241         
00242         if(initialize){ //em espera que o monitor a desbloquei e passe initialize para false
00243                 
00244 //              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);
00245                 
00246                 if (msg->header.frame_id == "monitor"){
00247                         printf("Let's Patrol!\n");
00248                         initialize = false;
00249                 }
00250                 
00251         }else {
00252           
00253                 if (msg->header.frame_id == "monitor" && msg->point.x == 1.0 && msg->point.y == 1.0 && msg->point.z == 1.0){
00254                         printf("The simulation is over. Let's leave\n");
00255                         end_simulation = true;
00256                 
00257                   
00258                 }else if (msg->header.frame_id != "monitor")    {       //Robot reached Goal or is sending intention (including itself!!!)      
00259                   
00260                   double vert = msg->point.x;
00261                   double interf = msg->point.y;
00262                   double init = msg->point.z;
00263                   
00264                   if (interf == 0.0 && init == 0.0){                  
00265                       if (robot_arrived != ID_ROBOT){   //ignorar msgs do proprio robô:
00266 
00267                         robot_arrived = atoi( msg->header.frame_id.c_str() ); 
00268                         vertex_arrived = (int)vert;
00269                         arrived = true;                                       
00270                         //printf("Robot %d reached Goal %d.\n", robot_arrived, vertex_arrived);
00271                       }
00272                       
00273                    }else if(interf == 2.0 && init == 0.0) {             //ROBOT SENDING AN INTENTION
00274                         robot_intention = atoi (msg->header.frame_id.c_str());
00275                         vertex_intention = (int)vert;
00276                         intention = true;
00277                         //printf("Robot %d intends to go to vertex %d.\n", robot_intention, vertex_intention);
00278                    }              
00279                         
00280                 }
00281         }
00282 }
00283 
00284 void initialize_node (){
00285   /*
00286   string frame_id       //robot ID
00287     float64 z           //initialization (0,0,Z=ID)  
00288 */      
00289         printf("Initialize Node: Robot %d\n",ID_ROBOT); 
00290         ros::Rate loop_rate(1); //1 segundo
00291         
00292         geometry_msgs::PointStamped msg;        
00293         
00294         char id_robot_str[3];
00295         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00296                 
00297         msg.header.frame_id = id_robot_str;
00298         msg.point.x = 0.0;
00299         msg.point.y = 0.0; 
00300         msg.point.z = (float) ID_ROBOT; //Z = ID
00301         
00302         int count = 0;
00303         while (count<2){
00304                 results_pub.publish(msg);
00305                 ros::spinOnce();
00306                 //printf("publiquei msg.\n");
00307                 loop_rate.sleep();
00308                 count++;
00309         }       
00310 }
00311 
00312 void send_interference(){
00313   /*
00314   string frame_id       //robot ID
00315     float64 y           //Interference (0,Y=1,0)  
00316 */      
00317         printf("Send Interference: Robot %d\n",ID_ROBOT);       
00318         //ros::Rate loop_rate(1); //1 segundo
00319         
00320         geometry_msgs::PointStamped msg;        
00321         char id_robot_str[3];
00322         sprintf(id_robot_str, "%d", ID_ROBOT);  //integer to array
00323                 
00324         msg.header.frame_id = id_robot_str;
00325         msg.point.x = 0.0;
00326         msg.point.y = 1.0; 
00327         msg.point.z = 0.0;
00328 
00329         results_pub.publish(msg);
00330         ros::spinOnce();
00331 }
00332 
00333 bool check_interference (void){ //verificar se os robots estao proximos
00334         
00335         int i;
00336         double dist_quad;
00337         
00338         /* Poderei usar TEAMSIZE para afinar */
00339         for (i=0; i<ID_ROBOT; i++){     //percorrer vizinhos (assim asseguro q cada interferencia é so encontrada 1 vez)
00340                 
00341                 dist_quad = (xPos[i] - xPos[ID_ROBOT])*(xPos[i] - xPos[ID_ROBOT]) + (yPos[i] - yPos[ID_ROBOT])*(yPos[i] - yPos[ID_ROBOT]);
00342                 
00343                 if (dist_quad <= /*sqrt*/4){    //robots are 2 meter or less apart
00344 //                      ROS_INFO("Feedback: Robots are very close. INTERFERENCE! Dist_Quad = %f", dist_quad);
00345                         interference = true;
00346                         return interference;
00347                 }               
00348         }
00349         
00350         interference = false;
00351         return interference;
00352         
00353 }
00354 
00355 void goalFeedbackCallback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback){    //publicar posições
00356 
00357 //      printf("ID_ROBOT = %d [feedback callback]\n", ID_ROBOT);
00358         
00359         //Publish Position to common node:
00360         nav_msgs::Odometry msg; 
00361         
00362         int idx = ID_ROBOT;
00363                 
00364         if (ID_ROBOT <= -1){
00365                 msg.header.frame_id = "odom";    //identificador do robot q publicou
00366                 idx = 0;
00367         }else{
00368                 char string[20];
00369                 strcpy (string,"robot_"); 
00370                 char id[3];
00371                 itoa(ID_ROBOT, id, 10);  
00372                 strcat(string,id);
00373                 strcat(string,"/odom"); //string = "robot_X/odom"       
00374                 //strcpy( msg.header.frame_id, string );
00375                 msg.header.frame_id = string;
00376         }
00377         
00378         msg.pose.pose.position.x = xPos[idx]; //send odometry.x
00379         msg.pose.pose.position.y = yPos[idx]; //send odometry.y
00380         
00381         odom_pub.publish(msg);
00382         ros::spinOnce();
00383         
00384         //ROS_INFO("[POSITION PUBLISHED]: ID = %s, X = %f, Y = %f", msg.header.frame_id.c_str(), xPos[idx], yPos[idx]);
00385 //      printf("ID_ROBOT = %d\n", ID_ROBOT);
00386 //      printf("TEAMSIZE = %d\n", TEAMSIZE);    
00387         check_interference();   
00388 }
00389 
00390 
00391 int main(int argc, char** argv){        //pass the .graph file to open
00392   /*
00393   argc=3
00394   argv[0]=/.../patrolling_sim/bin/GBS
00395   argv[1]=__name:=XXXXXX
00396   argv[2]=maps/1r-5-map.graph
00397   argv[3]=ID_ROBOT
00398   argv[4]=NUMBER_OF_ROBOTS      //this is only necessary to automatically define G2
00399   */
00400   
00401   
00402   //More than One robot (ID between 0 and 99)
00403   if ( atoi(argv[3])>NUM_MAX_ROBOTS || atoi(argv[3])<-1 ){
00404     ROS_INFO("The Robot's ID must be an integer number between 0 an 99"); //max 100 robots 
00405     return 0;
00406   }else{
00407     ID_ROBOT = atoi(argv[3]); 
00408     //printf("ID_ROBOT = %d\n",ID_ROBOT); //-1 in the case there is only 1 robot.
00409   }
00410 
00411   uint i = strlen( argv[2] );
00412   char graph_file[i];
00413   strcpy (graph_file,argv[2]);
00414   
00415   //Check Graph Dimension:
00416   uint dimension = GetGraphDimension(graph_file);
00417   
00418   //Create Structure to save the Graph Info;
00419   vertex vertex_web[dimension];
00420   
00421   //Get the Graph info from the Graph File
00422   GetGraphInfo(vertex_web, dimension, graph_file);
00423   
00424   
00425   
00427   double G1 = 0.1;
00428   
00429   int NUMBER_OF_ROBOTS = atoi(argv[4]);
00430  
00431   //default:
00432   double G2 = 100.0;
00433   double edge_min = 1.0;
00434   
00435   if ( strcmp (graph_file,"maps/grid/grid.graph") == 0 ){  
00436     if (NUMBER_OF_ROBOTS == 1){G2 = 20.54;}
00437     if (NUMBER_OF_ROBOTS == 2){G2 = 17.70;}
00438     if (NUMBER_OF_ROBOTS == 4){G2 = 11.15;}
00439     if (NUMBER_OF_ROBOTS == 6){G2 = 10.71;}
00440     if (NUMBER_OF_ROBOTS == 8){G2 = 10.29;}
00441     if (NUMBER_OF_ROBOTS == 12){G2 = 9.13;}
00442     
00443   }else if (strcmp (graph_file,"maps/example/example.graph") == 0 ) {
00444     if (NUMBER_OF_ROBOTS == 1){G2 = 220.0;}
00445     if (NUMBER_OF_ROBOTS == 2){G2 = 180.5;}
00446     if (NUMBER_OF_ROBOTS == 4){G2 = 159.3;}
00447     if (NUMBER_OF_ROBOTS == 6){G2 = 137.15;}
00448     if (NUMBER_OF_ROBOTS == 8 || NUMBER_OF_ROBOTS == 12){G2 = 126.1;}
00449     edge_min = 20.0;
00450     
00451   }else if (strcmp (graph_file,"maps/cumberland/cumberland.graph") == 0) {
00452     if (NUMBER_OF_ROBOTS == 1){G2 = 152.0;}
00453     if (NUMBER_OF_ROBOTS == 2){G2 = 100.4;}
00454     if (NUMBER_OF_ROBOTS == 4){G2 = 80.74;}
00455     if (NUMBER_OF_ROBOTS == 6){G2 = 77.0;}
00456     if (NUMBER_OF_ROBOTS == 8 || NUMBER_OF_ROBOTS == 12){G2 = 63.5;}
00457     edge_min = 50.0;
00458     
00459   }
00460   
00461   printf("G1 = %f, G2 = %f\n", G1, G2);
00462   
00463   
00464    
00465   /* Define Starting Vertex/Position (Launch File Parameters) */
00466 
00467   ros::init(argc, argv, "c_reactive");
00468   ros::NodeHandle nh;
00469   double initial_x, initial_y;
00470   
00471   XmlRpc::XmlRpcValue list;
00472   nh.getParam("initial_pos", list);
00473   ROS_ASSERT(list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00474   
00475   int value = ID_ROBOT;
00476   if (value == -1){value = 0;}
00477   
00478   ROS_ASSERT(list[2*value].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00479   initial_x = static_cast<double>(list[2*value]);
00480   
00481   ROS_ASSERT(list[2*value+1].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00482   initial_y = static_cast<double>(list[2*value+1]);
00483  
00484 //   printf("initial position: x = %f, y = %f\n", initial_x, initial_y);
00485   uint current_vertex = IdentifyVertex(vertex_web, dimension, initial_x, initial_y);
00486 //   printf("initial vertex = %d\n\n",current_vertex);  
00487   
00488   
00489   //INITIALIZE tab_intention:
00490   int tab_intention[NUMBER_OF_ROBOTS];
00491   for (i=0; i<NUMBER_OF_ROBOTS; i++){
00492     tab_intention[i] = -1;
00493   }
00494   
00495   
00496    //Publicar dados de "odom" para nó de posições
00497   odom_pub = nh.advertise<nav_msgs::Odometry>("positions", 1); //only concerned about the most recent
00498         
00499   //Subscrever posições de outros robots
00500   odom_sub = nh.subscribe("positions", 10, positionsCB);  
00501   
00502   char string[20];
00503   char string2[20];
00504   
00505   if(ID_ROBOT==-1){ 
00506     strcpy (string,"odom"); //string = "odom"
00507     strcpy (string2,"cmd_vel"); //string = "cmd_vel"
00508     TEAMSIZE = 1;
00509   }else{ 
00510     strcpy (string,"robot_");
00511     strcpy (string2,"robot_"); 
00512     char id[3];
00513     itoa(ID_ROBOT, id, 10);  
00514     strcat(string,id);
00515     strcat(string2,id);
00516     strcat(string,"/odom"); //string = "robot_X/odom" 
00517     strcat(string2,"/cmd_vel"); //string = "robot_X/cmd_vel"
00518     TEAMSIZE = ID_ROBOT + 1;
00519   }       
00520   
00521 //   printf("string de publicação da odometria: %s\n",string);
00522 
00523    //Cmd_vel to backup:
00524    cmd_vel_pub  = nh.advertise<geometry_msgs::Twist>(string2, 1);
00525    
00526   //Subscrever para obter dados de "odom" do robot corrente
00527   ros::Subscriber sub;
00528   sub = nh.subscribe(string, 1, odomCB); //size of the buffer = 1 (?)
00529   ros::spinOnce();    
00530     
00531   
00532   /* Define Goal */  
00533   
00534   if(ID_ROBOT==-1){ 
00535     strcpy (string,"move_base"); //string = "move_base
00536   }else{ 
00537     strcpy (string,"robot_"); 
00538     char id[3];
00539     itoa(ID_ROBOT, id, 10);  
00540     strcat(string,id);
00541     strcat(string,"/move_base"); //string = "robot_X/move_base"  
00542   }
00543   
00544   //printf("string = %s\n",string);
00545   MoveBaseClient ac(string, true); 
00546   
00547   //wait for the action server to come up
00548   while(!ac.waitForServer(ros::Duration(5.0))){
00549      ROS_INFO("Waiting for the move_base action server to come up");
00550   }  
00551 
00552   //Define Goal:
00553   move_base_msgs::MoveBaseGoal goal;
00554   
00555   //Publicar dados para "results"
00556   results_pub = nh.advertise<geometry_msgs::PointStamped>("results", 1); //only concerned about the most recent
00557   results_sub = nh.subscribe("results", 10, resultsCB); //Subscrever "results" vindo dos robots
00558   
00559   initialize_node(); //dizer q está vivo
00560   ros::Rate loop_rate(1); //1 segundo
00561   
00562   /* Wait until all nodes are ready.. */
00563   while(initialize){
00564         ros::spinOnce();
00565         loop_rate.sleep();
00566   }
00567   
00568   /* Run Algorithm */
00569    
00570   double instantaneous_idleness [dimension];
00571   double last_visit [dimension];
00572   for(i=0;i<dimension;i++){ 
00573     instantaneous_idleness[i]= 0.0; 
00574     last_visit[i]= 0.0; 
00575     
00576     if(i==current_vertex){
00577       last_visit[i]= 0.1; //Avoids getting back at the initial vertex
00578     }
00579   }
00580   
00581   interference = false;
00582   ResendGoal = false;
00583   goal_complete = true;
00584   
00585   double now;
00586   
00587   
00588   while(1){
00589           
00590     if(goal_complete){
00591             
00592             if(next_vertex>-1){
00593                 //Update Idleness Table:
00594                 now = ros::Time::now().toSec();
00595                         
00596                 for(i=0; i<dimension; i++){
00597                         if (i == next_vertex){
00598                                 last_visit[i] = now;    
00599                         }       
00600                         instantaneous_idleness[i]= now - last_visit[i];           
00601                 } 
00602                 
00603                 current_vertex = next_vertex;           
00604                 
00605                         
00606                 //Show Idleness Table:
00607         /*      for (i=0; i<dimension; i++){
00608                         printf("idleness[%u] = %f\n",i,instantaneous_idleness[i]);      
00609                 } */
00610             }
00611     
00612         //devolver proximo vertex tendo em conta apenas as idlenesses;
00613         next_vertex = (int) state_exchange_bayesian_strategy(current_vertex, vertex_web, instantaneous_idleness, tab_intention, NUMBER_OF_ROBOTS, G1, G2, edge_min);
00614         //printf("Move Robot to Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00615         
00617         send_intention(next_vertex);
00618         
00619         //Send the goal to the robot (Global Map)
00620         geometry_msgs::Quaternion angle_quat = tf::createQuaternionMsgFromYaw(0.0);
00621         goal.target_pose.header.frame_id = "map"; 
00622         goal.target_pose.header.stamp = ros::Time::now();    
00623         goal.target_pose.pose.position.x = vertex_web[next_vertex].x;
00624         goal.target_pose.pose.position.y = vertex_web[next_vertex].y;  
00625         goal.target_pose.pose.orientation = angle_quat;
00626         ROS_INFO("Sending goal - Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00627         ac.sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00628         //ac.waitForResult();   
00629         
00630         goal_complete = false;
00631     
00632     }else{
00633         if (interference){
00634                                                 
00635                 // Stop the robot..                     
00636                 ROS_INFO("Interference detected!\n");   
00637                 send_interference();
00638 
00639                 //get own "odom" positions...
00640                 ros::spinOnce();                
00641                                         
00642                 //Waiting until conflict is solved...
00643                 while(interference){
00644                         interference = check_interference();
00645                         if (goal_complete || ResendGoal){
00646                                 interference = false;
00647                         }
00648                 }
00649                         // se saiu é pq interference = false                   
00650         }           
00651             
00652         if(ResendGoal){
00653                 //Send the goal to the robot (Global Map)
00654                 geometry_msgs::Quaternion angle_quat = tf::createQuaternionMsgFromYaw(0.0);         
00655                 goal.target_pose.header.frame_id = "map"; 
00656                 goal.target_pose.header.stamp = ros::Time::now();    
00657                 goal.target_pose.pose.position.x = vertex_web[next_vertex].x;
00658                 goal.target_pose.pose.position.y = vertex_web[next_vertex].y;  
00659                 goal.target_pose.pose.orientation = angle_quat; //alpha -> orientação  (queria optimizar este parametro -> através da direcção do vizinho!)
00660                 ROS_INFO("Sending goal - Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00661 //              printf("ID_ROBOT = %d\n", ID_ROBOT);
00662                 ac.sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00663                 ResendGoal = false; //para nao voltar a entrar (envia goal so uma vez)
00664         }
00665         
00666         if (arrived && NUMBER_OF_ROBOTS>1){     //a different robot arrived at a vertex: update idleness table and keep track of last vertices positions of other robots.
00667 
00668           //printf("Robot %d reached Goal %d.\n", robot_arrived, vertex_arrived);    
00669 
00670           //Update Idleness Table:
00671           now = ros::Time::now().toSec();
00672                           
00673           for(i=0; i<dimension; i++){
00674                   if (i == vertex_arrived){
00675                             //actualizar last_visit[dimension]
00676                           last_visit[vertex_arrived] = now;     
00677                   }                     
00678                   //actualizar instantaneous_idleness[dimension]
00679                   instantaneous_idleness[i]= now - last_visit[i];           
00680           }       
00681                           
00682           //Show Idleness Table:                
00683 //         for (i=0; i<dimension; i++){
00684 //                printf("idleness[%u] = %f\n",i,instantaneous_idleness[i]);      
00685 //        } 
00686           
00687           arrived = false;
00688         }
00689         
00690         if (intention && NUMBER_OF_ROBOTS>1){     
00691           tab_intention[robot_intention] = vertex_intention;
00692           //printf("tab_intention[ID=%d]=%d\n",robot_intention,tab_intention[robot_intention]);
00693           intention = false;      
00694         }
00695         
00696         if(end_simulation){
00697               return 0;
00698         }       
00699         
00700     }
00701   }
00702   
00703   return 0; 
00704 }


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