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 typedef struct {
00055 uint current_vertex, next_vertex;
00056 double time_then;
00057 uint num_possible_neighs;
00058 uint id_neighbors [8];
00059 double idleness_old[8];
00060 uint node_count [8];
00061 double entropy;
00062
00063 }reinforcement_learning;
00064
00065
00066 inline long double log2(const long double x);
00067
00068 uint random (uint current_vertex, vertex *vertex_web);
00069
00070 uint conscientious_reactive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness);
00071
00072 uint heuristic_conscientious_reactive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness);
00073
00074 uint greedy_bayesian_strategy (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, double G1, double G2, double edge_min);
00075
00076 int count_intention (uint vertex, int *tab_intention, int nr_robots);
00077
00078 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);
00079
00080 void dijkstra( uint source, uint destination, int *shortest_path, uint &elem_s_path, vertex *vertex_web, uint dimension);
00081
00082 int is_neigh(uint vertex1, uint vertex2, vertex *vertex_web, uint dimension);
00083
00084 void dijkstra_mcost( uint source, uint destination, int *shortest_path, uint &elem_s_path, vertex *vertex_web, double new_costs[][8], uint dimension);
00085
00086 uint heuristic_pathfinder_conscientious_cognitive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, uint dimension, uint *path);
00087
00088
00089 bool pertence (int elemento, int *tab, int tam_tab);
00090
00091 int pertence_idx (int elemento, int *tab, int tam_tab);
00092
00093 bool UHC (vertex *vertex_web, int v1, int *caminho_principal, uint dimension);
00094
00095 void clear_visited (vertex *vertex_web, uint dimension);
00096
00097 bool procurar_ciclo (vertex *vertex_web, uint dimension, int *caminho_principal, int &elem_caminho, int &custo_max, int seed);
00098
00099 int devolve_viz_unicos (vertex *vertex_web, int vertice);
00100
00101 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);
00102
00103 bool caminho_apartir_vizinhos_unicos (vertex *vertex_web, int dimension, int *caminho_principal, int &elem_max, int &custo_max, int seed);
00104
00105 bool verificar_arco_cp (int no_1, int no_2, int *caminho_principal, int elem_cp);
00106
00107 bool check_visited (vertex *vertex_web, int dimension);
00108
00109 int devolve_vizinhos_nao_visitados (vertex *vertex_web, int dimension, int vertice);
00110
00111 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);
00112
00113 int computar_custo_caminho_final (vertex *vertex_web, int *caminho_final, int elem_caminho_final);
00114
00115 int cyclic (uint dimension, vertex *vertex_web, int *caminho_final);
00116
00117 void shift_cyclic_path (uint start_vertex, int *caminho_final, int elem_caminho_final);
00118
00119 uint get_MSP_dimension (const char* msp_file);
00120
00121 void get_MSP_route (uint *route, uint dimension, const char* msp_file);
00122
00123 void create_source_and_dest_tables(vertex *vertex_web, uint *source, uint *destination, uint dimension);
00124
00125 void get_hist_sort(vertex *vertex_web, double *hist_sort, uint dimension);
00126
00127 int get_hist_idx_from_edge_cost (double *hist_sort, uint size, double edge_cost);
00128
00129 int get_hist_idx (uint *source, uint *destination, uint source_vertex, uint dest_vertex, uint hist_dimension);
00130
00131 double get_edge_cost_between (vertex *vertex_web, uint vertex_A, uint vertex_B);
00132
00133 void load_real_histogram(double *real_histogram, uint size_hist, char* filename);
00134
00135 void normalize_histogram(double *real_histogram, double *histogram, uint size_hist);
00136
00137 int pertence_uint_idx (uint elemento, uint *tab, uint tam_tab);
00138
00139 int get_min(uint *tab, uint tam_tab);
00140
00141 double get_min_dbl(double *tab, uint tam_tab);
00142
00143 int get_max(uint *tab, uint tam_tab);
00144
00145 double get_max_dbl(double *tab, uint tam_tab);
00146
00147 void write_histogram_to_file (vertex *vertex_web, double *real_histogram, double *histogram, uint *source, uint *destination, uint hist_dimension, uint number, uint robotid);
00148
00149 void write_reward_evolution(double reward, uint robotid);
00150
00151 void update_likelihood_old (reinforcement_learning RL, double *real_histogram, double *hist_sort, uint size_hist, vertex *vertex_web);
00152
00153 void update_likelihood (reinforcement_learning RL, double *real_histogram, uint *source, uint *destination, uint hist_dimension, vertex *vertex_web, int minimum_global_node_count, uint robotid);
00154
00155 void update_likelihood_new (reinforcement_learning RL, uint *node_count_table, double *inst_idleness, uint dimension, double *real_histogram, uint *source, uint *destination, uint hist_dimension, vertex *vertex_web, uint robotid);
00156
00157 int learning_algorithm(uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, double *avg_idleness, int *tab_intention, double *histogram, uint *source, uint *destination, uint hist_dimension, int nr_robots, int id_robot, uint *node_count, reinforcement_learning &RL);
00158
00159
00160