PatrolAgent.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2014, 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-2014), and Luca Iocchi (2014-2016)
00036 *********************************************************************/
00037 
00038 #include <sstream>
00039 #include <string>
00040 #include <ros/ros.h>
00041 #include <ros/package.h> //to get pkg path
00042 #include <move_base_msgs/MoveBaseAction.h>
00043 #include <actionlib/client/simple_action_client.h>
00044 #include <tf/transform_broadcaster.h>
00045 #include <tf/transform_listener.h>
00046 #include <nav_msgs/Odometry.h>
00047 #include <std_srvs/Empty.h>
00048 
00049 
00050 #include "PatrolAgent.h"
00051 
00052 using namespace std;
00053 
00054 #define DELTA_TIME_SEQUENTIAL_START 15
00055 
00056 const std::string PS_path = ros::package::getPath("patrolling_sim");    //D.Portugal => get pkg path
00057 
00058 
00059 void PatrolAgent::init(int argc, char** argv) {
00060         /*
00061             argv[0]=/.../patrolling_sim/bin/GBS
00062             argv[1]=__name:=XXXXXX
00063             argv[2]=grid
00064             argv[3]=ID_ROBOT
00065         */
00066     
00067     srand ( time(NULL) );
00068     
00069     //More than One robot (ID between 0 and 99)
00070     if ( atoi(argv[3])>NUM_MAX_ROBOTS || atoi(argv[3])<-1 ){
00071         ROS_INFO("The Robot's ID must be an integer number between 0 an 99"); //max 100 robots 
00072         return;
00073     }else{
00074         ID_ROBOT = atoi(argv[3]); 
00075         //printf("ID_ROBOT = %d\n",ID_ROBOT); //-1 for 1 robot without prefix (robot_0)
00076     }
00077     
00079     chdir(PS_path.c_str());
00080                 
00081     mapname = string(argv[2]);
00082     graph_file = "maps/"+mapname+"/"+mapname+".graph";
00083     
00084     //Check Graph Dimension:
00085     dimension = GetGraphDimension(graph_file.c_str());
00086     
00087     //Create Structure to save the Graph Info;
00088     vertex_web = new vertex[dimension];
00089     
00090     //Get the Graph info from the Graph File
00091     GetGraphInfo(vertex_web, dimension, graph_file.c_str());
00092     
00093     
00094     uint nedges = GetNumberEdges(vertex_web,dimension);
00095     
00096     printf("Loaded graph %s with %d nodes and %d edges\n",mapname.c_str(),dimension,nedges);
00097 
00098 #if 0
00099     /* Output Graph Data */   
00100     for (i=0;i<dimension;i++){
00101         printf ("ID= %u\n", vertex_web[i].id);
00102         printf ("X= %f, Y= %f\n", vertex_web[i].x, vertex_web[i].y);
00103         printf ("#Neigh= %u\n", vertex_web[i].num_neigh);
00104         
00105         for (j=0;j<vertex_web[i].num_neigh; j++){
00106         printf("\tID = %u, DIR = %s, COST = %u\n", vertex_web[i].id_neigh[j], vertex_web[i].dir[j], vertex_web[i].cost[j]);
00107         }
00108         
00109         printf("\n");   
00110     }
00111 #endif
00112       
00113     interference = false;
00114     ResendGoal = false;
00115     goal_complete = true;
00116     last_interference = 0;
00117     goal_canceled_by_user = false;
00118     aborted_count = 0;
00119     resend_goal_count = 0;
00120     communication_delay = 0.0;
00121     lost_message_rate = 0.0;
00122     goal_reached_wait = 0.0;
00123     /* Define Starting Vertex/Position (Launch File Parameters) */
00124 
00125     ros::init(argc, argv, "patrol_agent");  // will be replaced by __name:=XXXXXX
00126     ros::NodeHandle nh;
00127     
00128     // wait a random time (avoid conflicts with other robots starting at the same time...)
00129     double r = 3.0 * ((rand() % 1000)/1000.0);
00130     ros::Duration wait(r); // seconds
00131     wait.sleep();
00132     
00133     double initial_x, initial_y;
00134     std::vector<double> list;
00135     nh.getParam("initial_pos", list);
00136     
00137     if (list.empty()){
00138      ROS_ERROR("No initial positions given: check \"initial_pos\" parameter.");
00139      ros::shutdown();
00140      exit(-1);
00141     }
00142        
00143     int value = ID_ROBOT;
00144     if (value == -1){value = 0;}
00145     
00146     initial_x = list[2*value];
00147     initial_y = list[2*value+1];
00148     
00149     //   printf("initial position: x = %f, y = %f\n", initial_x, initial_y);
00150     current_vertex = IdentifyVertex(vertex_web, dimension, initial_x, initial_y);
00151     //   printf("initial vertex = %d\n\n",current_vertex);  
00152     
00153     
00154     //instantaneous idleness and last visit initialized with zeros:
00155     instantaneous_idleness = new double[dimension];
00156     last_visit = new double[dimension];
00157     for(size_t i=0; i<dimension; i++){ 
00158         instantaneous_idleness[i]= 0.0; 
00159         last_visit[i]= 0.0; 
00160         
00161         if (i==current_vertex){
00162             last_visit[i]= 0.1; //Avoids getting back at the initial vertex
00163         }
00164         //ROS_INFO("last_visit[%d]=%f", i, last_visit[i]);
00165     }
00166         
00167     //Publicar dados de "odom" para nó de posições
00168     positions_pub = nh.advertise<nav_msgs::Odometry>("positions", 1); //only concerned about the most recent
00169         
00170     //Subscrever posições de outros robots
00171     positions_sub = nh.subscribe<nav_msgs::Odometry>("positions", 10, boost::bind(&PatrolAgent::positionsCB, this, _1));  
00172     
00173     char string1[40];
00174     char string2[40];
00175     
00176     if(ID_ROBOT==-1){ 
00177         strcpy (string1,"odom"); //string = "odom"
00178         strcpy (string2,"cmd_vel"); //string = "cmd_vel"
00179         TEAMSIZE = 1;
00180     }else{ 
00181         sprintf(string1,"robot_%d/odom",ID_ROBOT);
00182         sprintf(string2,"robot_%d/cmd_vel",ID_ROBOT);
00183         TEAMSIZE = ID_ROBOT + 1;
00184     }   
00185 
00186     /* Set up listener for global coordinates of robots */
00187     listener = new tf::TransformListener();
00188 
00189     //Cmd_vel to backup:
00190     cmd_vel_pub  = nh.advertise<geometry_msgs::Twist>(string2, 1);
00191     
00192     //Subscrever para obter dados de "odom" do robot corrente
00193     odom_sub = nh.subscribe<nav_msgs::Odometry>(string1, 1, boost::bind(&PatrolAgent::odomCB, this, _1)); //size of the buffer = 1 (?)
00194     
00195     ros::spinOnce(); 
00196     
00197     //Publicar dados para "results"
00198     results_pub = nh.advertise<std_msgs::Int16MultiArray>("results", 100);
00199     // results_sub = nh.subscribe("results", 10, resultsCB); //Subscrever "results" vindo dos robots
00200     results_sub = nh.subscribe<std_msgs::Int16MultiArray>("results", 100, boost::bind(&PatrolAgent::resultsCB, this, _1) ); //Subscrever "results" vindo dos robots
00201 
00202     // last time comm delay has been applied
00203     last_communication_delay_time = ros::Time::now().toSec();   
00204 
00205     readParams();
00206 }
00207     
00208 void PatrolAgent::ready() {
00209     
00210     char move_string[40];
00211     
00212     /* Define Goal */
00213     if(ID_ROBOT==-1){ 
00214         strcpy (move_string,"move_base"); //string = "move_base
00215     }else{
00216         sprintf(move_string,"robot_%d/move_base",ID_ROBOT);
00217     }
00218     
00219     ac = new MoveBaseClient(move_string, true); 
00220     
00221     //wait for the action server to come up
00222     while(!ac->waitForServer(ros::Duration(5.0))){
00223         ROS_INFO("Waiting for the move_base action server to come up");
00224     } 
00225     ROS_INFO("Connected with move_base action server");    
00226     
00227     initialize_node(); //announce that agent is alive
00228     
00229     ros::Rate loop_rate(1); //1 sec
00230     
00231     /* Wait until all nodes are ready.. */
00232     while(initialize){
00233         ros::spinOnce();
00234         loop_rate.sleep();
00235     }    
00236 
00237 }
00238 
00239 
00240 void PatrolAgent::readParams() {
00241 
00242     if (! ros::param::get("/goal_reached_wait", goal_reached_wait)) {
00243       //goal_reached_wait = 0.0;
00244       ROS_WARN("Cannot read parameter /goal_reached_wait. Using default value!");
00245       //ros::param::set("/goal_reached_wait", goal_reached_wait);
00246     }
00247 
00248     if (! ros::param::get("/communication_delay", communication_delay)) {
00249       //communication_delay = 0.0;
00250       ROS_WARN("Cannot read parameter /communication_delay. Using default value!");
00251       //ros::param::set("/communication_delay", communication_delay);
00252     } 
00253 
00254     if (! ros::param::get("/lost_message_rate", lost_message_rate)) {
00255       //lost_message_rate = 0.0;
00256       ROS_WARN("Cannot read parameter /lost_message_rate. Using default value!");
00257       //ros::param::set("/lost_message_rate", lost_message_rate);
00258     }
00259 
00260     if (! ros::param::get("/initial_positions", initial_positions)) {
00261       //initial_positions = "default";
00262       ROS_WARN("Cannot read parameter /initial_positions. Using default value '%s'!", initial_positions.c_str());
00263       //ros::param::set("/initial_pos", initial_positions);
00264     }
00265 
00266 }
00267 
00268 void PatrolAgent::run() {
00269     
00270     // get ready
00271     ready();
00272     
00273     //initially clear the costmap (to make sure the robot is not trapped):
00274     std_srvs::Empty srv;
00275     std::string mb_string;
00276      
00277      if (ID_ROBOT>-1){
00278              std::ostringstream id_string;
00279              id_string << ID_ROBOT;
00280              mb_string = "robot_" + id_string.str() + "/";
00281     }
00282     mb_string += "move_base/clear_costmaps";
00283     
00284     ROS_ERROR("%s",mb_string.c_str());
00285     
00286     if (ros::service::call(mb_string.c_str(), srv)){
00287     //if (ros::service::call("move_base/clear_costmaps", srv)){
00288         ROS_INFO("Costmap correctly cleared before patrolling task.");
00289     }else{
00290         ROS_WARN("Was not able to clear costmap before patrolling...");
00291     }
00292     
00293     // Asynch spinner (non-blocking)
00294     ros::AsyncSpinner spinner(2); // Use n threads
00295     spinner.start();
00296 //     ros::waitForShutdown();
00297 
00298     /* Run Algorithm */ 
00299     
00300     ros::Rate loop_rate(30); //0.033 seconds or 30Hz
00301     
00302     while(ros::ok()){
00303         
00304         if (goal_complete) {
00305             onGoalComplete();  // can be redefined
00306             resend_goal_count=0;
00307         }
00308         else { // goal not complete (active)
00309             if (interference) {
00310                 do_interference_behavior();
00311             }       
00312             
00313             if (ResendGoal) {
00314                 //Send the goal to the robot (Global Map)
00315                 if (resend_goal_count<3) {
00316                     resend_goal_count++;
00317                     ROS_INFO("Re-Sending goal (%d) - Vertex %d (%f,%f)", resend_goal_count, next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00318                     sendGoal(next_vertex);
00319                 }
00320                 else {
00321                     resend_goal_count=0;
00322                     onGoalNotComplete();
00323                 }
00324                 ResendGoal = false; //para nao voltar a entrar (envia goal so uma vez)
00325             }
00326             
00327             processEvents();
00328             
00329             if (end_simulation) {
00330                 return;
00331             }   
00332         
00333         } // if (goal_complete)
00334         
00335                 loop_rate.sleep(); 
00336 
00337     } // while ros.ok    
00338 }
00339 
00340 
00341 void PatrolAgent::onGoalComplete()
00342 {
00343     if(next_vertex>-1) {
00344         //Update Idleness Table:
00345         update_idleness();
00346         current_vertex = next_vertex;       
00347     }
00348     
00349     //devolver proximo vertex tendo em conta apenas as idlenesses;
00350     next_vertex = compute_next_vertex();
00351     //printf("Move Robot to Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00352 
00354     send_goal_reached(); // Send TARGET to monitor
00355     send_results();  // Algorithm specific function
00356 
00357     //Send the goal to the robot (Global Map)
00358     ROS_INFO("Sending goal - Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00359     //sendGoal(vertex_web[next_vertex].x, vertex_web[next_vertex].y);  
00360     sendGoal(next_vertex);  // send to move_base
00361     
00362     goal_complete = false;    
00363 }
00364 
00365 void PatrolAgent::onGoalNotComplete()
00366 {   
00367     int prev_vertex = next_vertex;
00368     
00369     ROS_INFO("Goal not complete - From vertex %d to vertex %d\n", current_vertex, next_vertex);   
00370     
00371     //devolver proximo vertex tendo em conta apenas as idlenesses;
00372     next_vertex = compute_next_vertex();
00373     //printf("Move Robot to Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00374 
00375     // Look for a random adjacent vertex different from the previous one
00376     int random_cnt=0;
00377     while (next_vertex == prev_vertex && random_cnt++<10) {
00378         int num_neighs = vertex_web[current_vertex].num_neigh;
00379         int i = rand() % num_neighs;
00380         next_vertex = vertex_web[current_vertex].id_neigh[i];
00381         ROS_INFO("Choosing another random vertex %d\n", next_vertex);
00382     }
00383     
00384     // Look for any random vertex different from the previous one
00385     while (next_vertex == prev_vertex && next_vertex == current_vertex) {
00386         int i = rand() % dimension;
00387         next_vertex = i;
00388         ROS_INFO("Choosing another random vertex %d\n", next_vertex);
00389     }
00390 
00391     //Send the goal to the robot (Global Map)
00392     ROS_INFO("Re-Sending NEW goal - Vertex %d (%f,%f)\n", next_vertex, vertex_web[next_vertex].x, vertex_web[next_vertex].y);
00393     //sendGoal(vertex_web[next_vertex].x, vertex_web[next_vertex].y);  
00394     sendGoal(next_vertex);  // send to move_base
00395     
00396     goal_complete = false;    
00397 }
00398 
00399 
00400 void PatrolAgent::processEvents() {
00401     
00402 }
00403 
00404 void PatrolAgent::update_idleness() {
00405     double now = ros::Time::now().toSec();
00406         
00407     for(size_t i=0; i<dimension; i++){
00408         if ((int)i == next_vertex){
00409             last_visit[i] = now;    
00410         }
00411         instantaneous_idleness[i] = now - last_visit[i];           
00412         
00413         //Show Idleness Table:
00414         //ROS_INFO("idleness[%u] = %f",i,instantaneous_idleness[i]);
00415     }
00416 }
00417 
00418 void PatrolAgent::initialize_node (){ //ID,msg_type,1
00419     
00420     int value = ID_ROBOT;
00421     if (value==-1){value=0;}
00422     ROS_INFO("Initialize Node: Robot %d",value); 
00423     
00424     std_msgs::Int16MultiArray msg;   
00425     msg.data.clear();
00426     msg.data.push_back(value);
00427     msg.data.push_back(INITIALIZE_MSG_TYPE);
00428     msg.data.push_back(1);  // Robot initialized
00429     
00430     int count = 0;
00431     
00432     //ATENÇÃO ao PUBLICADOR!
00433     ros::Rate loop_rate(0.5); //meio segundo
00434     
00435     while (count<3){ //send activation msg 3times
00436         results_pub.publish(msg);
00437         //ROS_INFO("publiquei msg: %s\n", msg.data.c_str());
00438         ros::spinOnce();
00439         loop_rate.sleep();
00440         count++;
00441     }
00442 }
00443 
00444 void PatrolAgent::getRobotPose(int robotid, float &x, float &y, float &theta) {
00445     
00446     if (listener==NULL) {
00447         ROS_ERROR("TF listener null");
00448         return;
00449     }
00450     
00451     std::stringstream ss; ss << "robot_" << robotid;
00452     std::string robotname = ss.str();
00453     std::string sframe = "/map";                //Patch David Portugal: Remember that the global map frame is "/map"
00454     std::string dframe;
00455     if(ID_ROBOT>-1){
00456         dframe = "/" + robotname + "/base_link";
00457     }else{
00458         dframe = "/base_link";
00459     }
00460     
00461     tf::StampedTransform transform;
00462 
00463     try {
00464         listener->waitForTransform(sframe, dframe, ros::Time(0), ros::Duration(3));
00465         listener->lookupTransform(sframe, dframe, ros::Time(0), transform);
00466     }
00467     catch(tf::TransformException ex) {
00468         ROS_ERROR("Cannot transform from %s to %s\n",sframe.c_str(),dframe.c_str());
00469         ROS_ERROR("%s", ex.what());
00470     }
00471 
00472     x = transform.getOrigin().x();
00473     y = transform.getOrigin().y();
00474     theta = tf::getYaw(transform.getRotation());
00475     // printf("Robot %d pose : %.1f %.1f \n",robotid,x,y);
00476 }
00477 
00478 void PatrolAgent::odomCB(const nav_msgs::Odometry::ConstPtr& msg) { //colocar propria posicao na tabela
00479     
00480 //  printf("Colocar Propria posição na tabela, ID_ROBOT = %d\n",ID_ROBOT);
00481     int idx = ID_ROBOT;
00482     
00483     if (ID_ROBOT<=-1){
00484         idx = 0;
00485     }
00486     
00487     float x,y,th;
00488     getRobotPose(idx,x,y,th);
00489     
00490     xPos[idx]=x; // msg->pose.pose.position.x;
00491     yPos[idx]=y; // msg->pose.pose.position.y;
00492     
00493 //  printf("Posicao colocada em Pos[%d]\n",idx);
00494 }
00495 
00496 
00497 
00498 void PatrolAgent::sendGoal(int next_vertex) 
00499 {
00500     goal_canceled_by_user = false;
00501     
00502     double target_x = vertex_web[next_vertex].x, 
00503            target_y = vertex_web[next_vertex].y;
00504     
00505     //Define Goal:
00506     move_base_msgs::MoveBaseGoal goal;
00507     //Send the goal to the robot (Global Map)
00508     geometry_msgs::Quaternion angle_quat = tf::createQuaternionMsgFromYaw(0.0);     
00509     goal.target_pose.header.frame_id = "map"; 
00510     goal.target_pose.header.stamp = ros::Time::now();    
00511     goal.target_pose.pose.position.x = target_x; // vertex_web[current_vertex].x;
00512     goal.target_pose.pose.position.y = target_y; // vertex_web[current_vertex].y;  
00513     goal.target_pose.pose.orientation = angle_quat; //doesn't matter really.
00514     ac->sendGoal(goal, boost::bind(&PatrolAgent::goalDoneCallback, this, _1, _2), boost::bind(&PatrolAgent::goalActiveCallback,this), boost::bind(&PatrolAgent::goalFeedbackCallback, this,_1));  
00515 }
00516 
00517 void PatrolAgent::cancelGoal() 
00518 {
00519     goal_canceled_by_user = true;
00520     ac->cancelAllGoals();
00521 }
00522 
00523 
00524 void PatrolAgent::goalDoneCallback(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result){ //goal terminado (completo ou cancelado)
00525 //  ROS_INFO("Goal is complete (suceeded, aborted or cancelled).");
00526     // If the goal succeeded send a new one!
00527     //if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED) sendNewGoal = true;
00528     // If it was aborted time to back up!
00529     //if(state.state_ == actionlib::SimpleClientGoalState::ABORTED) needToBackUp = true;    
00530     
00531     if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED){
00532         ROS_INFO("Goal reached ... WAITING %.2f sec",goal_reached_wait);
00533         ros::Duration delay(goal_reached_wait); // wait after goal is reached
00534         delay.sleep();
00535         ROS_INFO("Goal reached ... DONE");
00536         goal_complete = true;
00537     }else{
00538         aborted_count++;
00539         ROS_INFO("CANCELLED or ABORTED... %d",aborted_count);   //tentar voltar a enviar goal..
00540         if (!goal_canceled_by_user) {
00541             ROS_INFO("Goal not cancelled by the interference...");
00542 
00543             //ROS_INFO("Backup");
00544             backup();
00545 
00546             ROS_INFO("Clear costmap!");
00547 
00548             char srvname[80];
00549             
00550             if(ID_ROBOT<=-1){
00551                 sprintf(srvname,"/move_base/clear_costmaps");
00552             }else{
00553                 sprintf(srvname,"/robot_%d/move_base/clear_costmaps",ID_ROBOT);
00554             }
00555             
00556             ros::NodeHandle n;
00557             ros::ServiceClient client = n.serviceClient<std_srvs::Empty>(srvname);
00558             std_srvs::Empty srv;
00559             if (client.call(srv)) {
00560                 ROS_INFO("Costmaps cleared.\n");
00561             }
00562             else {
00563                 ROS_ERROR("Failed to call service move_base/clear_costmaps");
00564             }
00565 
00566             ROS_INFO("Resend Goal!");
00567             ResendGoal = true;
00568         }
00569     }
00570 }
00571 
00572 void PatrolAgent::goalActiveCallback(){  //enquanto o robot esta a andar para o goal...
00573     goal_complete = false;
00574 //      ROS_INFO("Goal is active.");
00575 }
00576 
00577 void PatrolAgent::goalFeedbackCallback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback){    //publicar posições
00578 
00579     send_positions();
00580     
00581     int value = ID_ROBOT;
00582     if (value==-1){ value = 0;}
00583     interference = check_interference(value);    
00584 }
00585 
00586 void PatrolAgent::send_goal_reached() {
00587     
00588     int value = ID_ROBOT;
00589     if (value==-1){ value = 0;}
00590     
00591     // [ID,msg_type,vertex,intention,0]
00592     std_msgs::Int16MultiArray msg;   
00593     msg.data.clear();
00594     msg.data.push_back(value);
00595     msg.data.push_back(TARGET_REACHED_MSG_TYPE);
00596     msg.data.push_back(current_vertex);
00597     //msg.data.push_back(next_vertex);
00598     //msg.data.push_back(0); //David Portugal: is this necessary?
00599     
00600     results_pub.publish(msg);   
00601     ros::spinOnce();  
00602 }
00603 
00604 bool PatrolAgent::check_interference (int robot_id){ //verificar se os robots estao proximos
00605     
00606     int i;
00607     double dist_quad;
00608     
00609     if (ros::Time::now().toSec()-last_interference<10)  // seconds
00610         return false; // false if within 10 seconds from the last one
00611     
00612     /* Poderei usar TEAMSIZE para afinar */
00613     for (i=0; i<robot_id; i++){ //percorrer vizinhos (assim asseguro q cada interferencia é so encontrada 1 vez)
00614         
00615         dist_quad = (xPos[i] - xPos[robot_id])*(xPos[i] - xPos[robot_id]) + (yPos[i] - yPos[robot_id])*(yPos[i] - yPos[robot_id]);
00616         
00617         if (dist_quad <= INTERFERENCE_DISTANCE*INTERFERENCE_DISTANCE){    //robots are ... meter or less apart
00618 //          ROS_INFO("Feedback: Robots are close. INTERFERENCE! Dist_Quad = %f", dist_quad);
00619             last_interference = ros::Time::now().toSec();
00620             return true;
00621         }       
00622     }
00623     return false;
00624     
00625 }
00626 
00627 void PatrolAgent::backup(){
00628     
00629     ros::Rate loop_rate(100); // 100Hz
00630     
00631     int backUpCounter = 0;
00632     while (backUpCounter<=100){
00633     
00634       if(backUpCounter==0){
00635           ROS_INFO("The wall is too close! I need to do some backing up...");
00636           // Move the robot back...
00637           geometry_msgs::Twist cmd_vel;
00638           cmd_vel.linear.x = -0.1;
00639           cmd_vel.angular.z = 0.0;
00640           cmd_vel_pub.publish(cmd_vel);
00641       }
00642               
00643       if(backUpCounter==20){
00644           // Turn the robot around...
00645           geometry_msgs::Twist cmd_vel;
00646           cmd_vel.linear.x = 0.0;
00647           cmd_vel.angular.z = 0.5;
00648           cmd_vel_pub.publish(cmd_vel);
00649       }
00650               
00651       if(backUpCounter==100){
00652           // Stop the robot...
00653           geometry_msgs::Twist cmd_vel;
00654           cmd_vel.linear.x = 0.0;
00655           cmd_vel.angular.z = 0.0;
00656           cmd_vel_pub.publish(cmd_vel);
00657               
00658           // ROS_INFO("Done backing up, now on with my life!");      
00659       }
00660 
00661       ros::spinOnce();
00662       loop_rate.sleep();
00663       backUpCounter++;
00664     
00665     }
00666     
00667 }
00668 
00669 void PatrolAgent::do_interference_behavior()
00670 {
00671     ROS_INFO("Interference detected! Executing interference behavior...\n");   
00672     send_interference();  // send interference to monitor for counting
00673     
00674 #if 1
00675     // Stop the robot..         
00676     cancelGoal();
00677     ROS_INFO("Robot stopped");
00678     ros::Duration delay(3); // seconds
00679     delay.sleep();
00680     ResendGoal = true;
00681 #else    
00682     //get own "odom" positions...
00683     ros::spinOnce();        
00684                 
00685     //Waiting until conflict is solved...
00686     int value = ID_ROBOT;
00687     if (value == -1){ value = 0;}
00688     while(interference){
00689         interference = check_interference(value);
00690         if (goal_complete || ResendGoal){
00691             interference = false;
00692         }
00693     }
00694 #endif
00695 }
00696 
00697 
00698 
00699 
00700 // ROBOT-ROBOT COMMUNICATION
00701 
00702 
00703 
00704 void PatrolAgent::send_positions()
00705 {
00706     //Publish Position to common node:
00707     nav_msgs::Odometry msg; 
00708     
00709     int idx = ID_ROBOT;
00710 
00711     if (ID_ROBOT <= -1){
00712         msg.header.frame_id = "map";    //identificador do robot q publicou
00713         idx = 0;
00714     }else{
00715         char string[20];
00716         sprintf(string,"robot_%d/map",ID_ROBOT);
00717         msg.header.frame_id = string;
00718     }
00719 
00720     msg.pose.pose.position.x = xPos[idx]; //send odometry.x
00721     msg.pose.pose.position.y = yPos[idx]; //send odometry.y
00722   
00723     positions_pub.publish(msg);
00724     ros::spinOnce();
00725 }
00726 
00727 
00728 void PatrolAgent::receive_positions()
00729 {
00730     
00731 }
00732 
00733 void PatrolAgent::positionsCB(const nav_msgs::Odometry::ConstPtr& msg) { //construir tabelas de posições
00734         
00735 //     printf("Construir tabela de posicoes (receber posicoes), ID_ROBOT = %d\n",ID_ROBOT);    
00736         
00737     char id[20]; //identificador do robot q enviou a msg d posição...
00738     strcpy( id, msg->header.frame_id.c_str() );
00739     //int stamp = msg->header.seq;
00740 //     printf("robot q mandou msg = %s\n", id);
00741     
00742     // Build Positions Table
00743     
00744     if (ID_ROBOT>-1){
00745     //verify id "XX" of robot: (string: "robot_XX/map")
00746     
00747         char str_idx[4];
00748         uint i;
00749         
00750         for (i=6; i<10; i++){
00751             if (id[i]=='/'){
00752                 str_idx[i-6] = '\0';
00753                 break;
00754             }else{
00755                 str_idx[i-6] = id[i];
00756             }
00757         }
00758         
00759         int idx = atoi (str_idx);
00760     //  printf("id robot q mandou msg = %d\n",idx);
00761         
00762         if (idx >= TEAMSIZE && TEAMSIZE <= NUM_MAX_ROBOTS){
00763             //update teamsize:
00764             TEAMSIZE = idx+1;
00765         }
00766         
00767         if (ID_ROBOT != idx){  //Ignore own positions   
00768             xPos[idx]=msg->pose.pose.position.x;
00769             yPos[idx]=msg->pose.pose.position.y;        
00770         }   
00771 //      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] );       
00772     }
00773     
00774     receive_positions();
00775 }
00776 
00777 
00778 void PatrolAgent::send_results() { 
00779 
00780 }
00781 
00782 // simulates blocking send operation with delay in communication
00783 void PatrolAgent::do_send_message(std_msgs::Int16MultiArray &msg) {
00784         if (communication_delay>0.001) {
00785         //double current_time = ros::Time::now().toSec();
00786         //if (current_time-last_communication_delay_time>1.0) { 
00787                 //ROS_INFO("Communication delay %.1f",communication_delay);
00788                 ros::Duration delay(communication_delay); // seconds
00789                 delay.sleep();
00790                 //last_communication_delay_time = current_time;
00791         //}
00792     }    
00793     results_pub.publish(msg);
00794     ros::spinOnce();
00795 }
00796 
00797 
00798 void PatrolAgent::receive_results() {
00799 
00800 }
00801 
00802 void PatrolAgent::send_interference(){
00803     //interference: [ID,msg_type]
00804     
00805     int value = ID_ROBOT;
00806     if (value==-1){value=0;}
00807     printf("Send Interference: Robot %d\n",value);   
00808     
00809     std_msgs::Int16MultiArray msg;   
00810     msg.data.clear();
00811     msg.data.push_back(value);
00812     msg.data.push_back(INTERFERENCE_MSG_TYPE);
00813     
00814     results_pub.publish(msg);   
00815     ros::spinOnce();
00816 }
00817 
00818 
00819 
00820 
00821 void PatrolAgent::resultsCB(const std_msgs::Int16MultiArray::ConstPtr& msg) { 
00822     
00823     std::vector<signed short>::const_iterator it = msg->data.begin();    
00824     
00825     vresults.clear();
00826     
00827     for (size_t k=0; k<msg->data.size(); k++) {
00828         vresults.push_back(*it); it++;
00829     } 
00830 
00831     int id_sender = vresults[0];
00832     int msg_type = vresults[1];
00833     
00834     //printf(" MESSAGE FROM %d TYPE %d ...\n",id_sender, msg_type);
00835     
00836     // messages coming from the monitor
00837     if (id_sender==-1 && msg_type==INITIALIZE_MSG_TYPE) {
00838         if (initialize==true && vresults[2]==100) {   //"-1,msg_type,100,seq_flag" (BEGINNING)
00839             ROS_INFO("Let's Patrol!\n");
00840             double r = 1.0 * ((rand() % 1000)/1000.0);
00841 
00842             //TODO if sequential start
00843             //r = DELTA_TIME_SEQUENTIAL_START * ID_ROBOT;
00844 
00845             ros::Duration wait(r); // seconds
00846 
00847             printf("Wait %.1f seconds (init pos:%s)\n",r,initial_positions.c_str());
00848 
00849             wait.sleep();
00850             initialize = false;
00851         }
00852         
00853         if (initialize==false && vresults[2]==999) {   //"-1,msg_type,999" (END)
00854             ROS_INFO("The simulation is over. Let's leave");
00855             end_simulation = true;     
00856         }
00857     }
00858     
00859     if (!initialize) {
00860 #if 0
00861         // communication delay
00862         if(ID_ROBOT>-1){
00863             if ((communication_delay>0.001) && (id_sender!=ID_ROBOT)) {
00864                     double current_time = ros::Time::now().toSec();
00865                     if (current_time-last_communication_delay_time>1.0) { 
00866                             ROS_INFO("Communication delay %.1f",communication_delay);
00867                             ros::Duration delay(communication_delay); // seconds
00868                             delay.sleep();
00869                             last_communication_delay_time = current_time;
00870                 }
00871             }
00872             bool lost_message = false;
00873             if ((lost_message_rate>0.0001)&& (id_sender!=ID_ROBOT)) {
00874                 double r = (rand() % 1000)/1000.0;
00875                 lost_message = r < lost_message_rate;
00876             }
00877             if (lost_message) {
00878                 ROS_INFO("Lost message");
00879             }
00880         }
00881 #endif
00882             receive_results();
00883     }
00884 
00885     ros::spinOnce();
00886   
00887 }


patrolling_sim
Author(s):
autogenerated on Mon Oct 2 2017 03:13:50