getgraph.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2011, 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
00036 *********************************************************************/
00037 
00038 #include <stdio.h>
00039 #include <stdlib.h>
00040 #include <cmath>
00041 
00042 //File Line of the First Vertex ID to read (Protection) - fscanf() ignores blank lines
00043 #define FIRST_VID 5
00044 
00045 typedef unsigned int uint;
00046 
00047 typedef struct {
00048   uint id, num_neigh;
00049   float x, y;           //pass these attributes in meters
00050   uint id_neigh[8], cost[8];
00051   bool visited[8];
00052   char dir [8][3];      //table of 8 strings with 3 chars max ("N","NE","E","SE","S","SW","W","NW")
00053 }vertex;
00054 
00055 uint WIDTH_PX;
00056 uint HEIGHT_PX;
00057 float RESOLUTION;
00058 float WIDTH_M;
00059 float HEIGHT_M;
00060 
00061 uint GetGraphDimension (char* graph_file){
00062   
00063    FILE *file;
00064    file = fopen (graph_file,"r");
00065    uint dimension;
00066    
00067    if(file == NULL){
00068       ROS_INFO("Can not open filename %s", graph_file);
00069       ROS_BREAK();      
00070    }else{
00071       ROS_INFO("Graph File Opened. Reading Dimensions.\n");
00072       fscanf (file, "%u", &dimension);
00073       
00074       //Initialize other dimension variables:
00075       fscanf (file, "%u", &WIDTH_PX);
00076       fscanf (file, "%u", &HEIGHT_PX);
00077       fscanf (file, "%f", &RESOLUTION);
00078       WIDTH_M = (float) WIDTH_PX * RESOLUTION;
00079       HEIGHT_M = (float) HEIGHT_PX * RESOLUTION;
00080    }
00081    fclose(file);
00082    return dimension;
00083 }
00084 
00085 
00086 void GetGraphInfo (vertex *vertex_web, uint dimension, char* graph_file){
00087    
00088    FILE *file;
00089    file = fopen (graph_file,"r");
00090    
00091    if(file == NULL){
00092       ROS_INFO("Can not open filename %s", graph_file);
00093       ROS_BREAK();      
00094    }else{
00095       ROS_INFO("Graph File Opened. Getting Graph Info.\n");
00096       
00097       uint i,j;
00098       float temp;
00099       
00100       //Start Reading the File from FIRST_VID On:
00101       for (i=0; i<FIRST_VID-1; i++){
00102          fscanf (file, "%f", &temp);
00103       }      
00104 
00105       for (i=0;i<dimension;i++){
00106         
00107         fscanf (file, "%u", &vertex_web[i].id);
00108         
00109         fscanf (file, "%f", &vertex_web[i].x);
00110         vertex_web[i].x *= RESOLUTION; //convert to m   
00111         
00112         fscanf (file, "%f", &vertex_web[i].y);
00113         vertex_web[i].y *= RESOLUTION; //convert to m
00114         
00115         fscanf (file, "%u", &vertex_web[i].num_neigh);
00116         
00117         for (j=0;j<vertex_web[i].num_neigh; j++){
00118           fscanf (file, "%u", &vertex_web[i].id_neigh[j]);
00119           fscanf (file, "%s", &vertex_web[i].dir[j]);
00120           fscanf (file, "%u", &vertex_web[i].cost[j]);  //can eventually be converted to meters also...
00121         }
00122         
00123       }     
00124       
00125    }
00126         
00127     //printf ("[v=10], x = %f (meters)\n",vertex_web[10].x); 
00128 
00129    fclose(file);   
00130           
00131   }
00132   
00133 uint IdentifyVertex (vertex *vertex_web, uint size, double x, double y){
00134   
00135   uint i, v=0;
00136   double dif_x, dif_y, result=INFINITY;
00137   
00138   for (i=0; i<size; i++){
00139     dif_x = vertex_web[i].x - x;
00140     dif_y = vertex_web[i].y - y;
00141     
00142 //     printf("[%u] result = %f, (dif_x+dif_y) = %f\n",i,result, fabs(dif_x) + fabs(dif_y));
00143     if( result > fabs (dif_x) + fabs (dif_y) ){ //Identify the Vertex closer to the initial coordinates x & y
00144       result = fabs (dif_x) + fabs (dif_y);
00145       v = i;
00146     }
00147   }
00148   return v;  
00149 }
00150 
00151 //integer to array (itoa for linux c)
00152 char* itoa(int value, char* str, int radix) {
00153     static char dig[] =
00154         "0123456789"
00155         "abcdefghijklmnopqrstuvwxyz";
00156     int n = 0, neg = 0;
00157     unsigned int v;
00158     char* p, *q;
00159     char c;
00160 
00161     if (radix == 10 && value < 0) {
00162         value = -value;
00163         neg = 1;
00164     }
00165     v = value;
00166     do {
00167         str[n++] = dig[v%radix];
00168         v /= radix;
00169     } while (v);
00170     if (neg)
00171         str[n++] = '-';
00172     str[n] = '\0';
00173 
00174     for (p = str, q = p + (n-1); p < q; ++p, --q)
00175         c = *p, *p = *q, *q = c;
00176     return str;
00177 }


patrolling_sim
Author(s): David Portugal
autogenerated on Mon Jan 6 2014 11:26:29