monitor.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 <sys/stat.h>
00039 #include <sys/types.h>
00040 #include <stdlib.h>
00041 #include <unistd.h>
00042 #include <time.h>
00043 #include <float.h>
00044 #include <fstream>
00045 #include <iostream>
00046 #include <string>
00047 
00048 #include <ros/ros.h>
00049 #include <ros/package.h> //to get pkg path
00050 #include <move_base_msgs/MoveBaseAction.h>
00051 #include <actionlib/client/simple_action_client.h>
00052 #include <tf/transform_broadcaster.h>
00053 #include <tf/transform_listener.h>
00054 #include <std_msgs/Int16MultiArray.h>
00055 #include <std_msgs/String.h>
00056 
00057 using namespace std;
00058 
00059 #include "getgraph.h"
00060 #include "message_types.h"
00061 #include "patrolling_sim/GoToStartPosSrv.h"
00062 
00063 #define NUM_MAX_ROBOTS 32
00064 #define MAX_COMPLETE_PATROL 100
00065 #define MAX_EXPERIMENT_TIME 86400  // seconds
00066 #define DEAD_ROBOT_TIME 300.0 // (seconds) time from last goal reached after which a robot is considered dead
00067 #define TIMEOUT_WRITE_RESULTS 180.0 // (seconds) timeout for writing results to file 
00068 #define FOREVER true
00069 // For hystograms
00070 #define RESOLUTION 1.0 // seconds
00071 #define MAXIDLENESS 500.0 // seconds
00072 
00073 #define LOG_MONITOR 0
00074 #define SAVE_HYSTOGRAMS 0
00075 #define EXTENDED_STAGE 0
00076 
00077 using std::string;
00078 using std::cout;
00079 using std::endl;
00080 
00081 typedef unsigned int uint;
00082 
00083 ros::Subscriber results_sub;
00084 ros::Publisher results_pub, screenshot_pub;
00085 ros::ServiceServer GotoStartPosMethod;
00086 
00087 //Initialization:
00088 bool initialize = true; // Initialization flag
00089 bool goto_start_pos = false; //default: robots already start in right position
00090 uint cnt=0;  // Count number of robots connected
00091 uint teamsize;
00092 bool init_robots[NUM_MAX_ROBOTS];
00093 double last_goal_reached[NUM_MAX_ROBOTS];
00094 
00095 // mutex for accessing last_goal_reached vector
00096 pthread_mutex_t lock_last_goal_reached;
00097 
00098 //State Variables:
00099 bool goal_reached = false;
00100 
00101 int goal;
00102 double time_zero, last_report_time;
00103 time_t real_time_zero;
00104 double goal_reached_wait,comm_delay,lost_message_rate;
00105 string algorithm, algparams, nav_mod, initial_positions;
00106 
00107 const std::string PS_path = ros::package::getPath("patrolling_sim");    //D.Portugal => get pkg path
00108 
00109 
00110 #define MAX_DIMENSION 200
00111 
00112 /* ESTRUTURAS DE DADOS A CALCULAR */
00113 double last_visit [MAX_DIMENSION], current_idleness [MAX_DIMENSION], avg_idleness [MAX_DIMENSION], stddev_idleness [MAX_DIMENSION];
00114 double total_0 [MAX_DIMENSION], total_1 [MAX_DIMENSION],  total_2[MAX_DIMENSION];
00115 int number_of_visits [MAX_DIMENSION];
00116 size_t dimension; // graph size
00117 
00118 double worst_avg_idleness, avg_graph_idl, median_graph_idl, stddev_graph_idl, avg_stddev_graph_idl, previous_avg_graph_idl = DBL_MAX;
00119 // global measures
00120 double min_idleness = 0.0, max_idleness = 0.0;
00121 double gavg, gstddev;
00122 double gT0=0.0, gT1=0.0, gT2=0.0;
00123 
00124 uint interference_cnt = 0;
00125 uint complete_patrol = 0;
00126 uint patrol_cnt = 1;
00127 
00128 
00129 
00130 #if SAVE_HYSTOGRAMS
00131 #define hn ((int)(MAXIDLENESS/RESOLUTION)+1)
00132 int hsum;
00133 int hv[hn];
00134 #endif
00135 
00136 // Idleness file
00137 FILE *idlfile;
00138 
00139 // log file
00140 FILE *logfile = NULL;
00141 
00142 void dolog(const char *str) {
00143   if (logfile) {
00144     fprintf(logfile,"%s\n",str);
00145     fflush(logfile);
00146   }
00147 }
00148 
00149 void update_stats(int id_robot, int goal);
00150 
00151 
00152 double get_last_goal_reached(int k)
00153 {
00154   pthread_mutex_lock(&lock_last_goal_reached);
00155   double r = last_goal_reached[k];
00156   pthread_mutex_unlock(&lock_last_goal_reached);
00157   return r;
00158 }
00159 
00160 void set_last_goal_reached(int k, double val)
00161 {
00162   pthread_mutex_lock(&lock_last_goal_reached);
00163   last_goal_reached[k] = val;
00164   pthread_mutex_unlock(&lock_last_goal_reached);
00165 }
00166 
00167 
00168 void resultsCB(const std_msgs::Int16MultiArray::ConstPtr& msg) 
00169 {
00170     dolog("resultsCB - begin");
00171 
00172     std::vector<signed short>::const_iterator it = msg->data.begin();    
00173     
00174     std::vector<int> vresults;
00175     
00176     vresults.clear();
00177     
00178     for (size_t k=0; k<msg->data.size(); k++) {
00179         vresults.push_back(*it); it++;
00180     }
00181 
00182     int id_robot = vresults[0];  // robot sending the message
00183     int msg_type = vresults[1];  // message type
00184 
00185     switch(msg_type) {
00186         case INITIALIZE_MSG_TYPE:
00187         {
00188         if (initialize && vresults[2]==1){ 
00189             if (init_robots[id_robot] == false){   //receive init msg: "ID,msg_type,1"
00190                 printf("Robot [ID = %d] is Active!\n", id_robot);
00191                 init_robots[id_robot] = true;
00192                 
00193                 //Patch D.Portugal (needed to support other simulators besides Stage):
00194                 double current_time = ros::Time::now().toSec();
00195                 //initialize last_goal_reached:
00196                 set_last_goal_reached(id_robot,current_time);
00197                 
00198                 cnt++;
00199             } 
00200             if (cnt==teamsize){
00201                 
00202                 // check if robots need to travel to starting positions
00203                 while(goto_start_pos){ //if or while (?)
00204                     
00205                     patrolling_sim::GoToStartPosSrv::Request Req;
00206                     Req.teamsize.data = teamsize;
00207                     Req.sleep_between_goals.data = 20; //time in secs to wait before sending goals to each different robot
00208                     patrolling_sim::GoToStartPosSrv::Response Rep;      
00209                     
00210                     ROS_INFO("Sending all robots to starting position.");
00211                     
00212                     if (!ros::service::call("/GotoStartPosSrv", Req, Rep)){ //blocking call
00213                         ROS_ERROR("Error invoking /GotoStartPosSrv.");  
00214                         ROS_ERROR("Sending robots to initial position failed.");
00215                         ros::shutdown(); //make sense for while implementation
00216                         return;
00217                         
00218                     }else{
00219                         goto_start_pos = false;
00220                         system("rosnode kill GoToStartPos &");  //we don't need the service anymore.
00221                     }               
00222                     
00223                 }
00224                     
00225                 printf("All Robots GO!\n");
00226                 initialize = false;
00227                     
00228                 //Clock Reset:
00229                 time_zero = ros::Time::now().toSec();
00230                 last_report_time = time_zero; 
00231                                     
00232                 time (&real_time_zero);
00233                 printf("Time zero = %.1f (sim) = %lu (real) \n", time_zero,(long)real_time_zero);
00234 
00235                 std_msgs::Int16MultiArray msg;  // -1,msg_type,100,0,0
00236                 msg.data.clear();
00237                 msg.data.push_back(-1);
00238                 msg.data.push_back(INITIALIZE_MSG_TYPE);
00239                 msg.data.push_back(100);  // Go !!!
00240                 results_pub.publish(msg);
00241                 ros::spinOnce();      
00242                 
00243                 }
00244             }
00245             
00246         //}
00247         break;
00248         }
00249         
00250         case TARGET_REACHED_MSG_TYPE:
00251         {
00252             //goal sent by a robot during the experiment [ID,msg_type,vertex,intention,0]
00253             if (initialize==false){ 
00254                 goal = vresults[2];
00255                 ROS_INFO("Robot %d reached Goal %d.\n", id_robot, goal); 
00256                 fflush(stdout);
00257                 goal_reached = true;
00258                 update_stats(id_robot, goal);
00259                 ros::spinOnce();
00260             }
00261             break;
00262         }
00263          
00264         case INTERFERENCE_MSG_TYPE:
00265         {
00266             //interference: [ID,msg_type]
00267             if (initialize==false){
00268                 ROS_INFO("Robot %d sent interference.\n", id_robot); 
00269                 interference_cnt++;
00270                 ros::spinOnce();
00271             }
00272             break;
00273         }
00274     }
00275 
00276     dolog("resultsCB - end");
00277 
00278 }
00279 
00280 void finish_simulation (){ //-1,msg_type,999,0,0
00281   ROS_INFO("Sending stop signal to patrol agents.");
00282   std_msgs::Int16MultiArray msg;  
00283   msg.data.clear();
00284   msg.data.push_back(-1);
00285   msg.data.push_back(INITIALIZE_MSG_TYPE);
00286   msg.data.push_back(999);  // end of the simulation
00287   results_pub.publish(msg);
00288   ros::spinOnce();  
00289 
00290   ROS_INFO("Taking a screenshot of the simulator...");
00291   std_msgs::String ss;
00292   ss.data = "screenshot";
00293   screenshot_pub.publish(ss);
00294   ros::spinOnce();  
00295 }
00296 
00297 // return the median value in a vector of size "dimension" floats pointed to by a
00298 double Median( double *a, uint dimension )
00299 {
00300    uint table_size = dimension/2;   
00301    if(dimension % 2 != 0){ //odd
00302    table_size++; 
00303    }   
00304    if (table_size==0) {table_size = 1;}
00305    
00306    double left[table_size], right[table_size], median, *p;
00307    unsigned char nLeft, nRight;
00308 
00309    // pick first value as median candidate
00310    p = a;
00311    median = *p++;
00312    nLeft = nRight = 1;
00313 
00314    for(;;)
00315    {
00316        // get next value
00317        double val = *p++;
00318 
00319        // if value is smaller than median, append to left heap
00320        if( val < median )
00321        {
00322            // move biggest value to the heap top
00323            unsigned char child = nLeft++, parent = (child - 1) / 2;
00324            while( parent && val > left[parent] )
00325            {
00326                left[child] = left[parent];
00327                child = parent;
00328                parent = (parent - 1) / 2;
00329            }
00330            left[child] = val;
00331 
00332            // if left heap is full
00333            if( nLeft == table_size )
00334            {
00335                // for each remaining value
00336                for( unsigned char nVal = dimension - (p - a); nVal; --nVal )
00337                {
00338                    // get next value
00339                    val = *p++;
00340 
00341                    // if value is to be inserted in the left heap
00342                    if( val < median )
00343                    {
00344                        child = left[2] > left[1] ? 2 : 1;
00345                        if( val >= left[child] )
00346                            median = val;
00347                        else
00348                        {
00349                            median = left[child];
00350                            parent = child;
00351                            child = parent*2 + 1;
00352                            while( child < table_size )
00353                            {
00354                                if( child < table_size-1 && left[child+1] > left[child] )
00355                                    ++child;
00356                                if( val >= left[child] )
00357                                    break;
00358                                left[parent] = left[child];
00359                                parent = child;
00360                                child = parent*2 + 1;
00361                            }
00362                            left[parent] = val;
00363                        }
00364                    }
00365                }
00366                return median;
00367            }
00368        }
00369 
00370        // else append to right heap
00371        else
00372        {
00373            // move smallest value to the heap top
00374            unsigned char child = nRight++, parent = (child - 1) / 2;
00375            while( parent && val < right[parent] )
00376            {
00377                right[child] = right[parent];
00378                child = parent;
00379                parent = (parent - 1) / 2;
00380            }
00381            right[child] = val;
00382 
00383            // if right heap is full
00384            if( nRight == 14 )
00385            {
00386                // for each remaining value
00387                for( unsigned char nVal = dimension - (p - a); nVal; --nVal )
00388                {
00389                    // get next value
00390                    val = *p++;
00391 
00392                    // if value is to be inserted in the right heap
00393                    if( val > median )
00394                    {
00395                        child = right[2] < right[1] ? 2 : 1;
00396                        if( val <= right[child] )
00397                            median = val;
00398                        else
00399                        {
00400                            median = right[child];
00401                            parent = child;
00402                            child = parent*2 + 1;
00403                            while( child < table_size )
00404                            {
00405                                if( child < 13 && right[child+1] < right[child] )
00406                                    ++child;
00407                                if( val <= right[child] )
00408                                    break;
00409                                right[parent] = right[child];
00410                                parent = child;
00411                                child = parent*2 + 1;
00412                            }
00413                            right[parent] = val;
00414                        }
00415                    }
00416                }
00417                return median;
00418            }
00419        }
00420    }
00421 }
00422 
00423 
00424 uint calculate_patrol_cycle ( int *nr_visits, uint dimension ){
00425   dolog("    calculate_patrol_cycle - begin");
00426   uint result = INT_MAX;
00427   uint imin=0;
00428   for (uint i=0; i<dimension; i++){
00429     if ((uint)nr_visits[i] < result){
00430       result = nr_visits[i]; imin=i;
00431     }
00432   }
00433   //printf("  --- complete patrol: visits of %d : %d\n",imin,result);
00434   dolog("    calculate_patrol_cycle - end");
00435   return result;  
00436 }
00437 
00438 void scenario_name(char* name, const char* graph_file, const char* teamsize_str)
00439 {
00440     uint i, start_char=0, end_char = strlen(graph_file)-1;
00441     
00442     for (i=0; i<strlen(graph_file); i++){
00443         if(graph_file[i]=='/' && i < strlen(graph_file)-1){
00444             start_char = i+1;
00445         }
00446         
00447         if(graph_file[i]=='.' && i>0){
00448             end_char = i-1;
00449             break;
00450         }
00451     }
00452     
00453     for (i=start_char; i<=end_char; i++){
00454         name [i-start_char] = graph_file [i];
00455         if (i==end_char){
00456             name[i-start_char+1] = '\0';
00457         }
00458     }
00459     
00460     strcat(name,"_");
00461     strcat(name,teamsize_str);
00462 }
00463 
00464 //write_results to file
00465 void write_results (double *avg_idleness, double *stddev_idleness, int *number_of_visits, uint complete_patrol, uint dimension, 
00466                     double worst_avg_idleness, double avg_graph_idl, double median_graph_idl, double stddev_graph_idl, 
00467                     double min_idleness, double gavg, double gstddev, double max_idleness,
00468                     uint interference_cnt, uint tot_visits, float avg_visits,
00469                     const char* graph_file, const char* teamsize_str, 
00470                     double duration, double real_duration, double comm_delay,
00471                             string filename) {
00472 
00473     dolog("write_results - begin");
00474 
00475     FILE *file;
00476   
00477     printf("writing to file %s\n",filename.c_str());
00478     // printf("graph file %s\n",graph_file);
00479         
00480     file = fopen (filename.c_str(),"a");
00481     
00482     //fprintf(file,"%i\n%i\n%i\n\n",num_nos,largura(),altura());
00483     fprintf(file, "\nComplete Patrol Cycles:\t%u\n\n", complete_patrol);
00484     fprintf(file, "Vertex\tAvg Idl\tStdDev Idl\t#Visits\n");
00485     for (uint i=0; i<dimension; i++){
00486         fprintf(file, "%u\t%.1f\t%.1f\t%d\n", i, avg_idleness[i], stddev_idleness[i], number_of_visits[i] );
00487     }
00488 
00489         fprintf(file,"\nNode idleness\n");
00490         fprintf(file,"   worst_avg_idleness (graph) = %.1f\n", worst_avg_idleness);
00491         fprintf(file,"   avg_idleness (graph) = %.1f\n", avg_graph_idl);
00492         fprintf(file,"   median_idleness (graph) = %.1f\n", median_graph_idl);
00493         fprintf(file,"   stddev_idleness (graph) = %.1f\n", stddev_graph_idl);
00494 
00495         fprintf(file,"\nGlobal idleness\n");
00496         fprintf(file,"   min = %.1f\n", min_idleness);
00497         fprintf(file,"   avg = %.1f\n", gavg);
00498         fprintf(file,"   stddev = %.1f\n", gstddev);
00499         fprintf(file,"   max = %.1f\n", max_idleness);
00500 
00501         fprintf(file,"\nInterferences\t%u\nInterference rate\t%.2f\nVisits\t%u\nAvg visits per node\t%.1f\nTime Elapsed\t%.1f\nReal Time Elapsed\t%.1f\nComm delay: %.2f\n",
00502                 interference_cnt,(float)interference_cnt/duration*60,tot_visits,avg_visits,duration,real_duration,comm_delay);
00503     
00504     fprintf(file,"----------------------------------------------------------------------------------------------------------------------------------------------------------------\n\n\n");    
00505     
00506     
00507     fclose(file); /*done!*/  
00508 
00509     dolog("write_results - end");
00510 
00511 }
00512 
00513 bool check_dead_robots() {
00514 
00515     dolog("  check_dead_robots - begin");
00516 
00517     double current_time = ros::Time::now().toSec();
00518     bool r=false;
00519     for (size_t i=0; i<teamsize; i++) {
00520       double l = get_last_goal_reached(i);
00521       double delta = current_time - l;
00522       // printf("DEBUG dead robot: %d   %.1f - %.1f = %.1f\n",i,current_time,l,delta);
00523       if (delta>DEAD_ROBOT_TIME*0.75) {
00524         printf("Robot %lu: dead robot - delta = %.1f / %.1f \n",i,delta,DEAD_ROBOT_TIME);
00525         system("play -q beep.wav");
00526       }
00527       if (delta>DEAD_ROBOT_TIME) {
00528           // printf("Dead robot %d. Time from last goal reached = %.1f\n",i,delta);
00529           r=true;
00530           break;
00531       }
00532     }
00533 
00534     dolog("  check_dead_robots - end");
00535 
00536     return r;
00537 }
00538 
00539 
00540 // update stats after robot 'id_robot' visits node 'goal'
00541 void update_stats(int id_robot, int goal) {
00542 
00543     dolog("  update_stats - begin");
00544 
00545     
00546 //   printf("last_visit [%d] = %.1f\n", goal, last_visit [goal]);
00547      double current_time = ros::Time::now().toSec();
00548 
00549     printf("Robot %d reached goal %d (current time: %.2f, alg: %s, nav: %s)\n", id_robot, goal, current_time, algorithm.c_str(), nav_mod.c_str());
00550             
00551     double last_visit_temp = current_time - time_zero; //guarda o valor corrente
00552     number_of_visits [goal] ++;
00553     
00554     set_last_goal_reached(id_robot,current_time);
00555 
00556     printf("   nr_of_visits = %d -", number_of_visits [goal]);
00557 
00558     if (number_of_visits [goal] == 0) {
00559         avg_idleness [goal] = 0.0; stddev_idleness[goal] = 0.0;
00560         total_0 [goal] = 0.0; total_1 [goal] = 0.0;  total_2 [goal] = 0.0;
00561     }
00562     else { // if (number_of_visits [goal] > 0) {
00563 
00564         current_idleness [goal] = last_visit_temp - last_visit [goal];
00565     
00566         if (current_idleness [goal] > max_idleness)
00567             max_idleness=current_idleness [goal];
00568         if (current_idleness [goal] < min_idleness || min_idleness<0.1)
00569             min_idleness=current_idleness [goal];
00570         
00571         // global stats
00572         gT0++; gT1 += current_idleness[goal]; gT2 += current_idleness[goal]*current_idleness[goal];
00573     
00574         // node stats
00575         total_0 [goal] += 1.0; total_1 [goal] += current_idleness [goal];  total_2 [goal] += current_idleness [goal]*current_idleness [goal];
00576         avg_idleness [goal] = total_1[goal]/total_0[goal]; 
00577         stddev_idleness[goal] = 1.0/total_0[goal] * sqrt(total_0[goal]*total_2[goal]-total_1[goal]*total_1[goal]); 
00578         
00579         printf(" idl current = %.2f, ", current_idleness[goal]);
00580         printf(" avg = %.1f, stddev = %.1f,", avg_idleness [goal], stddev_idleness[goal]);
00581         printf(" max = %.1f - interf = %d\n", max_idleness,interference_cnt);
00582 
00583         // save data in idleness file
00584         fprintf(idlfile,"%.1f;%d;%d;%.1f;%d\n",current_time,id_robot,goal,current_idleness[goal],interference_cnt);
00585         fflush(idlfile);
00586 
00587 #if SAVE_HYSTOGRAMS
00588         // compute values for hystograms
00589         int b = (int)(current_idleness[goal]/RESOLUTION);
00590         if (b<hn) {
00591           hv[b]++; hsum++;
00592         }
00593 #endif
00594 
00595     }
00596 
00597     complete_patrol = calculate_patrol_cycle ( number_of_visits, dimension );                
00598     printf("   complete patrol cycles = %d\n", complete_patrol); 
00599     
00600     // Compute node with highest current idleness
00601     size_t hnode; double hidl=0;
00602     for (size_t i=0; i<dimension; i++) {
00603         double cidl = last_visit_temp - last_visit [i];
00604         if (cidl>hidl) {
00605             hidl=cidl; hnode=i;
00606         }
00607     }
00608     printf("   highest current idleness: node %lu idl %.1f\n\n",hnode,hidl);
00609     
00610     last_visit [goal] = last_visit_temp;
00611     
00612     goal_reached = false;
00613 
00614     dolog("  update_stats - end");
00615 
00616 }
00617 
00618 
00619 int main(int argc, char** argv){  //pass TEAMSIZE GRAPH ALGORITHM
00620   /*
00621   argc=3
00622   argv[0]=/.../patrolling_sim/bin/monitor
00623   argv[1]=grid
00624   argv[2]=ALGORITHM = {MSP,Cyc,CC,CR,HCR}
00625   argv[3]=TEAMSIZE
00626   */
00627   
00628   //ex: "rosrun patrolling_sim monitor maps/example/example.graph MSP 2"
00629   
00630 //   uint teamsize;
00631   char teamsize_str[3];
00632   teamsize = atoi(argv[3]);
00633   
00634   if ( teamsize >= NUM_MAX_ROBOTS || teamsize <1 ){
00635     ROS_INFO("The Teamsize must be an integer number between 1 and %d", NUM_MAX_ROBOTS);
00636     return 0;
00637   }else{
00638     strcpy (teamsize_str, argv[3]); 
00639 //     printf("teamsize: %s\n", teamsize_str);
00640 //     printf("teamsize: %u\n", teamsize);
00641   }
00642   
00643   
00644   algorithm = string(argv[2]);
00645   printf("Algorithm: %s\n",algorithm.c_str());
00646   
00647   string mapname = string(argv[1]);
00648   string graph_file = "maps/"+mapname+"/"+mapname+".graph";
00649 
00650   printf("Graph: %s\n",graph_file.c_str());
00651      
00653   chdir(PS_path.c_str());
00654   
00655   //Check Graph Dimension:
00656   dimension = GetGraphDimension(graph_file.c_str());
00657   if (dimension>MAX_DIMENSION) {
00658     cout << "ERROR!!! dimension > MAX_DIMENSION (static value) !!!" << endl;
00659     abort();
00660   }
00661   printf("Dimension: %u\n",(uint)dimension);
00662    
00663   char hostname[80];
00664     
00665   int r = gethostname(hostname,80);
00666   if (r<0)
00667     strcpy(hostname,"default");
00668     
00669   printf("Host name: %s\n",hostname);
00670        
00671   
00672   
00673   for (size_t i=0; i<dimension; i++){
00674     number_of_visits[i] = -1;  // first visit should not be cnted for avg
00675     current_idleness[i] = 0.0;
00676     last_visit[i] = 0.0;
00677   }
00678   
00679   for (size_t i=0; i<NUM_MAX_ROBOTS; i++){
00680     init_robots[i] = false;
00681     last_goal_reached[i] = 0.0;
00682   }
00683 
00684   bool dead = false; // check if there is a dead robot
00685     
00686     bool simrun, simabort; // check if simulation is running and if it has been aborted by the user
00687 
00688     // Scenario name (to be used in file and directory names)
00689     char sname[80];
00690     scenario_name(sname,graph_file.c_str(),teamsize_str);
00691     
00692 
00693     // Create directory results if does not exist
00694     string path1 = "results";
00695     
00696     string path2,path3,path4;
00697     
00698     path2 = path1 + "/" + string(sname);
00699     path3 = path2 + "/" + algorithm;
00700     path4 = path3 + "/" + hostname;
00701 
00702     
00703     struct stat st;
00704     
00705     if (stat(path1.c_str(), &st) != 0)
00706       mkdir(path1.c_str(), 0777);
00707     if (stat(path2.c_str(), &st) != 0)
00708       mkdir(path2.c_str(), 0777);
00709     if (stat(path3.c_str(), &st) != 0)
00710       mkdir(path3.c_str(), 0777);
00711     if (stat(path4.c_str(), &st) != 0)
00712       mkdir(path4.c_str(), 0777);
00713 
00714     printf("Path experimental results: %s\n",path4.c_str());
00715     
00716     // Local time (real clock time)
00717     time_t rawtime;
00718     struct tm * timeinfo;
00719     char strnow[80];
00720     
00721     time (&rawtime);
00722     timeinfo = localtime(&rawtime);
00723     sprintf(strnow,"%d%02d%02d_%02d%02d%02d",  timeinfo->tm_year+1900,timeinfo->tm_mon+1,timeinfo->tm_mday,timeinfo->tm_hour,timeinfo->tm_min,timeinfo->tm_sec);
00724     printf("Date-time of the experiment: %s\n",strnow);
00725     
00726     // File to log all the idlenesses of an experimental scenario
00727 
00728     string idlfilename,resultsfilename,resultstimecsvfilename,expname; 
00729     expname = path4 + "/" + string(strnow);
00730     idlfilename = expname + "_idleness.csv";
00731     resultsfilename = expname + "_results.txt";
00732     resultstimecsvfilename = expname + "_timeresults.csv";
00733 
00734     FILE *fexplist;
00735     fexplist = fopen("experiments.txt", "a");
00736     fprintf(fexplist,"%s\n",expname.c_str());
00737     fclose(fexplist);
00738 
00739     idlfile = fopen (idlfilename.c_str(),"a");
00740     fprintf(idlfile,"Time;Robot;Node;Idleness;Interferences\n"); // header
00741 
00742     FILE *resultstimecsvfile;
00743     resultstimecsvfile = fopen(resultstimecsvfilename.c_str(), "w");
00744 
00745     fprintf(resultstimecsvfile,"Time;Idleness min;Idleness avg;Idleness stddev;Idleness max;Interferences\n"); // header
00746 
00747 #if LOG_MONITOR
00748     char logfilename[80];
00749     sprintf(logfilename,"monitor_%s.log",strnow);
00750     logfile = fopen(logfilename, "w");
00751 #endif
00752 
00753     dolog("Monitor node starting");
00754     dolog(expname.c_str());
00755 
00756 #if SAVE_HYSTOGRAMS    
00757     // Vectors for hystograms
00758     for (int k=0; k<hn; k++) hv[k]=0;
00759     hsum=0;
00760 #endif
00761     
00762   //Wait for all robots to connect! (Exchange msgs)
00763   ros::init(argc, argv, "monitor");
00764   ros::NodeHandle nh;
00765   
00766   //Subscribe "results" from robots
00767   results_sub = nh.subscribe("results", 100, resultsCB);   
00768   
00769   //Publish data to "results"
00770   results_pub = nh.advertise<std_msgs::Int16MultiArray>("results", 100);
00771   
00772   screenshot_pub = nh.advertise<std_msgs::String>("/stageGUIRequest", 100);
00773     
00774 
00775   double duration = 0.0, real_duration = 0.0;
00776   
00777   ros::Rate loop_rate(30); //0.033 seconds or 30Hz
00778   
00779   nh.setParam("/simulation_running", "true");
00780   nh.setParam("/simulation_abort", "false");
00781   
00782   if(ros::service::exists("/GotoStartPosSrv", false)){ //see if service has been advertised or not
00783        goto_start_pos = true;  //if service exists: robots need to be sent to starting positions
00784        ROS_INFO("/GotoStartPosSrv is advertised. Robots will be sent to starting positions.");
00785   }else{
00786       ROS_WARN("/GotoStartPosSrv does not exist. Assuming robots are already at starting positions.");
00787   }
00788     
00789   double current_time = ros::Time::now().toSec();
00790   
00791     // read parameters
00792     if (! ros::param::get("/goal_reached_wait", goal_reached_wait)) {
00793       goal_reached_wait = 0.0;
00794       ROS_WARN("Cannot read parameter /goal_reached_wait. Using default value 0.0!");
00795     }
00796 
00797     if (! ros::param::get("/communication_delay", comm_delay)) {
00798       comm_delay = 0.0;
00799       ROS_WARN("Cannot read parameter /communication_delay. Using default value 0.0!");
00800     } 
00801 
00802     if (! ros::param::get("/lost_message_rate", lost_message_rate)) {
00803       lost_message_rate = 0.0;
00804       ROS_WARN("Cannot read parameter /lost_message_rate. Using default value 0.0!");
00805     }
00806 
00807     if (! ros::param::get("/initial_positions", initial_positions)) {
00808       initial_positions = "default";
00809       ROS_WARN("Cannot read parameter /initial_positions. Using default value '%s'!", initial_positions.c_str());
00810     }
00811 
00812     if (! ros::param::get("/navigation_module", nav_mod)) {
00813       ROS_WARN("Cannot read parameter /navigation_module. Using default value 'ros'!");
00814       nav_mod = "ros";
00815     }
00816 
00817 
00818   // mutex for accessing last_goal_reached vector
00819   pthread_mutex_init(&lock_last_goal_reached, NULL);
00820 
00821 
00822 
00823   while( ros::ok() ){
00824     
00825     dolog("main loop - begin");
00826 
00827     if (!initialize){  //check if msg is goal or interference -> compute necessary results.
00828             
00829       // check time
00830       double report_time = ros::Time::now().toSec();
00831       
00832       // printf("### report time=%.1f  last_report_time=%.1f diff = %.1f\n",report_time, last_report_time, report_time - last_report_time);
00833       
00834       // write results every TIMEOUT_WRITE_RESULTS seconds anyway
00835       bool timeout_write_results = (report_time - last_report_time > TIMEOUT_WRITE_RESULTS);
00836       
00837       if ((patrol_cnt == complete_patrol) || timeout_write_results){ 
00838 
00839         dolog("main loop - write results begin");
00840 
00841         if (complete_patrol==1) {
00842                 ros::param::get("/algorithm_params", algparams);
00843             if (! ros::param::get("/goal_reached_wait", goal_reached_wait))
00844                 goal_reached_wait = 0.0;
00845         }
00846 
00847         // write results every time a patrolling cycle is finished.
00848         // or after some time
00849         previous_avg_graph_idl = avg_graph_idl; //save previous avg idleness graph value
00850 
00851         printf("******************************************\n");
00852         printf("Patrol completed [%d]. Write to File!\n",complete_patrol);
00853 
00854         worst_avg_idleness = 0.0;
00855         avg_graph_idl = 0.0;
00856         stddev_graph_idl = 0.0;
00857         avg_stddev_graph_idl = 0.0;
00858                 
00859         // Compute avg and stddev
00860         double T0=0.0,T1=0.0,T2=0.0,S1=0.0;
00861         for (size_t i=0; i<dimension; i++){
00862             T0++; T1+=avg_idleness[i]; T2+=avg_idleness[i]*avg_idleness[i];
00863             S1+=stddev_idleness[i];
00864             if ( avg_idleness[i] > worst_avg_idleness ){
00865                 worst_avg_idleness = avg_idleness[i];
00866             }
00867         }
00868                 
00869         avg_graph_idl = T1/T0;
00870         stddev_graph_idl = 1.0/T0 * sqrt(T0*T2-T1*T1);
00871         avg_stddev_graph_idl = S1/T0;
00872         // global stats
00873         gavg = gT1/gT0;
00874         gstddev = 1.0/gT0 * sqrt(gT0*gT2-gT1*gT1);
00875 
00876         uint i,tot_visits=0;
00877         for (size_t i=0; i<dimension; i++){
00878             tot_visits += number_of_visits[i];
00879         }
00880         float avg_visits = (float)tot_visits/dimension;
00881 
00882         duration = report_time-time_zero;
00883         time_t real_now; time (&real_now); 
00884         real_duration = (double)real_now - (double)real_time_zero;                              
00885         
00886         printf("Node idleness\n");
00887         printf("   worst_avg_idleness (graph) = %.2f\n", worst_avg_idleness);
00888         printf("   avg_idleness (graph) = %.2f\n", avg_graph_idl);
00889         median_graph_idl = Median (avg_idleness, dimension);
00890         printf("   median_idleness (graph) = %.2f\n", median_graph_idl);
00891         printf("   stddev_idleness (graph) = %.2f\n", stddev_graph_idl);
00892 
00893         printf("Global idleness\n");
00894         printf("   min = %.1f\n", min_idleness);
00895         printf("   avg = %.1f\n", gavg);
00896         printf("   stddev = %.1f\n", gstddev);
00897         printf("   max = %.1f\n", max_idleness);
00898 
00899         printf("\nInterferences\t%u\nInterference rate\t%.2f\nVisits\t%u\nAvg visits per node\t%.1f\nTime Elapsed\t%.1f\nReal Time Elapsed\t%.1f\n",
00900             interference_cnt,(float)interference_cnt/duration*60,tot_visits,avg_visits,duration,real_duration);
00901         
00902         if (timeout_write_results)
00903           last_report_time = report_time;
00904         else
00905           patrol_cnt++;
00906         
00907                 
00908         double tolerance = 0.025 * avg_graph_idl;  //2.5% tolerance
00909         printf ("diff avg_idleness = %.1f\n",fabs(previous_avg_graph_idl - avg_graph_idl));
00910         printf ("tolerance = %.1f\n",tolerance);
00911         
00912         // write results to file
00913         if (!timeout_write_results)
00914             write_results (avg_idleness, stddev_idleness, number_of_visits, complete_patrol, dimension, 
00915                    worst_avg_idleness, avg_graph_idl, median_graph_idl, stddev_graph_idl,
00916                    min_idleness, gavg, gstddev, max_idleness,
00917                    interference_cnt, tot_visits, avg_visits,
00918                    graph_file.c_str(), teamsize_str, duration, real_duration, comm_delay,
00919                    resultsfilename);
00920         else {
00921             /*
00922             write_results (avg_idleness, stddev_idleness, number_of_visits, complete_patrol, dimension, 
00923                    worst_avg_idleness, avg_graph_idl, median_graph_idl, stddev_graph_idl,
00924                    min_idleness, gavg, gstddev, max_idleness,
00925                    interference_cnt, tot_visits, avg_visits,
00926                    graph_file.c_str(), teamsize_str, duration, real_duration, comm_delay,
00927                    resultstimefilename);
00928             */
00929 
00930             fprintf(resultstimecsvfile,"%.1f;%.1f;%.1f;%.1f;%.1f;%d\n", 
00931                                                  duration,min_idleness,gavg,gstddev,max_idleness,interference_cnt);
00932             fflush(resultstimecsvfile);
00933 
00934                 }
00935 
00936         dolog("main loop - write results begin");
00937 
00938       } // if ((patrol_cnt == complete_patrol) || timeout_write_results)
00939       
00940 
00941       dolog("    check - begin");
00942 
00943       // Check if simulation must be terminated
00945       dead = check_dead_robots();
00946                 
00947       simrun=true; simabort=false;
00948       std::string psimrun, psimabort; bool bsimabort;
00949       if (nh.getParam("/simulation_running", psimrun))
00950           if (psimrun=="false")
00951               simrun = false;
00952       if (nh.getParam("/simulation_abort", psimabort))
00953           if (psimabort=="true")
00954               simabort = true;
00955       if (nh.getParam("/simulation_abort", bsimabort))
00956           simabort = bsimabort;
00957         
00958       if ( (dead) || (!simrun) || (simabort) ) {
00959           printf ("Simulation is Over\n");                
00960           nh.setParam("/simulation_running", false);
00961           finish_simulation ();
00962           ros::spinOnce();
00963           break;
00964       }
00967       dolog("    check - end");
00968 
00969     } // if ! initialize  
00970     
00971     current_time = ros::Time::now().toSec();
00972     ros::spinOnce();
00973     loop_rate.sleep();
00974 
00975     dolog("main loop - end");
00976         
00977   } // while ros ok
00978 
00979   ros::shutdown();
00980 
00981   fclose(idlfile);
00982   fclose(resultstimecsvfile);
00983 
00984 
00985 
00986     
00987     duration = current_time-time_zero;
00988     time_t real_now; time (&real_now); 
00989     real_duration = (double)real_now - (double)real_time_zero;
00990 
00991     uint tot_visits=0;
00992     for (size_t i=0; i<dimension; i++){
00993         tot_visits += number_of_visits[i];
00994     }
00995     float avg_visits = (float)tot_visits/dimension;
00996 
00997 
00998     // Write info file with overall results 
00999     string infofilename;
01000     infofilename = expname + "_info.csv";
01001 
01002     FILE *infofile;
01003     infofile = fopen (infofilename.c_str(),"w");
01004     fprintf(infofile,"%s;%s;%s;%.1f;%.2f;%s;%s;%s;%s;%s;%.1f;%.1f;%d;%s;%.1f;%.1f;%.1f;%.1f;%.2f;%d;%.1f;%d\n",
01005             mapname.c_str(),teamsize_str,initial_positions.c_str(),goal_reached_wait,comm_delay,nav_mod.c_str(),
01006             algorithm.c_str(), algparams.c_str(),hostname,
01007             strnow,duration,real_duration,interference_cnt,(dead?"FAIL":(simabort?"ABORT":"TIMEOUT")),
01008             min_idleness, gavg, gstddev, max_idleness, (float)interference_cnt/duration*60,
01009             tot_visits, avg_visits, complete_patrol
01010     );
01011 
01012     fclose(infofile);
01013     cout << "Info file " << infofilename << " saved." << endl;
01014 
01015 
01016 #if SAVE_HYSTOGRAMS
01017     // Hystogram files
01018     string hfilename,chfilename;
01019     hfilename = expname + ".hist";
01020     chfilename = expname + ".chist";
01021 
01022     cout << "Histogram output files: " << hfilename << endl;
01023     std::ofstream of1; of1.open(hfilename.c_str());
01024     std::ofstream of2; of2.open(chfilename.c_str());
01025     double c=0;
01026     for (int k=0; k<hn; k++) {
01027         of1 << k*RESOLUTION << " " << (double)hv[k]/hsum << endl;
01028         c += (double)hv[k]/hsum;
01029         of2 << k*RESOLUTION << " " << c << endl;
01030     }
01031     of1.close();   of2.close();
01032 #endif
01033     
01034   printf("Monitor closed.\n");
01035 
01036   dolog("Monitor closed");
01037 
01038 #if EXTENDED_STAGE
01039   sleep(5);
01040   char cmd[80];
01041   sprintf(cmd, "mv ~/.ros/stage-000003.png %s/%s_stage.png", path4.c_str(),strnow);
01042   system(cmd);
01043   printf("%s\n",cmd);
01044   printf("Screenshot image copied.\n");
01045   sleep(3);  
01046   dolog("Snapshots done");
01047 #endif
01048   
01049 }
01050 


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