#include <ctime>
#include <climits>
#include <cmath>
#include <ros/ros.h>
#include "getgraph.h"
#include "algorithms.h"
Go to the source code of this file.
Functions | |
bool | caminho_apartir_vizinhos_unicos (vertex *vertex_web, int dimension, int *caminho_principal, int &elem_max, int &custo_max, int seed) |
bool | check_visited (vertex *vertex_web, int dimension) |
void | clear_visited (vertex *vertex_web, uint dimension) |
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) |
int | computar_custo_caminho_final (vertex *vertex_web, int *caminho_final, int elem_caminho_final) |
uint | conscientious_reactive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness) |
int | count_intention (uint vertex, int *tab_intention, int nr_robots) |
int | count_intention_cbls (uint vertex, int *tab_intention, int nr_robots, int id_robot) |
void | create_source_and_dest_tables (vertex *vertex_web, uint *source, uint *destination, uint dimension) |
int | cyclic (uint dimension, vertex *vertex_web, int *caminho_final) |
int | devolve_viz_unicos (vertex *vertex_web, int vertice) |
int | devolve_vizinhos_nao_visitados (vertex *vertex_web, int dimension, int vertice) |
void | dijkstra (uint source, uint destination, int *shortest_path, uint &elem_s_path, vertex *vertex_web, uint dimension) |
void | dijkstra_mcost (uint source, uint destination, int *shortest_path, uint &elem_s_path, vertex *vertex_web, double new_costs[][8], uint dimension) |
double | get_edge_cost_between (vertex *vertex_web, uint vertex_A, uint vertex_B) |
int | get_hist_idx (uint *source, uint *destination, uint source_vertex, uint dest_vertex, uint hist_dimension) |
int | get_hist_idx_from_edge_cost (double *hist_sort, uint size, double edge_cost) |
void | get_hist_sort (vertex *vertex_web, double *hist_sort, uint dimension) |
int | get_max (uint *tab, uint tam_tab) |
double | get_max_dbl (double *tab, uint tam_tab) |
int | get_min (uint *tab, uint tam_tab) |
double | get_min_dbl (double *tab, uint tam_tab) |
uint | get_MSP_dimension (const char *msp_file) |
void | get_MSP_route (uint *route, uint dimension, const char *msp_file) |
uint | greedy_bayesian_strategy (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, double G1, double G2, double edge_min) |
uint | heuristic_conscientious_reactive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness) |
uint | heuristic_pathfinder_conscientious_cognitive (uint current_vertex, vertex *vertex_web, double *instantaneous_idleness, uint dimension, uint *path) |
int | is_neigh (uint vertex1, uint vertex2, vertex *vertex_web, uint dimension) |
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) |
void | load_real_histogram (double *real_histogram, uint size_hist, char *filename) |
long double | log2 (const long double x) |
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) |
void | normalize_histogram (double *real_histogram, double *histogram, uint size_hist) |
bool | pertence (int elemento, int *tab, int tam_tab) |
int | pertence_idx (int elemento, int *tab, int tam_tab) |
int | pertence_uint_idx (uint elemento, uint *tab, uint tam_tab) |
bool | procurar_ciclo (vertex *vertex_web, uint dimension, int *caminho_principal, int &elem_caminho, int &custo_max, int seed) |
uint | random (uint current_vertex, vertex *vertex_web) |
void | shift_cyclic_path (uint start_vertex, int *caminho_final, int elem_caminho_final) |
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) |
bool | UHC (vertex *vertex_web, int v1, int *caminho_principal, uint dimension) |
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) |
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) |
void | update_likelihood_old (reinforcement_learning RL, double *real_histogram, double *hist_sort, uint size_hist, vertex *vertex_web) |
bool | verificar_arco_cp (int no_1, int no_2, int *caminho_principal, int elem_cp) |
void | write_histogram_to_file (vertex *vertex_web, double *real_histogram, double *histogram, uint *source, uint *destination, uint hist_dimension, uint number, uint robotid) |
void | write_reward_evolution (double reward, uint robotid) |
Variables | |
uint | reward_count = 0 |
bool caminho_apartir_vizinhos_unicos | ( | vertex * | vertex_web, |
int | dimension, | ||
int * | caminho_principal, | ||
int & | elem_max, | ||
int & | custo_max, | ||
int | seed | ||
) |
Definition at line 1638 of file algorithms.cpp.
bool check_visited | ( | vertex * | vertex_web, |
int | dimension | ||
) |
Definition at line 1736 of file algorithms.cpp.
void clear_visited | ( | vertex * | vertex_web, |
uint | dimension | ||
) |
Definition at line 929 of file algorithms.cpp.
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 | ||
) |
Definition at line 1778 of file algorithms.cpp.
int computar_custo_caminho_final | ( | vertex * | vertex_web, |
int * | caminho_final, | ||
int | elem_caminho_final | ||
) |
Definition at line 2248 of file algorithms.cpp.
uint conscientious_reactive | ( | uint | current_vertex, |
vertex * | vertex_web, | ||
double * | instantaneous_idleness | ||
) |
Definition at line 72 of file algorithms.cpp.
int count_intention | ( | uint | vertex, |
int * | tab_intention, | ||
int | nr_robots | ||
) |
Definition at line 301 of file algorithms.cpp.
int count_intention_cbls | ( | uint | vertex, |
int * | tab_intention, | ||
int | nr_robots, | ||
int | id_robot | ||
) |
Definition at line 313 of file algorithms.cpp.
void create_source_and_dest_tables | ( | vertex * | vertex_web, |
uint * | source, | ||
uint * | destination, | ||
uint | dimension | ||
) |
Definition at line 2643 of file algorithms.cpp.
Definition at line 2274 of file algorithms.cpp.
int devolve_viz_unicos | ( | vertex * | vertex_web, |
int | vertice | ||
) |
Definition at line 1310 of file algorithms.cpp.
int devolve_vizinhos_nao_visitados | ( | vertex * | vertex_web, |
int | dimension, | ||
int | vertice | ||
) |
Definition at line 1757 of file algorithms.cpp.
void dijkstra | ( | uint | source, |
uint | destination, | ||
int * | shortest_path, | ||
uint & | elem_s_path, | ||
vertex * | vertex_web, | ||
uint | dimension | ||
) |
Definition at line 415 of file algorithms.cpp.
void dijkstra_mcost | ( | uint | source, |
uint | destination, | ||
int * | shortest_path, | ||
uint & | elem_s_path, | ||
vertex * | vertex_web, | ||
double | new_costs[][8], | ||
uint | dimension | ||
) |
Definition at line 535 of file algorithms.cpp.
double get_edge_cost_between | ( | vertex * | vertex_web, |
uint | vertex_A, | ||
uint | vertex_B | ||
) |
Definition at line 2703 of file algorithms.cpp.
int get_hist_idx | ( | uint * | source, |
uint * | destination, | ||
uint | source_vertex, | ||
uint | dest_vertex, | ||
uint | hist_dimension | ||
) |
Definition at line 2691 of file algorithms.cpp.
int get_hist_idx_from_edge_cost | ( | double * | hist_sort, |
uint | size, | ||
double | edge_cost | ||
) |
Definition at line 2677 of file algorithms.cpp.
void get_hist_sort | ( | vertex * | vertex_web, |
double * | hist_sort, | ||
uint | dimension | ||
) |
Definition at line 2658 of file algorithms.cpp.
Definition at line 2799 of file algorithms.cpp.
double get_max_dbl | ( | double * | tab, |
uint | tam_tab | ||
) |
Definition at line 2812 of file algorithms.cpp.
Definition at line 2773 of file algorithms.cpp.
double get_min_dbl | ( | double * | tab, |
uint | tam_tab | ||
) |
Definition at line 2786 of file algorithms.cpp.
uint get_MSP_dimension | ( | const char * | msp_file | ) |
Definition at line 2596 of file algorithms.cpp.
void get_MSP_route | ( | uint * | route, |
uint | dimension, | ||
const char * | msp_file | ||
) |
Definition at line 2613 of file algorithms.cpp.
uint greedy_bayesian_strategy | ( | uint | current_vertex, |
vertex * | vertex_web, | ||
double * | instantaneous_idleness, | ||
double | G1, | ||
double | G2, | ||
double | edge_min | ||
) |
Definition at line 226 of file algorithms.cpp.
uint heuristic_conscientious_reactive | ( | uint | current_vertex, |
vertex * | vertex_web, | ||
double * | instantaneous_idleness | ||
) |
Definition at line 124 of file algorithms.cpp.
uint heuristic_pathfinder_conscientious_cognitive | ( | uint | current_vertex, |
vertex * | vertex_web, | ||
double * | instantaneous_idleness, | ||
uint | dimension, | ||
uint * | path | ||
) |
Definition at line 642 of file algorithms.cpp.
Definition at line 522 of file algorithms.cpp.
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 | ||
) |
IMMEDIATE LOCAL NORMALIZED PRIOR - BEFORE
LOCAL LOOKAHEAD PRIOR
IMMEDIATE LOCAL NORMALIZED PRIOR - BEFORE
LOCAL LOOKAHEAD PRIOR
CALCULATE DECISION ENTROPY
NORMALIZE ENTROPY ACCORDING TO NR# DECISIONS
Definition at line 3445 of file algorithms.cpp.
void load_real_histogram | ( | double * | real_histogram, |
uint | size_hist, | ||
char * | filename | ||
) |
Definition at line 2716 of file algorithms.cpp.
long double log2 | ( | const long double | x | ) | [inline] |
Definition at line 53 of file algorithms.cpp.
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 | ||
) |
Definition at line 1321 of file algorithms.cpp.
void normalize_histogram | ( | double * | real_histogram, |
double * | histogram, | ||
uint | size_hist | ||
) |
Definition at line 2745 of file algorithms.cpp.
bool pertence | ( | int | elemento, |
int * | tab, | ||
int | tam_tab | ||
) |
Definition at line 832 of file algorithms.cpp.
int pertence_idx | ( | int | elemento, |
int * | tab, | ||
int | tam_tab | ||
) |
Definition at line 845 of file algorithms.cpp.
int pertence_uint_idx | ( | uint | elemento, |
uint * | tab, | ||
uint | tam_tab | ||
) |
Definition at line 2760 of file algorithms.cpp.
bool procurar_ciclo | ( | vertex * | vertex_web, |
uint | dimension, | ||
int * | caminho_principal, | ||
int & | elem_caminho, | ||
int & | custo_max, | ||
int | seed | ||
) |
Definition at line 942 of file algorithms.cpp.
Definition at line 58 of file algorithms.cpp.
void shift_cyclic_path | ( | uint | start_vertex, |
int * | caminho_final, | ||
int | elem_caminho_final | ||
) |
Definition at line 2564 of file algorithms.cpp.
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 | ||
) |
Definition at line 325 of file algorithms.cpp.
Definition at line 858 of file algorithms.cpp.
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 | ||
) |
node counts normalizados pelo vertex degree*2 (se deg>1)
reward se for a menor node_cont (não normalizado) do grafo global
Dimension this as a parameter (alfa) in the reward funcion
alfa = 100
1- CALCULAR A NOVA Idleness BASEADA NO INSTANTE DE TEMPO ***
2- Quanto mais baixa a entropia, maior o reward ou punishment
ALTERADO PARA SER EDGE DIRIGIDA: Faz mais sentido...
Definition at line 2977 of file algorithms.cpp.
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 | ||
) |
AQUI POSSO PENALIZAR BASTANTE = NÓ QUE ACABEI DE VISITAR E NAO QUERO CA VOLTAR
reward se for a menor node_cont (não normalizado) do grafo global
Definition at line 3206 of file algorithms.cpp.
void update_likelihood_old | ( | reinforcement_learning | RL, |
double * | real_histogram, | ||
double * | hist_sort, | ||
uint | size_hist, | ||
vertex * | vertex_web | ||
) |
1- CALCULAR A NOVA Idleness BASEADA NO INSTANTE DE TEMPO ***
2- Quanto mais baixa a entropia, maior o reward ou punishment
Definition at line 2872 of file algorithms.cpp.
bool verificar_arco_cp | ( | int | no_1, |
int | no_2, | ||
int * | caminho_principal, | ||
int | elem_cp | ||
) |
Definition at line 1710 of file algorithms.cpp.
void write_histogram_to_file | ( | vertex * | vertex_web, |
double * | real_histogram, | ||
double * | histogram, | ||
uint * | source, | ||
uint * | destination, | ||
uint | hist_dimension, | ||
uint | number, | ||
uint | robotid | ||
) |
Definition at line 2825 of file algorithms.cpp.
void write_reward_evolution | ( | double | reward, |
uint | robotid | ||
) |
Definition at line 2853 of file algorithms.cpp.
uint reward_count = 0 |
Definition at line 47 of file algorithms.cpp.