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: Luca Iocchi (2014-2016) 00036 *********************************************************************/ 00037 00038 #include "SSIPatrolAgent.h" 00039 00040 00041 00042 00043 //Sequential Single Item Auction with dynamic compact partition of the environment 00044 class DTASSIPart_Agent: public SSIPatrolAgent { 00045 00046 protected: 00047 //center location given current tasks: task location that is at minimum path distance from all other locations. This is always a task location. 00048 size_t current_center_location; 00049 00050 //compute minimum path cost considering all tasks (tasks) and the next vertex (nv). 00051 //The first room is always the current goal (if any), then rooms are visited in decreasing order of utility. 00052 //The path cost is sum of travel cost given the order. 00053 double compute_bid(int nv); 00054 00055 //update tasks setting to true only the vertices for which this robot has the current highest bid 00056 //based on the array bids 00057 void update_tasks(); 00058 00059 //compute center point given current tasks 00060 void compute_center_location(); 00061 00062 double compute_sum_distance(int cv); 00063 00064 00065 00066 public: 00067 00068 DTASSIPart_Agent(){} 00069 00070 void init(int argc, char** argv); 00071 00072 00073 }; 00074 00075 void DTASSIPart_Agent::init(int argc, char** argv) { 00076 00077 // logfile = fopen("DTASSIOut.log","w"); 00078 00079 // fprintf(logfile,"INITIALIZING \n"); 00080 // fflush(logfile); 00081 00082 SSIPatrolAgent::init(argc,argv); 00083 00084 // fprintf(logfile,"INITIALIZING 2 \n"); 00085 // fflush(logfile); 00086 00087 //set current center location to current vertex 00088 current_center_location = current_vertex; 00089 00090 // fprintf(logfile,"initialised current center location to: %d \n",current_center_location); 00091 00092 //initialize parameters 00093 00094 } 00095 00096 double DTASSIPart_Agent::compute_bid(int nv){ 00097 00098 /*printf("computing bid for vertex %d (using dynamic partition) \n ",nv); 00099 printf("current tasks = "); 00100 for (size_t i = 0; i<dimension;i++){ 00101 printf(" %d, ",tasks[i]); 00102 } 00103 printf("] \n");*/ 00104 00105 if (nv==next_vertex || nv==next_next_vertex){ 00106 // printf("already going to %d sending 0 (current target: %d)",nv,next_vertex); 00107 return 0.; 00108 } 00109 00110 size_t num_tasks = 1; 00111 for (size_t i = 0; i<dimension ; i++){ 00112 if (tasks[i]){ 00113 num_tasks++; 00114 } 00115 } 00116 00117 // size_t cv = current_vertex; 00118 // if (next_vertex >= 0 && next_vertex <dimension){ 00119 // cv = next_vertex; 00120 // } 00121 00122 double bid_value = compute_cost(nv,current_center_location)*num_tasks; 00123 //printf("bid for %d (current center %zu, num task %zu): %.2f \n",nv,current_center_location,num_tasks,bid_value); 00124 00125 return bid_value; 00126 } 00127 00128 00129 00130 00131 void DTASSIPart_Agent::compute_center_location(){ 00132 size_t min = current_vertex; 00133 // printf("compute center:: min: %d current center: %d \n",min,current_center_location); 00134 double min_dist = compute_sum_distance(min); 00135 // printf("compute center:: min dist: %.2f \n",min_dist); 00136 for (size_t i = 0; i<dimension; i++){ 00137 if (i!=current_center_location && tasks[i]){ 00138 double dist = compute_sum_distance(i); 00139 // printf("compute center:: current dist: %.2f, min dist: %.2f, current min: %d, current point: %d \n",dist,min_dist,min,i); 00140 if ( dist < min_dist){ 00141 min = i; 00142 min_dist = dist; 00143 } 00144 } 00145 } 00146 current_center_location = min; 00147 00148 } 00149 00150 double DTASSIPart_Agent::compute_sum_distance(int cv){ 00151 if(cv<0 || cv >= dimension){ 00152 // printf("return big number: cv = %d",cv); 00153 return BIG_NUMBER; 00154 } 00155 double sum = 0.; 00156 for (size_t i = 0; i<dimension ; i++){ 00157 if (tasks[i]){ 00158 // printf("sum: %2.f \n",sum); 00159 sum+= compute_cost(cv,i); 00160 } 00161 } 00162 return sum; 00163 } 00164 00165 void DTASSIPart_Agent::update_tasks(){ 00166 00167 /*debug print 00168 printf("updating tasks: \n tasks before["); 00169 for (size_t i = 0; i<dimension; i++){ 00170 printf(" %d, ",tasks[i]); 00171 } 00172 printf("] \n"); 00173 00174 printf("bids ["); 00175 for (size_t i = 0; i<dimension; i++){ 00176 printf(" <%.2f,%d>, ",bids[i].bidValue,bids[i].robotId); 00177 } 00178 printf("] \n"); 00179 00180 printf("center location before %d \n",current_center_location); 00181 00182 ------------*/ 00183 00184 int value = ID_ROBOT; 00185 if (value==-1){value=0;} 00186 00187 nactivetasks=0; 00188 bool changed = false; 00189 for (size_t i = 0; i< dimension; i++){ 00190 if (!changed && tasks[i] != (bids[i].robotId == value)){ 00191 changed = true; 00192 } 00193 tasks[i] = (bids[i].robotId == value); 00194 if (tasks[i]) nactivetasks++; 00195 } 00196 00197 if (changed){ 00198 compute_center_location(); 00199 } 00200 00201 #if DEBUG_PRINT 00202 00203 printf("DTAP current center location: %lu\n",current_center_location); 00204 printf("DTAP: Active Tasks %d [",nactivetasks); 00205 for (size_t i = 0; i<dimension; i++){ 00206 if (tasks[i]) printf("%lu ",i); 00207 } 00208 printf("] \n"); 00209 00210 00211 00212 #endif 00213 } 00214 00215 00216 00217 int main(int argc, char** argv) { 00218 00219 DTASSIPart_Agent agent; 00220 agent.init(argc,argv); 00221 agent.run(); 00222 00223 return 0; 00224 } 00225