00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 typedef unsigned int uint;
00039
00040
00041 typedef struct {
00042 int id, dist, elem_path;
00043 int path[1000];
00044 bool visit;
00045 }s_path;
00046
00047 typedef struct {
00048 int id, elem_path;
00049 double dist;
00050 int path[1000];
00051 bool visit;
00052 }s_path_mcost;
00053
00054 uint conscientious_reactive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness){
00055
00056
00057 uint num_neighs = vertex_web[current_vertex].num_neigh;
00058 uint next_vertex;
00059
00060 if (num_neighs > 1){
00061
00062 double decision_table [num_neighs];
00063 uint neighbors [num_neighs];
00064 uint possibilities[num_neighs];
00065
00066 uint i, hits=0;
00067 double max_idleness= -1;
00068
00069 for (i=0; i<num_neighs; i++){
00070 neighbors[i] = vertex_web[current_vertex].id_neigh[i];
00071 decision_table[i] = instantaneous_idleness [ neighbors[i] ];
00072
00073
00074 if (decision_table[i] > max_idleness){
00075 max_idleness = decision_table[i];
00076
00077 hits=0;
00078 possibilities[hits] = neighbors[i];
00079
00080 }else if(decision_table[i] == max_idleness){
00081 hits ++;
00082 possibilities[hits] = neighbors[i];
00083 }
00084 }
00085
00086 if(hits>0){
00087 srand ( time(NULL) );
00088 i = rand() % (hits+1) + 0;
00089
00090
00091 next_vertex = possibilities [i];
00092
00093 }else{
00094 next_vertex = possibilities[hits];
00095 }
00096
00097 }else{
00098 next_vertex = vertex_web[current_vertex].id_neigh[0];
00099 }
00100
00101 return next_vertex;
00102
00103 }
00104
00105
00106 uint heuristic_conscientious_reactive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness){
00107
00108
00109 uint num_neighs = vertex_web[current_vertex].num_neigh;
00110 uint next_vertex;
00111
00112 if (num_neighs > 1){
00113
00114
00115
00116
00117
00118 uint i, max_distance=0;
00119 double max_idleness=-1;
00120 uint neighbors [num_neighs];
00121
00122
00123
00124
00125 for (i=0; i<num_neighs; i++){
00126 neighbors[i] = vertex_web[current_vertex].id_neigh[i];
00127
00128 if (instantaneous_idleness [neighbors[i]] > max_idleness){
00129 max_idleness = instantaneous_idleness [neighbors[i]];
00130 }
00131
00132 if (vertex_web[current_vertex].cost[i] > max_distance){
00133 max_distance = vertex_web[current_vertex].cost[i];
00134 }
00135
00136
00137
00138 }
00139
00140
00141
00142
00143
00144 double normalized_idleness, normalized_distance, distance, idleness;
00145 double decision_table [num_neighs];
00146
00147
00148 for (i=0; i<num_neighs; i++){
00149
00150 distance = vertex_web[current_vertex].cost[i];
00151 idleness = instantaneous_idleness [ neighbors[i] ];
00152
00153 normalized_distance = (double) (max_distance - distance) / (double) (max_distance);
00154 if (max_idleness == 0.0){
00155 normalized_idleness = 0.0;
00156 }else{
00157 normalized_idleness = idleness / max_idleness;
00158 }
00159
00160
00161
00162
00163 decision_table[i] = normalized_distance + normalized_idleness;
00164
00165 }
00166
00167 double max_decision=-1;
00168 uint hits = 0;
00169 uint possibilities[num_neighs];
00170
00171
00172 for (i=0; i<num_neighs; i++){
00173
00174 if (decision_table[i]>max_decision){
00175 max_decision = decision_table[i];
00176 hits = 0;
00177 possibilities[hits] = neighbors[i];
00178 }else if (decision_table[i]==max_decision){
00179 hits ++;
00180 possibilities[hits] = neighbors[i];
00181 }
00182 }
00183
00184 if(hits>0){
00185
00186 srand ( time(NULL) );
00187 i = rand() % (hits+1) + 0;
00188
00189
00190 next_vertex = possibilities [i];
00191
00192
00193 }else{
00194 next_vertex = possibilities[hits];
00195
00196 }
00197
00198
00199 }else{
00200 next_vertex = vertex_web[current_vertex].id_neigh[0];
00201
00202 }
00203
00204 return next_vertex;
00205
00206 }
00207
00208 uint greedy_bayesian_strategy (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, double G1, double G2, double edge_min){
00209
00210
00211 uint num_neighs = vertex_web[current_vertex].num_neigh;
00212 uint next_vertex;
00213
00214 if (num_neighs > 1){
00215
00216 double posterior_probability [num_neighs];
00217 uint neighbors [num_neighs];
00218 uint possibilities[num_neighs];
00219
00220 uint i, hits=0;
00221 double max_pp= -1;
00222 double gain, exp_param, edge_weight;
00223 double log_result = log (1.0/G1);
00224
00225 for (i=0; i<num_neighs; i++){
00226 neighbors[i] = vertex_web[current_vertex].id_neigh[i];
00227
00228 edge_weight = (double) vertex_web[current_vertex].cost[i];
00229 if (edge_weight<edge_min) {edge_weight = edge_min;}
00230
00231
00232 gain = (instantaneous_idleness [ neighbors[i] ] / edge_weight);
00233
00234
00235 if (gain < G2){
00236
00237
00238
00239 exp_param = (log_result/G2)*gain;
00240
00241
00242 posterior_probability[i] = G1 * exp (exp_param);
00243
00244
00245 }else{
00246 posterior_probability[i] = 1.0;
00247 }
00248
00249 printf("Vertex [%d]; PP = %f\n", vertex_web[current_vertex].id_neigh[i], posterior_probability[i]);
00250
00251
00252 if (posterior_probability[i] > max_pp){
00253 max_pp = posterior_probability[i];
00254
00255 hits=0;
00256 possibilities[hits] = neighbors[i];
00257
00258 }else if (posterior_probability[i] == max_pp){
00259 hits ++;
00260 possibilities[hits] = neighbors[i];
00261 }
00262 }
00263
00264 if(hits>0){
00265 srand ( time(NULL) );
00266 i = rand() % (hits+1) + 0;
00267
00268
00269 next_vertex = possibilities [i];
00270
00271 }else{
00272 next_vertex = possibilities[hits];
00273 }
00274
00275 }else{
00276 next_vertex = vertex_web[current_vertex].id_neigh[0];
00277 }
00278
00279 return next_vertex;
00280
00281 }
00282
00283 int count_intention (uint vertex, int *tab_intention, int nr_robots){
00284
00285 int count = 0;
00286
00287 for (int i = 0; i<nr_robots; i++){
00288 if(tab_intention[i]==vertex){
00289 count++;
00290 }
00291 }
00292 return count;
00293 }
00294
00295 uint state_exchange_bayesian_strategy (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, int *tab_intention, int nr_robots, double G1, double G2, double edge_min){
00296
00297
00298 uint num_neighs = vertex_web[current_vertex].num_neigh;
00299 uint next_vertex;
00300
00301 if (num_neighs > 1){
00302
00303 double posterior_probability [num_neighs];
00304 uint neighbors [num_neighs];
00305 uint possibilities[num_neighs];
00306
00307 uint i, hits=0;
00308 double max_pp= -1;
00309 double gain, exp_param, edge_weight;
00310 double log_result = log (1.0/G1);
00311
00312 for (i=0; i<num_neighs; i++){
00313 neighbors[i] = vertex_web[current_vertex].id_neigh[i];
00314
00315 edge_weight = (double) vertex_web[current_vertex].cost[i];
00316 if (edge_weight<edge_min) {edge_weight = edge_min;}
00317
00318
00319 gain = (instantaneous_idleness [ neighbors[i] ] / edge_weight);
00320
00321
00322 if (gain < G2){
00323
00324
00325
00326 exp_param = (log_result/G2)*gain;
00327
00328
00329 posterior_probability[i] = G1 * exp (exp_param);
00330
00331
00332 }else{
00333 posterior_probability[i] = 1.0;
00334 }
00335
00336
00337
00338
00339 int count = count_intention (neighbors[i], tab_intention, nr_robots);
00340
00341 if (count>0){
00342
00343
00344 printf("Vertex [%d]; PP (without state exchange) = %f\n", vertex_web[current_vertex].id_neigh[i], posterior_probability[i]);
00345 double P_gain_state = ( pow(2,nr_robots-count) ) / ( pow(2,nr_robots) - 1.0);
00346 posterior_probability[i] *= P_gain_state;
00347
00348
00349 }
00350
00351 printf("Vertex [%d]; PP = %f\n", vertex_web[current_vertex].id_neigh[i], posterior_probability[i]);
00352
00353
00354 if (posterior_probability[i] > max_pp){
00355 max_pp = posterior_probability[i];
00356
00357 hits=0;
00358 possibilities[hits] = neighbors[i];
00359
00360 }else if (posterior_probability[i] == max_pp){
00361 hits ++;
00362 possibilities[hits] = neighbors[i];
00363 }
00364 }
00365
00366 if(hits>0){
00367 srand ( time(NULL) );
00368 i = rand() % (hits+1) + 0;
00369
00370
00371 next_vertex = possibilities [i];
00372
00373 }else{
00374 next_vertex = possibilities[hits];
00375 }
00376
00377 }else{
00378 next_vertex = vertex_web[current_vertex].id_neigh[0];
00379 }
00380
00381 return next_vertex;
00382
00383 }
00384
00385 void dijkstra( uint source, uint destination, int *shortest_path, uint &elem_s_path, vertex *vertex_web, uint dimension){
00386
00387 uint i,j,k,x;
00388 int id_next_vertex=-1;
00389
00390 s_path *tab_dijkstra = new s_path[dimension];
00391
00392
00393 for(i=0; i<dimension; i++){
00394
00395 tab_dijkstra[i].id = vertex_web[i].id;
00396 tab_dijkstra[i].elem_path = 0;
00397 tab_dijkstra[i].visit = false;
00398
00399 if (vertex_web[i].id == source) {
00400 tab_dijkstra[i].dist = 0;
00401 tab_dijkstra[i].path[0] = source;
00402 tab_dijkstra[i].elem_path++;
00403 id_next_vertex = i;
00404 }else{
00405 tab_dijkstra[i].dist = INT_MAX;
00406 }
00407
00408 }
00409
00410 int next_vertex = source;
00411 int minim_dist;
00412 bool cont;
00413
00414 while(true){
00415
00416
00417
00418 if(next_vertex == destination){
00419 break;
00420 }
00421
00422 tab_dijkstra[id_next_vertex].visit = true;
00423
00424
00425
00426
00427
00428
00429 for(k=0; k<vertex_web[next_vertex].num_neigh; k++){
00430
00431 cont = false;
00432
00433
00434 for(j=0; j<dimension; j++){
00435 if(tab_dijkstra[j].id == vertex_web[next_vertex].id_neigh[k] && tab_dijkstra[j].visit == false){
00436 cont = true;
00437 break;
00438 }
00439 }
00440
00441 if(cont){
00442
00443
00444 if( tab_dijkstra[id_next_vertex].dist + vertex_web[next_vertex].cost[k] < tab_dijkstra[j].dist){
00445
00446
00447 tab_dijkstra[j].dist = tab_dijkstra[id_next_vertex].dist + vertex_web[next_vertex].cost[k];
00448
00449
00450 for (x=0; x<tab_dijkstra[id_next_vertex].elem_path; x++){
00451 tab_dijkstra[j].path[x] = tab_dijkstra[id_next_vertex].path[x];
00452 }
00453
00454 tab_dijkstra[j].path[tab_dijkstra[id_next_vertex].elem_path] = tab_dijkstra[j].id;
00455 tab_dijkstra[j].elem_path = tab_dijkstra[id_next_vertex].elem_path+1;
00456
00457 }
00458
00459 }
00460
00461
00462
00463 }
00464
00465 minim_dist = INT_MAX;
00466
00467
00468 for(i=0; i<dimension; i++){
00469
00470 if(tab_dijkstra[i].dist < minim_dist && tab_dijkstra[i].visit == false){
00471 minim_dist = tab_dijkstra[i].dist;
00472 next_vertex = tab_dijkstra[i].id;
00473 id_next_vertex = i;
00474 }
00475
00476 }
00477
00478 }
00479
00480
00481 elem_s_path = tab_dijkstra[id_next_vertex].elem_path;
00482
00483 for(i=0; i<elem_s_path; i++){
00484 shortest_path[i] = tab_dijkstra[id_next_vertex].path[i];
00485 }
00486
00487 delete [] tab_dijkstra;
00488
00489 }
00490
00491
00492 int is_neigh(uint vertex1, uint vertex2, vertex *vertex_web, uint dimension){
00493 int i;
00494
00495 for (i=0; i<vertex_web[vertex1].num_neigh; i++){
00496 if(vertex2 == vertex_web[vertex1].id_neigh[i]){
00497 return i;
00498 }
00499 }
00500
00501 return -1;
00502 }
00503
00504
00505 void dijkstra_mcost( uint source, uint destination, int *shortest_path, uint &elem_s_path, vertex *vertex_web, double new_costs[][8], uint dimension){
00506
00507 uint i,j,k,x;
00508 int id_next_vertex=-1;
00509
00510 s_path_mcost *tab_dijkstra = new s_path_mcost[dimension];
00511
00512
00513 for(i=0; i<dimension; i++){
00514
00515 tab_dijkstra[i].id = vertex_web[i].id;
00516 tab_dijkstra[i].elem_path = 0;
00517 tab_dijkstra[i].visit = false;
00518
00519 if (vertex_web[i].id == source) {
00520 tab_dijkstra[i].dist = 0.0;
00521 tab_dijkstra[i].path[0] = source;
00522 tab_dijkstra[i].elem_path++;
00523 id_next_vertex = i;
00524 }else{
00525 tab_dijkstra[i].dist = INFINITY;
00526 }
00527
00528 }
00529
00530 int next_vertex = source;
00531 double minim_dist;
00532 bool cont;
00533
00534 while(true){
00535
00536
00537
00538 if(next_vertex == destination){
00539 break;
00540 }
00541
00542 tab_dijkstra[id_next_vertex].visit = true;
00543
00544
00545
00546
00547
00548
00549 for(k=0; k<vertex_web[next_vertex].num_neigh; k++){
00550
00551 cont = false;
00552
00553
00554 for(j=0; j<dimension; j++){
00555 if(tab_dijkstra[j].id == vertex_web[next_vertex].id_neigh[k] && tab_dijkstra[j].visit == false){
00556 cont = true;
00557 break;
00558 }
00559 }
00560
00561 if(cont){
00562
00563
00564 if( tab_dijkstra[id_next_vertex].dist + new_costs[next_vertex][k] < tab_dijkstra[j].dist){
00565
00566
00567 tab_dijkstra[j].dist = tab_dijkstra[id_next_vertex].dist + new_costs[next_vertex][k];
00568
00569
00570 for (x=0; x<tab_dijkstra[id_next_vertex].elem_path; x++){
00571 tab_dijkstra[j].path[x] = tab_dijkstra[id_next_vertex].path[x];
00572 }
00573
00574 tab_dijkstra[j].path[tab_dijkstra[id_next_vertex].elem_path] = tab_dijkstra[j].id;
00575 tab_dijkstra[j].elem_path = tab_dijkstra[id_next_vertex].elem_path+1;
00576
00577 }
00578
00579 }
00580
00581
00582
00583 }
00584
00585 minim_dist = INFINITY;
00586
00587
00588 for(i=0; i<dimension; i++){
00589
00590 if(tab_dijkstra[i].dist < minim_dist && tab_dijkstra[i].visit == false){
00591 minim_dist = tab_dijkstra[i].dist;
00592 next_vertex = tab_dijkstra[i].id;
00593 id_next_vertex = i;
00594 }
00595
00596 }
00597
00598 }
00599
00600
00601 elem_s_path = tab_dijkstra[id_next_vertex].elem_path;
00602
00603 for(i=0; i<elem_s_path; i++){
00604 shortest_path[i] = tab_dijkstra[id_next_vertex].path[i];
00605 }
00606
00607 delete [] tab_dijkstra;
00608
00609 }
00610
00611
00612 uint heuristic_pathfinder_conscientious_cognitive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, uint dimension, uint *path){
00613
00614
00615 uint distance[dimension];
00616 uint i,j, elem_s_path, max_distance=0, max_cost=0, min_cost=INT_MAX;
00617 double max_idleness=-1;
00618
00619
00620 for (i=0; i<dimension; i++){
00621
00622
00623 if (instantaneous_idleness [i] > max_idleness){
00624 max_idleness = instantaneous_idleness [i];
00625 }
00626
00627 if (i==current_vertex){
00628 distance[i] = 0;
00629
00630
00631 }else{
00632
00633 int id_neigh = is_neigh(current_vertex, i, vertex_web, dimension);
00634
00635 if (id_neigh>=0){
00636 distance[i] = vertex_web[current_vertex].cost[id_neigh];
00637
00638
00639 }else{
00640
00641 int *shortest_path = new int[dimension];
00642 uint j;
00643
00644
00645 dijkstra( current_vertex, i, shortest_path, elem_s_path, vertex_web, dimension);
00646 distance[i] = 0;
00647
00648 for(j=0; j<elem_s_path; j++){
00649
00650
00651 if (j<elem_s_path-1){
00652 id_neigh = is_neigh(shortest_path[j], shortest_path[j+1], vertex_web, dimension);
00653 distance[i] += vertex_web[shortest_path[j]].cost[id_neigh];
00654 }
00655 }
00656
00657 delete [] shortest_path;
00658 }
00659 }
00660
00661
00662 for(j=0; j<vertex_web[i].num_neigh; j++){
00663 if (vertex_web[i].cost[j] > max_cost){
00664 max_cost = vertex_web[i].cost[j];
00665 }
00666 if (vertex_web[i].cost[j] < min_cost){
00667 min_cost = vertex_web[i].cost[j];
00668 }
00669 }
00670
00671
00672 if (distance[i] > max_distance){
00673 max_distance = distance[i];
00674 }
00675 }
00676
00677
00678
00679
00680
00681 double normalized_idleness, normalized_distance;
00682 double decision_table [dimension];
00683
00684
00685 for (i=0; i<dimension; i++){
00686
00687 normalized_distance = (double) (max_distance - distance[i]) / (double) (max_distance);
00688
00689 if (max_idleness == 0.0){
00690 normalized_idleness = 0.0;
00691 }else{
00692 normalized_idleness = instantaneous_idleness[i] / max_idleness;
00693 }
00694
00695 if (i!=current_vertex){
00696 decision_table[i] = normalized_distance + normalized_idleness;
00697 }else{
00698 decision_table[i] = 0.0;
00699 }
00700 }
00701
00702
00703
00704
00705
00706 uint next_vertex;
00707
00708
00709 double new_costs [dimension][8];
00710
00711 for (i=0; i<dimension; i++){
00712
00713
00714
00715
00716
00717
00718
00719
00720
00721
00722 for(j=0; j<vertex_web[i].num_neigh; j++){
00723
00724
00725 if (max_idleness==0.0){
00726 normalized_idleness = 0.0;
00727 }else{
00728 normalized_idleness = (max_idleness - instantaneous_idleness[ vertex_web[i].id_neigh[j] ]) / max_idleness;
00729 }
00730
00731 if (max_cost==min_cost){
00732 normalized_distance = 0.0;
00733 }else{
00734 normalized_distance = (double)(vertex_web[i].cost[j] - min_cost) / (double)(max_cost-min_cost);
00735 }
00736
00737
00738
00739
00740 new_costs[i][j] = normalized_idleness + normalized_distance;
00741
00742
00743 }
00744
00745 }
00746
00747
00748 double max_decision=-1;
00749 uint hits = 0;
00750 uint possibilities[dimension];
00751
00752
00753 for (i=0; i<dimension; i++){
00754
00755 if (decision_table[i]>max_decision){
00756 max_decision = decision_table[i];
00757 hits = 0;
00758 possibilities[hits] = i;
00759 }else if (decision_table[i]==max_decision){
00760 hits ++;
00761 possibilities[hits] = i;
00762 }
00763 }
00764
00765 if(hits>0){
00766
00767 srand ( time(NULL) );
00768 i = rand() % (hits+1) + 0;
00769
00770
00771 next_vertex = possibilities [i];
00772
00773
00774 }else{
00775 next_vertex = possibilities[hits];
00776
00777 }
00778
00779
00780
00781
00782 int *shortest_path = new int[dimension];
00783
00784
00785 dijkstra_mcost( current_vertex, next_vertex, shortest_path, elem_s_path, vertex_web, new_costs, dimension);
00786
00787
00788
00789
00790 for(i=0; i<elem_s_path; i++){
00791 path[i] = shortest_path[i];
00792
00793 }
00794
00795 delete [] shortest_path;
00796
00797 return elem_s_path;
00798
00799 }
00800
00801
00802 bool pertence (int elemento, int *tab, int tam_tab){
00803
00804 for (int i=0; i<tam_tab; i++){
00805
00806 if( tab[i] == elemento) {
00807 return true;
00808 }
00809
00810 }
00811
00812 return false;
00813 }
00814
00815 int pertence_idx (int elemento, int *tab, int tam_tab){
00816
00817 for (int i=0; i<tam_tab; i++){
00818
00819 if( tab[i] == elemento) {
00820 return i;
00821 }
00822
00823 }
00824
00825 return -1;
00826 }
00827
00828 bool UHC (vertex *vertex_web, int v1, int *caminho_principal, uint dimension) {
00829
00830
00831
00832
00833 int prox_vertice = v1, elem_cp = 0, v, i, i_viz;
00834 int caminho_parcial [dimension];
00835 int *viz_pvert = new int[8];
00836 srand(1000);
00837
00838 caminho_parcial[elem_cp] = prox_vertice;
00839 elem_cp++;
00840
00841
00842
00843 while( elem_cp < dimension ){
00844
00845 i_viz=0;
00846
00847
00848 for(i=0; i<vertex_web[prox_vertice].num_neigh; i++){
00849
00850 if ( !pertence (vertex_web[prox_vertice].id_neigh[i], caminho_parcial, elem_cp) ){
00851 viz_pvert[i_viz] = vertex_web[prox_vertice].id_neigh[i];
00852 i_viz++;
00853 }
00854
00855
00856 }
00857
00858 if(i_viz>0){
00859 i = rand() % i_viz;
00860 v = viz_pvert[i];
00861 }else{
00862
00863 return false;
00864 }
00865
00866
00867
00868
00869
00870 if( !pertence(v, caminho_parcial, elem_cp) ) {
00871
00872 caminho_parcial [elem_cp] = v;
00873 elem_cp++;
00874
00875 prox_vertice = v;
00876 }
00877
00878
00879
00880
00881
00882
00883
00884 }
00885
00886
00887
00888 delete [] viz_pvert;
00889
00890
00891 for(i=0; i<elem_cp; i++){
00892 caminho_principal[i] = caminho_parcial[i];
00893 }
00894
00895 return true;
00896
00897 }
00898
00899 void clear_visited (vertex *vertex_web, uint dimension){
00900
00901 int i,j;
00902
00903 for (i=0; i<dimension; i++){
00904 for(j=0; j<vertex_web[i].num_neigh; j++){
00905
00906 vertex_web[i].visited[j] = false;
00907 }
00908 }
00909
00910 }
00911
00912 bool procurar_ciclo (vertex *vertex_web, uint dimension, int *caminho_principal, int &elem_caminho, int &custo_max, int seed) {
00913
00914 int i, k=0, n, rec, i_list=0, origem, custo, ult_elemento, elem_cp=0, caminho_parcial [dimension];
00915 bool encontra_destino, escolha_aleatoria;
00916 int *lista_v2v = new int[1000];
00917
00918 clear_visited(vertex_web, dimension);
00919
00920 for(i=0; i<dimension; i++){
00921
00922 if( vertex_web[i].num_neigh > 1 ) {
00923
00924 lista_v2v[i_list] = vertex_web[i].id;
00925 i_list++;
00926
00927 }
00928 }
00929
00930
00931
00932 bool encontrou_ciclo=false;
00933 int count=0;
00934 custo_max = 0;
00935
00936 for (n=0; n<i_list+1; n++){
00937
00938 if(encontrou_ciclo && count<3){
00939
00940 count++;
00941 seed+=1000;
00942 n--;
00943
00944 }else{
00945 count = 0;
00946 seed = 1000;
00947 if(n==i_list){break;}
00948 }
00949
00950 encontrou_ciclo = false;
00951 srand(seed);
00952
00953
00954
00955 clear_visited(vertex_web, dimension);
00956
00957
00958
00959 for(i=0; i<dimension; i++){
00960
00961 if( vertex_web[i].num_neigh == 1 ) {
00962
00963 vertex_web[i].visited[0] = true;
00964
00965
00966 rec = vertex_web[i].id_neigh[0];
00967
00968 for(k=0; k<vertex_web[rec].num_neigh; k++){
00969 if (vertex_web[rec].id_neigh[k] == vertex_web[i].id){
00970 vertex_web[rec].visited[k]=true;
00971
00972 break;
00973 }
00974 }
00975
00976 }
00977 }
00978
00979
00980
00981
00982 custo = 0;
00983 origem = lista_v2v[n];
00984 elem_cp = 0;
00985 encontra_destino = false;
00986 int *viz = new int[8];
00987 ult_elemento=-1;
00988 int aux, conta, viz_c_4_arcos;
00989
00990
00991 caminho_parcial [ elem_cp ] = origem;
00992 elem_cp++;
00993
00994 while( ult_elemento!=origem || elem_cp>1 ){
00995
00996 escolha_aleatoria = false;
00997
00998 ult_elemento = caminho_parcial [elem_cp-1];
00999
01000
01001
01002
01003
01004
01005
01006 k=0;
01007
01008
01009 for(i=0; i<vertex_web[ult_elemento].num_neigh; i++){
01010
01011
01012
01013
01014
01015
01016
01017
01018
01019 if ( vertex_web[ult_elemento].visited[i] == false){
01020 viz[k] = vertex_web[ult_elemento].id_neigh[i];
01021 k++;
01022 }
01023
01024
01025 }
01026
01027
01028 if (k==0){
01029
01030
01031 encontra_destino = true;
01032
01033 if(elem_cp>1){
01034
01035
01036
01037 for(i=0; i<vertex_web[ult_elemento].num_neigh; i++){
01038
01039
01040
01041
01042
01043
01044
01045
01046
01047 if ( vertex_web[ vertex_web[ult_elemento].id_neigh[i] ].num_neigh > 1 ){
01048
01049
01050
01051
01052 if( !pertence(vertex_web[ult_elemento].id_neigh[i],caminho_parcial,elem_cp)){
01053
01054
01055
01056
01057 vertex_web[ult_elemento].visited[i] = false;
01058
01059
01060
01061
01062 for(k=0; k<vertex_web[vertex_web[ult_elemento].id_neigh[i]].num_neigh; k++){
01063 if( vertex_web[vertex_web[ult_elemento].id_neigh[i]].id_neigh[k] == vertex_web[ult_elemento].id){
01064 vertex_web[vertex_web[ult_elemento].id_neigh[i]].visited[k] = false;
01065
01066 break;
01067 }
01068 }
01069
01070 }
01071 }
01072
01073 }
01074
01075 elem_cp--;
01076
01077 }else{
01078
01079
01080 break;
01081 }
01082
01083 }else{
01084
01085
01086
01087
01088 if(pertence(origem, viz, k)){
01089
01090
01091
01092
01093 if(encontra_destino || k==1){
01094
01095
01096 caminho_parcial[elem_cp] = origem;
01097 elem_cp++;
01098
01099
01100
01101
01102
01103
01104
01105
01106
01107
01108
01109
01110
01111 for (i=0; i<elem_cp-1; i++){
01112 for(k=0; k<vertex_web[ caminho_parcial[i] ].num_neigh; k++){
01113 if( vertex_web[ caminho_parcial[i] ].id_neigh[k] == vertex_web[ caminho_parcial[i+1] ].id ){
01114 custo += vertex_web[ caminho_parcial[i] ].cost[k];
01115 break;
01116 }
01117 }
01118 }
01119
01120
01121
01122 if(custo>custo_max){
01123 custo_max=custo;
01124
01125
01126 for(i=0; i<elem_cp; i++){
01127 caminho_principal[i] = caminho_parcial[i];
01128 }
01129
01130 elem_caminho = elem_cp;
01131 }
01132
01133
01134
01135 encontrou_ciclo = true;
01136 break;
01137
01138 }else{
01139
01140
01141
01142 for(i=0; i<k; i++){
01143
01144 if(viz[i] == origem){
01145
01146 if(i<k-1){
01147 for(rec=i; rec<k-1; rec++){
01148 viz[rec] = viz[rec+1];
01149 }
01150 }
01151
01152
01153 k--;
01154
01155 }
01156 }
01157
01158
01159
01160
01161
01162
01163
01164 escolha_aleatoria = true;
01165 }
01166
01167 }else{
01168
01169 escolha_aleatoria = true;
01170 }
01171
01172 if(escolha_aleatoria == true){
01173
01174 if(encontra_destino){encontra_destino=false;}
01175
01176
01177
01178
01179
01180
01181
01182
01183 viz_c_4_arcos = -1;
01184
01185 for(i=0; i<k; i++){
01186
01187 conta=0;
01188
01189
01190
01191 for(aux=0; aux<vertex_web[viz[i]].num_neigh; aux++){
01192
01193
01194
01195
01196
01197
01198
01199 if(vertex_web[viz[i]].visited[aux] == false){
01200 conta++;
01201
01202 }
01203
01204 if(conta>=4){
01205 viz_c_4_arcos = viz[i];
01206
01207 break;
01208 }
01209
01210
01211
01212 }
01213 }
01214
01215
01216
01217 if (viz_c_4_arcos==-1){
01218 i = rand() % k;
01219 caminho_parcial [elem_cp] = viz[i];
01220
01221
01222 }else{
01223 caminho_parcial [elem_cp] = viz_c_4_arcos;
01224 }
01225
01226
01227
01228
01229
01230
01231
01232
01233 for(rec=0; rec<vertex_web[ult_elemento].num_neigh; rec++){
01234 if( is_neigh ( vertex_web[ult_elemento].id, vertex_web[ult_elemento].id_neigh[rec], vertex_web, dimension ) > -1){
01235
01236 if (vertex_web[ult_elemento].id_neigh[rec] == caminho_parcial [elem_cp]){
01237
01238 vertex_web[ult_elemento].visited[rec] = true;
01239
01240
01241
01242
01243
01244 for(k=0; k<vertex_web[caminho_parcial [elem_cp]].num_neigh; k++){
01245 if (vertex_web[caminho_parcial [elem_cp]].id_neigh[k] == vertex_web[ult_elemento].id){
01246
01247 vertex_web[caminho_parcial [elem_cp]].visited[k]=true;
01248 break;
01249 }
01250 }
01251
01252 }
01253
01254 }
01255 }
01256
01257 elem_cp++;
01258
01259 }
01260
01261 }
01262
01263
01264
01265
01266
01267 }
01268
01269 delete [] viz;
01270
01271
01272 }
01273
01274
01275
01276 return true;
01277
01278 }
01279
01280 int devolve_viz_unicos (vertex *vertex_web, int vertice){
01281
01282 if (vertex_web[vertice].num_neigh == 1){
01283 return vertex_web[vertice].id_neigh[0];
01284
01285 }else{
01286 return -1;
01287 }
01288
01289 }
01290
01291 int longest_path (vertex *vertex_web, int origem, int destino, int *lista_v1v, int i_list, int dimension, int seed, int *caminho_parcial, int &elem_cp) {
01292
01293
01294
01295
01296 bool debug = false;
01297
01298 int i, k;
01299 int rec;
01300
01301 elem_cp = 0;
01302 int custo = 0;
01303
01304
01305 clear_visited(vertex_web, dimension);
01306
01307
01308 for(i=0; i<i_list; i++){
01309 if(!(lista_v1v[i]== origem || lista_v1v[i]==destino)){
01310
01311 vertex_web[ lista_v1v[i] ].visited[0] = true;
01312 if(debug){printf("ID = %i, Vizinho = %i -> descartado\n", lista_v1v[i],vertex_web[ lista_v1v[i] ].id_neigh[0]);}
01313
01314 rec = vertex_web[ lista_v1v[i] ].id_neigh[0];
01315
01316 for(k=0; k<vertex_web[rec].num_neigh; k++){
01317 if (vertex_web[rec].id_neigh[k] == vertex_web[lista_v1v[i]].id){
01318 vertex_web[rec].visited[k]=true;
01319 break;
01320 if(debug){printf("ID = %i, Vizinho = %i -> descartado\n", rec,vertex_web[ rec ].id_neigh[k]);}
01321 }
01322 }
01323
01324 }else{
01325
01326 vertex_web[ lista_v1v[i] ].visited[0] = false;
01327
01328 rec = vertex_web[ lista_v1v[i] ].id_neigh[0];
01329
01330 for(k=0; k<vertex_web[rec].num_neigh; k++){
01331 if (vertex_web[rec].id_neigh[k] == vertex_web[lista_v1v[i]].id){
01332 vertex_web[rec].visited[k]=false;
01333 break;
01334 }
01335 }
01336
01337 }
01338 }
01339
01340 if(debug){printf("\n");}
01341
01342
01343
01344 bool encontra_destino = false;
01345 bool escolha_aleatoria;
01346 int *viz = new int[8];
01347 int ult_elemento=-1;
01348 int aux, conta, viz_c_4_arcos;
01349
01350 caminho_parcial [ elem_cp ] = origem;
01351 elem_cp++;
01352
01353 srand(seed);
01354
01355
01356 while( ult_elemento!=destino ){
01357
01358 escolha_aleatoria = false;
01359
01360 ult_elemento = caminho_parcial [elem_cp-1];
01361
01362 if(debug){printf("---------------------------------------\n");
01363 printf("Ultimo Elemento = %i\n", ult_elemento);
01364 printf("elementos no cp= %i\n", elem_cp);}
01365
01366
01367 k=0;
01368
01369
01370 for(i=0; i<vertex_web[ult_elemento].num_neigh; i++){
01371
01372
01373
01374
01375
01376 if ( vertex_web[ult_elemento].visited[i] == false ){
01377 viz[k] = vertex_web[ult_elemento].id_neigh[i];
01378 k++;
01379 }
01380
01381
01382 }
01383
01384 if(debug){printf("k=%i\n",k);}
01385
01386
01387 if (k==0){
01388 encontra_destino = true;
01389
01390 if(elem_cp>1){
01391
01392 if(debug){printf("percorrer vizinhos de %i\n", vertex_web[ult_elemento].id);}
01393 for(i=0; i<vertex_web[ult_elemento].num_neigh; i++){
01394
01395 if(debug){printf("vizinho %i\n", vertex_web[ult_elemento].id_neigh[i]);}
01396
01397
01398
01399
01400
01401
01402
01403 if ( vertex_web[ vertex_web[ult_elemento].id_neigh[i] ].num_neigh > 1 ){
01404
01405 if(debug){ printf("%i tem + de 1 vizinho\n", vertex_web[ult_elemento].id_neigh[i]); }
01406
01407
01408
01409
01410 if( !pertence(vertex_web[ult_elemento].id_neigh[i],caminho_parcial,elem_cp)) {
01411
01412 if(debug){ printf("%i e diferente do ult. vertice do caminho parcial %i\n", vertex_web[ult_elemento].id_neigh[i], vertex_web[caminho_parcial[elem_cp-2]].id); }
01413
01414
01415 vertex_web[ult_elemento].visited[i] = false;
01416 if(debug){ printf("ID = %i, Vizinho = %i -> disponivel\n", vertex_web[ult_elemento].id, vertex_web[ult_elemento].id_neigh[i]); }
01417
01418
01419
01420
01421
01422 for(k=0; k<vertex_web[vertex_web[ult_elemento].id_neigh[i]].num_neigh; k++){
01423 if( vertex_web[vertex_web[ult_elemento].id_neigh[i]].id_neigh[k] == vertex_web[ult_elemento].id){
01424 vertex_web[vertex_web[ult_elemento].id_neigh[i]].visited[k] = false;
01425 if(debug){ printf("Reciproco: ID = %i, Vizinho = %i -> descartado\n", vertex_web[vertex_web[ult_elemento].id_neigh[i]].id, vertex_web[vertex_web[ult_elemento].id_neigh[i]].id_neigh[k]);}
01426 break;
01427 }
01428 }
01429
01430 }
01431 }
01432
01433 }
01434 elem_cp--;
01435 }else{
01436
01437
01438 return 0;
01439 }
01440
01441 }else{
01442
01443
01444 if(pertence(destino, viz, k)){
01445
01446
01447
01448
01449 if(encontra_destino || k==1){
01450
01451
01452 caminho_parcial[elem_cp] = destino;
01453 elem_cp++;
01454 if(debug){ printf("acabei com sucesso (nao sobram + vizinhos para alem do destino)\n");
01455 printf("caminho_parcial: ");
01456 for(i=0; i<elem_cp; i++){
01457 if(i==elem_cp-1){printf("%i\n", caminho_parcial[i]);}else{printf("%i, ", caminho_parcial[i]);}
01458 }
01459 printf("elementos = %i\n----------------------\n", elem_cp); }
01460
01461
01462
01463
01464 for (i=0; i<elem_cp-1; i++){
01465 for(k=0; k<vertex_web[ caminho_parcial[i] ].num_neigh; k++){
01466 if( vertex_web[ caminho_parcial[i] ].id_neigh[k] == vertex_web[ caminho_parcial[i+1] ].id ){
01467 custo += vertex_web[ caminho_parcial[i] ].cost[k];
01468 break;
01469 }
01470 }
01471 }
01472
01473
01474
01475 delete [] viz;
01476 return custo;
01477
01478 }else{
01479
01480 if(debug){printf("retirar o destino da lista de vizinhos!\n");}
01481
01482 for(i=0; i<k; i++){
01483
01484 if(viz[i] == destino){
01485
01486 if(i<k-1){
01487 for(rec=i; rec<k-1; rec++){
01488 viz[rec] = viz[rec+1];
01489 }
01490 }
01491
01492
01493 k--;
01494
01495 }
01496 }
01497
01498 if(debug){printf("lista de vizinhos apos retirar:\n");
01499 for(i=0; i<k; i++){printf("viz[%i]=%i\n",i,viz[i]); }
01500 }
01501
01502
01503 escolha_aleatoria = true;
01504 }
01505
01506 }else{
01507
01508 escolha_aleatoria = true;
01509 }
01510
01511 if(escolha_aleatoria == true){
01512
01513 if(encontra_destino){encontra_destino=false;}
01514
01515
01516
01517
01518
01519
01520
01521
01522 viz_c_4_arcos = -1;
01523
01524 for(i=0; i<k; i++){
01525
01526 conta=0;
01527
01528 if(debug){printf("verificar arcos ligados a %i\n", viz[i]);}
01529
01530 for(aux=0; aux<vertex_web[viz[i]].num_neigh; aux++){
01531
01532 if(debug){printf("arco q liga a %i\n", vertex_web[viz[i]].id_neigh[aux]);}
01533
01534
01535
01536
01537
01538 if(vertex_web[viz[i]].visited[aux] == false){
01539 conta++;
01540 if(debug){printf("conta = %i\n",conta);}
01541 }
01542
01543 if(conta>=4){
01544 viz_c_4_arcos = viz[i];
01545 if(debug){printf("encontrei vizinho com 4 arcos livres: %i\n", viz[i]);}
01546 break;
01547 }
01548
01549
01550
01551 }
01552 }
01553
01554
01555
01556 if (viz_c_4_arcos==-1){
01557 i = rand() % k;
01558 caminho_parcial [elem_cp] = viz[i];
01559
01560
01561 }else{
01562 caminho_parcial [elem_cp] = viz_c_4_arcos;
01563 }
01564
01565
01566 if(debug){ printf("escolhas possiveis: ");
01567 for(i=0; i<k; i++){printf("%i ",viz[i]);}
01568 printf("\nproximo vertice escolhido aleatoriamente = %i\n", caminho_parcial [elem_cp]); }
01569
01570
01571 for(rec=0; rec<vertex_web[ult_elemento].num_neigh; rec++){
01572 if( is_neigh ( vertex_web[ult_elemento].id, vertex_web[ult_elemento].id_neigh[rec], vertex_web, dimension ) > -1){
01573
01574 if (vertex_web[ult_elemento].id_neigh[rec] == caminho_parcial [elem_cp]){
01575 if(debug){ printf("arco de %i para %i passou a fazer parte do caminho\n", vertex_web[ult_elemento].id, vertex_web[ult_elemento].id_neigh[rec]);}
01576 vertex_web[ult_elemento].visited[rec] = true;
01577
01578
01579
01580
01581
01582 for(k=0; k<vertex_web[caminho_parcial [elem_cp]].num_neigh; k++){
01583 if (vertex_web[caminho_parcial [elem_cp]].id_neigh[k] == vertex_web[ult_elemento].id){
01584 if(debug){ printf("RECIPROCO: arco de %i para %i passou a fazer parte do caminho\n", vertex_web[caminho_parcial [elem_cp]].id, vertex_web[caminho_parcial [elem_cp]].id_neigh[k]);}
01585 vertex_web[caminho_parcial [elem_cp]].visited[k]=true;
01586 break;
01587 }
01588 }
01589
01590 }
01591
01592 }
01593 }
01594
01595 elem_cp++;
01596
01597 }
01598
01599 }
01600
01601 }
01602
01603 delete [] viz;
01604 return 0;
01605
01606 }
01607
01608 bool caminho_apartir_vizinhos_unicos (vertex *vertex_web, int dimension, int *caminho_principal, int &elem_max, int &custo_max, int seed){
01609
01610 int i,j,i_uc = 0;
01611
01612 int *lista_v1v = new int[1000];
01613 int i_list=0;
01614
01615
01616
01617 int valor = -1;
01618
01619
01620 for(i=0; i<dimension; i++){
01621
01622 valor = devolve_viz_unicos (vertex_web, vertex_web[i].id);
01623
01624 if (valor > -1){
01625
01626 lista_v1v[i_list] = vertex_web[i].id;
01627
01628 i_list++;
01629
01630 }
01631
01632 }
01633
01634
01635
01636 if (i_list<=1){
01637 printf("Impossible to compute longest path.\n");
01638
01639 return false;
01640 }
01641
01642
01643
01644
01645
01646
01647 custo_max = 0;
01648 int retorno=0, origem_caminho=-1, destino_caminho=-1, elem_caminho = 0;
01649 int caminho_parcial[dimension];
01650
01651 for(i=0; i<i_list; i++){
01652 for(j=0; j<i_list; j++){
01653 if(i<j){
01654
01655 retorno = longest_path(vertex_web, lista_v1v[i], lista_v1v[j], lista_v1v, i_list, dimension, seed, caminho_parcial, elem_caminho);
01656
01657 if(retorno>custo_max){
01658 custo_max=retorno;
01659
01660 for(i_uc = 0; i_uc<elem_caminho; i_uc++){
01661 caminho_principal[i_uc] = caminho_parcial[i_uc];
01662 }
01663
01664 elem_max = elem_caminho;
01665
01666 origem_caminho=lista_v1v[i];
01667 destino_caminho=lista_v1v[j];
01668 }
01669 }
01670 }
01671 }
01672
01673
01674
01675 delete [] lista_v1v;
01676 return true;
01677
01678 }
01679
01680 bool verificar_arco_cp (int no_1, int no_2, int *caminho_principal, int elem_cp){
01681
01682 int i;
01683 for(i=0; i<elem_cp; i++){
01684
01685 if(caminho_principal[i] == no_1){
01686
01687 if(i>0){
01688 if(caminho_principal[i-1] == no_2){
01689 return true;
01690 }
01691 }
01692
01693 if(i<elem_cp-1){
01694 if(caminho_principal[i+1] == no_2){
01695 return true;
01696 }
01697 }
01698
01699 }
01700 }
01701
01702 return false;
01703
01704 }
01705
01706 bool check_visited (vertex *vertex_web, int dimension){
01707
01708 int i, j;
01709
01710 for(i=0; i<dimension; i++){
01711
01712 for(j=0; j<vertex_web[i].num_neigh; j++){
01713
01714 if( vertex_web[i].visited[j] == false ){
01715
01716 return false;
01717
01718 }
01719 }
01720 }
01721
01722 return true;
01723
01724 }
01725
01726
01727 int devolve_vizinhos_nao_visitados (vertex *vertex_web, int dimension, int vertice){
01728
01729 int i_viz=0;
01730 int i;
01731
01732
01733 for(i=0; i<vertex_web[vertice].num_neigh; i++){
01734
01735
01736
01737 if(vertex_web[vertice].visited[i] == false){
01738 i_viz++;
01739 }
01740
01741
01742 }
01743
01744 return i_viz;
01745
01746 }
01747
01748 bool computar_caminho_de_ida (vertex *vertex_web, int dimension, int *caminho_de_ida, int &elem_c_ida, int *caminho_principal, int elem_cp, int num_arcos){
01749
01750 int i,j;
01751 int rec, idx_viz_cp=-1;
01752
01753 int arcos_ja_visitados;
01754
01755 int desvio [dimension*5];
01756 int regresso [dimension];
01757 int i_desvio=0, i_reg, idx_reg_directo=-1;
01758 bool sai_logo;
01759 int no_ant, prox_no, ult_no_cp, viz_escolhido, idx_cp=0;
01760 bool sai, tem_reg_directo, pertence_CP;
01761 int lista_viz[8];
01762 int i_list, num_neigh;
01763
01764 caminho_de_ida[0] = caminho_principal[idx_cp];
01765
01766 elem_c_ida++;
01767
01768 while(idx_cp<elem_cp){
01769
01770
01771
01772 prox_no = caminho_principal[idx_cp+1];
01773 ult_no_cp = caminho_principal[idx_cp];
01774
01775
01776 if(vertex_web[ult_no_cp].id != ult_no_cp){vertex_web[ult_no_cp].id = ult_no_cp;}
01777
01778
01779 for(j=0; j<vertex_web[ult_no_cp].num_neigh; j++){
01780
01781 if( is_neigh (ult_no_cp, vertex_web[ult_no_cp].id_neigh[j],vertex_web,dimension) > -1
01782 && vertex_web[ult_no_cp].visited[j] == false
01783 && !verificar_arco_cp (ult_no_cp, vertex_web[ult_no_cp].id_neigh[j], caminho_principal, elem_cp) ){
01784
01785 prox_no = vertex_web[ult_no_cp].id_neigh[j];
01786
01787 break;
01788 }
01789
01790
01791 if (vertex_web[ult_no_cp].id_neigh[j]== caminho_principal[idx_cp+1]){
01792 idx_viz_cp = j;
01793 }
01794
01795 }
01796
01797
01798
01799
01800
01801 if(prox_no == caminho_principal[idx_cp+1]){
01802
01803
01804 for(i=0; i<vertex_web[ult_no_cp].num_neigh; i++){
01805 if(vertex_web[ult_no_cp].id_neigh[i] == vertex_web[ult_no_cp].id_neigh[idx_viz_cp] && vertex_web[ult_no_cp].visited[i] == false) {
01806 vertex_web[ult_no_cp].visited[i] = true;
01807 }
01808 }
01809
01810 rec = vertex_web[ult_no_cp].id_neigh[idx_viz_cp];
01811
01812 for(j=0; j<vertex_web[rec].num_neigh; j++){
01813 if(vertex_web[rec].id_neigh[j] == ult_no_cp && vertex_web[rec].visited[j]==false){
01814 vertex_web[rec].visited[j] = true;
01815 }
01816 }
01817
01818
01819 caminho_de_ida[elem_c_ida] = prox_no;
01820
01821 elem_c_ida++;
01822 idx_cp++;
01823
01824 if(prox_no == caminho_principal[elem_cp-1]){
01825
01826 break;
01827 }
01828
01829 }else{
01830
01831
01832
01833
01834
01835
01836
01837
01838
01839
01840
01841 arcos_ja_visitados = 0;
01842 no_ant = ult_no_cp;
01843
01844
01845
01846
01847 i_desvio=0; i_reg=0;
01848 desvio[i_desvio] = ult_no_cp;
01849 i_desvio++;
01850 bool assinala;
01851 sai = false;
01852 sai_logo = false;
01853 pertence_CP = false;
01854
01855
01856 if( pertence (vertex_web[ult_no_cp].id_neigh[j], caminho_principal, elem_cp) ){
01857
01858 pertence_CP = true;
01859 sai = true;
01860 }
01861
01862 while (arcos_ja_visitados<num_arcos){
01863
01864 tem_reg_directo = false;
01865 assinala = false;
01866
01867
01868
01869
01870
01871
01872
01873 for(i=0; i<vertex_web[prox_no].num_neigh; i++){
01874 if(vertex_web[prox_no].id_neigh[i] == no_ant && vertex_web[prox_no].visited[i] == false){
01875 vertex_web[prox_no].visited[i] = true;
01876 assinala = true;
01877
01878 }
01879
01880
01881 if (vertex_web[prox_no].id_neigh[i] == ult_no_cp){
01882 tem_reg_directo = true;
01883 idx_reg_directo = i;
01884 }
01885 }
01886
01887
01888 if(assinala){
01889
01890
01891 for(i=0; i<vertex_web[no_ant].num_neigh; i++){
01892 if(vertex_web[no_ant].id_neigh[i] == vertex_web[no_ant].id_neigh[j] && vertex_web[no_ant].visited[i] == false){
01893 vertex_web[no_ant].visited[i] = true;
01894
01895 }
01896 }
01897 }
01898
01899
01900
01901 desvio[i_desvio] = prox_no;
01902
01903
01904 viz_escolhido = pertence_idx (desvio[i_desvio], desvio, i_desvio-1);
01905
01906 if( viz_escolhido > -1){
01907
01908
01909
01910
01911
01912 if ( is_neigh (prox_no, regresso[i_reg-1], vertex_web, dimension) == -1 ){
01913
01914 regresso[i_reg] = no_ant;
01915 i_reg++;
01916
01917 }
01918
01919 }else{
01920
01921 regresso[i_reg] = no_ant;
01922 i_reg++;
01923
01924
01925 arcos_ja_visitados++;
01926 }
01927
01928
01929 i_desvio++;
01930
01931
01932 if(pertence_CP){
01933 desvio[i_desvio] = regresso[i_reg-1];
01934 i_desvio++;
01935 i_reg--;
01936
01937
01938 rec = no_ant;
01939 no_ant = prox_no;
01940 prox_no = rec;
01941 }
01942
01943
01944
01945
01946
01947
01948
01949
01950
01951
01952
01953
01954
01955
01956
01957 pertence_CP = false;
01958
01959 viz_escolhido = -1;
01960
01961 if(arcos_ja_visitados>=num_arcos){
01962
01963
01964
01965 if (tem_reg_directo && i_reg>0){
01966
01967
01968
01969
01970 vertex_web[prox_no].visited[idx_reg_directo] = true;
01971
01972
01973 for(i=0; i<vertex_web[ult_no_cp].num_neigh; i++){
01974 if(vertex_web[ult_no_cp].id_neigh[i] == prox_no){
01975 vertex_web[ult_no_cp].visited[i] = true;
01976 }
01977 }
01978
01979 desvio[i_desvio] = ult_no_cp;
01980 i_desvio++;
01981
01982
01983
01984
01985
01986
01987 break;
01988
01989 }else{
01990
01991 sai=true;
01992 }
01993
01994 }else{
01995
01996
01997
01998
01999 i_list=0;
02000 pertence_CP = false;
02001
02002 for(i=0; i<vertex_web[prox_no].num_neigh; i++){
02003
02004 if (is_neigh (prox_no, vertex_web[prox_no].id_neigh[i], vertex_web, dimension)>-1
02005 && vertex_web[prox_no].visited[i] == false && !verificar_arco_cp(prox_no, vertex_web[prox_no].id_neigh[i], caminho_principal, elem_cp) ){
02006
02007 lista_viz[i_list] = vertex_web[prox_no].id_neigh[i];
02008 i_list++;
02009
02010 }
02011 }
02012
02013
02014
02015
02016
02017
02018 i=0;
02019
02020 while(i_list>1){
02021
02022 if( pertence(lista_viz[i], caminho_principal, elem_cp)){
02023
02024 if(i<i_list-1){
02025 for(j=i; j<i_list-1; j++){
02026 lista_viz[j] = lista_viz[j+1];
02027 }
02028 }
02029
02030 i_list--;
02031 }
02032
02033 i++;
02034
02035 if(i == i_list){
02036
02037
02038
02039
02040
02041
02042 break;
02043 }
02044
02045 }
02046
02047 if(i_list==1){
02048
02049 if(pertence(lista_viz[0], caminho_principal, elem_cp)){
02050 pertence_CP = true;
02051
02052 }
02053 }
02054
02055 if(i_list <= 0){
02056
02057
02058
02059
02060 for(i=i_reg-1; i>=0; i--){
02061
02062 j = devolve_vizinhos_nao_visitados(vertex_web, dimension, regresso[i]);
02063
02064
02065 if( j > 0) {
02066
02067
02068 break;
02069
02070 }else{
02071
02072 desvio[i_desvio] = regresso [i];
02073 i_desvio++;
02074 i_reg--;
02075 }
02076
02077 }
02078
02079 if(i<=0){
02080
02081
02082
02083 sai = true;
02084
02085 }else{
02086
02087
02088 for(j=0; j<i_desvio;j++){
02089 if (desvio[j] == regresso[i]){
02090 prox_no = desvio[j];
02091 no_ant = desvio[j+1];
02092
02093 break;
02094 }
02095
02096 if(j==i_desvio-1){
02097
02098 printf("Error: There was no atribution of previous and next vertex.\n");
02099 }
02100 }
02101
02102
02103
02104 i_reg-=(i_reg-i);
02105
02106
02107
02108
02109
02110
02111
02112
02113 }
02114
02115
02116 }else{
02117
02118
02119
02120 if(i_list==1){
02121 viz_escolhido = lista_viz[0];
02122
02123
02124 }else{
02125
02126
02127
02128
02129 num_neigh=INT_MAX;
02130
02131 for(i=0; i<i_list; i++){
02132
02133 j=devolve_vizinhos_nao_visitados(vertex_web, dimension, lista_viz[i]);
02134
02135
02136 if(j<num_neigh){
02137 viz_escolhido = lista_viz[i];
02138 num_neigh = j;
02139 }
02140
02141
02142
02143
02144
02145
02146
02147
02148
02149
02150
02151
02152
02153
02154 }
02155
02156 }
02157
02158
02159
02160
02161
02162 for(j=0; j<vertex_web[prox_no].num_neigh; j++){
02163 if(vertex_web[prox_no].id_neigh[j] == viz_escolhido && vertex_web[prox_no].visited[j]==false){
02164 break;
02165 }
02166 }
02167
02168 no_ant = prox_no;
02169 prox_no = viz_escolhido;
02170
02171 }
02172
02173
02174 }
02175
02176 if(sai){
02177
02178
02179 for(i=i_reg-1; i>=0; i--){
02180 desvio[i_desvio] = regresso[i];
02181 i_desvio++;
02182 }
02183
02184
02185 break;
02186
02187 }
02188
02189 }
02190
02191
02192
02193
02194
02195
02196
02197
02198 for(i=1; i<i_desvio; i++){
02199
02200 caminho_de_ida[elem_c_ida] = desvio[i];
02201
02202 elem_c_ida++;
02203 }
02204
02205 }
02206
02207
02208
02209 }
02210
02211
02212
02213 sai = check_visited (vertex_web, dimension);
02214 return sai;
02215
02216 }
02217
02218 int computar_custo_caminho_final (vertex *vertex_web, int *caminho_final, int elem_caminho_final){
02219
02220 int i,j;
02221 int custo_final = 0;
02222 int anterior, proximo;
02223
02224 for(i=1; i<elem_caminho_final; i++){
02225
02226 anterior = caminho_final[i-1];
02227 proximo = caminho_final[i];
02228
02229 for(j=0; j<vertex_web[anterior].num_neigh; j++){
02230
02231 if(vertex_web[anterior].id_neigh[j] == proximo){
02232 custo_final += vertex_web[anterior].cost[j];
02233 break;
02234 }
02235
02236 }
02237
02238 }
02239
02240 return custo_final;
02241
02242 }
02243
02244 int cyclic (uint dimension, vertex *vertex_web, int *caminho_final) {
02245
02246 int caminho_principal [dimension+1];
02247 int elem_caminho;
02248 int custo_caminho;
02249
02250 bool testa = false;
02251 bool hamilton_path = false;
02252 bool cycle = false;
02253 int i;
02254 uint j;
02255
02256 clear_visited(vertex_web,dimension);
02257
02258 for(i=0; i<dimension; i++){
02259
02260 testa = UHC ( vertex_web, vertex_web[i].id, caminho_principal, dimension);
02261
02262 if(testa){
02263
02264
02265
02266
02267
02268
02269 int hcycle;
02270
02271 printf("Hamilton Path found.\n");
02272 hamilton_path = true;
02273
02274
02275 hcycle = is_neigh ( caminho_principal[0], caminho_principal[dimension-1], vertex_web, dimension);
02276
02277
02278 if(hcycle>-1){
02279 printf("Hamilton circuit found.\n");
02280 caminho_principal [dimension] = caminho_principal [0];
02281 cycle = true;
02282 break;
02283 }
02284
02285 }
02286 }
02287
02288
02289
02290
02291 if(!hamilton_path){
02292
02293 printf("No Hamilton Circuit/Path found.\n\n");
02294
02295 int *ciclo_principal = new int[dimension];
02296 int elem_ciclo = 0, custo_ciclo = 0;
02297 int seed = 1000;
02298
02299
02300 procurar_ciclo(vertex_web, dimension, ciclo_principal, elem_ciclo, custo_ciclo, seed);
02301
02302 clear_visited(vertex_web, dimension);
02303
02304
02305 caminho_apartir_vizinhos_unicos(vertex_web, dimension, caminho_principal, elem_caminho, custo_caminho, seed);
02306
02307
02308
02309
02310 if(elem_ciclo>=(dimension/2)){
02311
02312 custo_caminho = custo_ciclo;
02313 elem_caminho=elem_ciclo;
02314
02315 for(i=0; i<elem_caminho; i++){
02316 caminho_principal [i] = ciclo_principal[i];
02317 }
02318
02319 cycle = true;
02320
02321 }
02322
02323
02324 delete [] ciclo_principal;
02325
02326
02327
02328
02329
02330
02331
02332
02333
02334 }else{
02335
02336 if(cycle){
02337
02338
02339 elem_caminho = dimension+1;
02340
02341 }else{
02342
02343 elem_caminho = dimension;
02344 }
02345
02346
02347 printf("Hamilton Path/Circuit: ");
02348 custo_caminho=0;
02349
02350 for(i=0; i<elem_caminho; i++){
02351
02352 if(i==elem_caminho-1){
02353 printf("%i\n", caminho_principal[i]);
02354 printf("cost = %i\n", custo_caminho);
02355
02356 }else{
02357 printf("%i, ", caminho_principal[i]);
02358
02359
02360 for(j=0; j<vertex_web[ caminho_principal[i] ].num_neigh; j++){
02361 if( vertex_web[ caminho_principal[i] ].id_neigh[j] == caminho_principal[i+1] ){
02362 custo_caminho += vertex_web[ caminho_principal[i] ].cost[j];
02363 break;
02364 }
02365 }
02366
02367 }
02368 }
02369 }
02370
02371 int *caminho_de_ida = new int[3*dimension];
02372 int elem_c_ida;
02373
02374 if (!hamilton_path){
02375
02376
02377
02378 int num_max = elem_caminho;
02379 int num_min = 1;
02380 bool resultado = false, sai = false;
02381 double tentativa = 1;
02382 int num_arcos = num_min;
02383
02384
02385 clear_visited(vertex_web, dimension);
02386 elem_c_ida = 0;
02387 resultado = computar_caminho_de_ida (vertex_web, dimension, caminho_de_ida, elem_c_ida, caminho_principal, elem_caminho, num_min);
02388
02389 if(resultado == true){ sai=true; }
02390
02391
02392 resultado = false;
02393
02394 int prob_reg = 0;
02395 bool haprob = false;
02396
02397 if(!sai){
02398 while (!resultado){
02399
02400 clear_visited(vertex_web, dimension);
02401 elem_c_ida = 0;
02402 resultado = computar_caminho_de_ida (vertex_web, dimension, caminho_de_ida, elem_c_ida, caminho_principal, elem_caminho, num_max);
02403
02404
02405
02406 tentativa+=0.5;
02407
02408 if(!resultado) {
02409 num_min = num_max;
02410 num_max = tentativa*elem_caminho;
02411 prob_reg++;
02412 }
02413
02414
02415 if(prob_reg == 100){
02416 resultado = true;
02417 num_max = elem_caminho;
02418 haprob = true;
02419 }
02420
02421 }
02422
02423 num_arcos = (num_min + num_max)/2;
02424 if ( (num_min + num_max)%2 == 1 ){num_arcos++;}
02425
02426 tentativa = 0;
02427
02428 }
02429
02430 while(sai==false && haprob==false){
02431
02432 tentativa++;
02433
02434 clear_visited(vertex_web, dimension);
02435 elem_c_ida = 0;
02436 resultado = computar_caminho_de_ida (vertex_web, dimension, caminho_de_ida, elem_c_ida, caminho_principal, elem_caminho, num_arcos);
02437
02438
02439
02440
02441 if(resultado){
02442
02443 num_max = num_arcos;
02444
02445 if( num_max - 1 == num_min) {
02446 sai=true;
02447
02448 }else{
02449 num_arcos = (num_min + num_max)/2;
02450 if ( (num_min + num_max)%2 == 1 ){num_arcos++;}
02451 }
02452
02453 }else{
02454
02455 num_min = num_arcos;
02456
02457 if( num_max - 1 == num_min) {
02458 num_arcos++;
02459
02460 }else{
02461
02462 num_arcos = (num_min + num_max)/2;
02463 if ( (num_min + num_max)%2 == 1 ){num_arcos++;}
02464
02465 }
02466
02467 }
02468
02469 }
02470
02471
02472
02473
02474
02475
02476
02477
02478
02479
02480 }else{
02481
02482
02483 for (i=0; i<elem_caminho; i++){
02484 caminho_de_ida [i] = caminho_principal[i];
02485 }
02486 elem_c_ida = elem_caminho;
02487 }
02488
02489
02490
02491
02492 int elem_caminho_final = 2*elem_c_ida-1;
02493
02494
02495
02496 for(i=0; i<elem_c_ida; i++){
02497 caminho_final [i] = caminho_de_ida[i];
02498 }
02499
02500
02501
02502 if(!cycle){
02503
02504 for(i=elem_c_ida-2; i>=0; i--){
02505 caminho_final [2*(elem_c_ida-1) - i] = caminho_de_ida[i];
02506 }
02507
02508 }else{
02509 elem_caminho_final = elem_c_ida;
02510 }
02511
02512
02513 delete [] caminho_de_ida;
02514
02515
02516
02517
02518
02519
02520
02521
02522 i = computar_custo_caminho_final (vertex_web, caminho_final, elem_caminho_final);
02523
02524
02525
02526
02527
02528 clear_visited(vertex_web, dimension);
02529
02530 return elem_caminho_final;
02531
02532 }
02533
02534 void shift_cyclic_path (uint start_vertex, int *caminho_final, int elem_caminho_final){
02535
02536 uint posshift = 0;
02537 int i;
02538 int temp_table[elem_caminho_final];
02539
02540 for (i=0; i<elem_caminho_final; i++){
02541 if (caminho_final[i] == start_vertex){
02542 posshift = i;
02543 break;
02544 }
02545 }
02546
02547 uint aux;
02548 i=0;
02549
02550 for(aux=posshift; aux<elem_caminho_final-1; aux++){
02551 temp_table[i] = caminho_final[aux];
02552 i++;
02553 }
02554
02555 for(aux=0; aux<=posshift; aux++){
02556 temp_table[i]=caminho_final[aux];
02557 i++;
02558 }
02559
02560 for(i=0; i<elem_caminho_final;i++){
02561 caminho_final[i] = temp_table[i];
02562 }
02563
02564 }
02565
02566 uint get_MSP_dimension (char* msp_file) {
02567
02568 FILE *file;
02569 file = fopen (msp_file,"r");
02570 uint dimension;
02571
02572 if(file == NULL){
02573 ROS_INFO("Can not open filename %s", msp_file);
02574 ROS_BREAK();
02575 }else{
02576 ROS_INFO("MSP Route File Opened. Reading Dimensions.\n");
02577 fscanf (file, "%u", &dimension);
02578 }
02579 fclose(file);
02580 return dimension;
02581 }
02582
02583 void get_MSP_route (uint *route, uint dimension, char* msp_file) {
02584
02585 FILE *file;
02586 file = fopen (msp_file,"r");
02587
02588 if(file == NULL){
02589 ROS_INFO("Can not open filename %s", msp_file);
02590 ROS_BREAK();
02591 }else{
02592 ROS_INFO("MSP Route File Opened. Getting MSP Route.\n");
02593
02594 uint i;
02595 float temp;
02596
02597
02598
02599 fscanf (file, "%f", &temp);
02600
02601
02602 for (i=0;i<dimension;i++){
02603 fscanf (file, "%u", &route[i]);
02604 }
02605
02606 }
02607
02608
02609
02610 fclose(file);
02611 }