Conscientious_Reactive_Agent.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 <ros/ros.h>
00040 #include <move_base_msgs/MoveBaseAction.h>
00041 #include <actionlib/client/simple_action_client.h>
00042 #include <tf/transform_broadcaster.h>
00043 #include <tf/transform_listener.h>
00044 #include <nav_msgs/Odometry.h>
00045 
00046 #include "PatrolAgent.h"
00047 
00048 
00049 
00050 class Conscientious_Reactive_Agent: public PatrolAgent {
00051     
00052 public:
00053     virtual int compute_next_vertex();
00054     //virtual void send_results();
00055     //virtual void receive_results();    
00056 };
00057 
00058 
00059 
00060 int Conscientious_Reactive_Agent::compute_next_vertex() {
00061 
00062   //number of neighbors of current vertex (number of existing possibilites)
00063   uint num_neighs = vertex_web[current_vertex].num_neigh;
00064   uint next_vertex;
00065   
00066   if (num_neighs > 1){
00067     
00068     double decision_table [num_neighs];
00069     uint neighbors [num_neighs];
00070     uint possibilities[num_neighs];
00071      
00072     uint i, hits=0;
00073     double max_idleness= -1;
00074     
00075     for (i=0; i<num_neighs; i++){
00076         neighbors[i] = vertex_web[current_vertex].id_neigh[i];        //neighbors table
00077         decision_table[i] = instantaneous_idleness [ neighbors[i] ];  //corresponding idleness table
00078         //printf("   --- vertex %u -> idleness %.1f\n",neighbors[i],decision_table[i]);
00079         
00080         //choose the one with maximum idleness:
00081         if (decision_table[i] > max_idleness){
00082             max_idleness = decision_table[i];       //maximum idleness
00083             hits=0;
00084             possibilities[hits] = neighbors[i];    
00085         } 
00086         else if(decision_table[i] == max_idleness) {
00087             hits ++;
00088             possibilities[hits] = neighbors[i];
00089         }
00090     }      
00091       
00092     if(hits>0){ //more than one possibility (choose at random)
00093       srand ( time(NULL) );
00094       i = rand() % (hits+1) + 0;    //0, ... ,hits
00095     
00096       //printf("rand integer = %d\n", i);
00097       next_vertex = possibilities [i];      // random vertex with higher idleness
00098         
00099       }else{
00100         next_vertex = possibilities[hits];  //vertex with higher idleness
00101       }
00102     
00103     }else{
00104         next_vertex = vertex_web[current_vertex].id_neigh[0]; //only one possibility
00105     }
00106   
00107     ROS_INFO("Conscientious_Reactive choice: %d",next_vertex);
00108     return next_vertex;
00109 }
00110 
00111 #if 0
00112 // FIXME Not needed at all, right?
00113 void Conscientious_Reactive_Agent::send_results() {
00114   ros::spinOnce();    
00115 }
00116 
00117 void Conscientious_Reactive_Agent::receive_results() {
00118   ros::spinOnce();   
00119 }
00120 #endif
00121 
00122 int main(int argc, char** argv) {
00123   
00124     Conscientious_Reactive_Agent agent;
00125     agent.init(argc,argv);
00126     agent.run();
00127 
00128     return 0; 
00129 }
00130 


patrolling_sim
Author(s):
autogenerated on Thu Jun 6 2019 20:27:09