map.h
Go to the documentation of this file.
00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000  Brian Gerkey   &  Kasper Stoy
00004  *                      gerkey@usc.edu    kaspers@robotics.usc.edu
00005  *
00006  *  This library is free software; you can redistribute it and/or
00007  *  modify it under the terms of the GNU Lesser General Public
00008  *  License as published by the Free Software Foundation; either
00009  *  version 2.1 of the License, or (at your option) any later version.
00010  *
00011  *  This library is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00014  *  Lesser General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU Lesser General Public
00017  *  License along with this library; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /**************************************************************************
00022  * Desc: Global map (grid-based)
00023  * Author: Andrew Howard
00024  * Date: 6 Feb 2003
00025  * CVS: $Id: map.h 1713 2003-08-23 04:03:43Z inspectorg $
00026  **************************************************************************/
00027 
00028 #ifndef MAP_H
00029 #define MAP_H
00030 
00031 #include <stdint.h>
00032 
00033 #ifdef __cplusplus
00034 extern "C" {
00035 #endif
00036 
00037 // Forward declarations
00038 struct _rtk_fig_t;
00039 
00040   
00041 // Limits
00042 #define MAP_WIFI_MAX_LEVELS 8
00043 
00044   
00045 // Description for a single map cell.
00046 typedef struct
00047 {
00048   // Occupancy state (-1 = free, 0 = unknown, +1 = occ)
00049   int occ_state;
00050 
00051   // Distance to the nearest occupied cell
00052   double occ_dist;
00053 
00054   // Wifi levels
00055   //int wifi_levels[MAP_WIFI_MAX_LEVELS];
00056 
00057 } map_cell_t;
00058 
00059 
00060 // Description for a map
00061 typedef struct
00062 {
00063   // Map origin; the map is a viewport onto a conceptual larger map.
00064   double origin_x, origin_y;
00065   
00066   // Map scale (m/cell)
00067   double scale;
00068 
00069   // Map dimensions (number of cells)
00070   int size_x, size_y;
00071   
00072   // The map data, stored as a grid
00073   map_cell_t *cells;
00074 
00075   // Max distance at which we care about obstacles, for constructing
00076   // likelihood field
00077   double max_occ_dist;
00078   
00079 } map_t;
00080 
00081 
00082 
00083 /**************************************************************************
00084  * Basic map functions
00085  **************************************************************************/
00086 
00087 // Create a new (empty) map
00088 map_t *map_alloc(void);
00089 
00090 // Destroy a map
00091 void map_free(map_t *map);
00092 
00093 // Get the cell at the given point
00094 map_cell_t *map_get_cell(map_t *map, double ox, double oy, double oa);
00095 
00096 // Load an occupancy map
00097 int map_load_occ(map_t *map, const char *filename, double scale, int negate);
00098 
00099 // Load a wifi signal strength map
00100 //int map_load_wifi(map_t *map, const char *filename, int index);
00101 
00102 // Update the cspace distances
00103 void map_update_cspace(map_t *map, double max_occ_dist);
00104 
00105 
00106 /**************************************************************************
00107  * Range functions
00108  **************************************************************************/
00109 
00110 // Extract a single range reading from the map
00111 double map_calc_range(map_t *map, double ox, double oy, double oa, double max_range);
00112 
00113 
00114 /**************************************************************************
00115  * GUI/diagnostic functions
00116  **************************************************************************/
00117 
00118 // Draw the occupancy grid
00119 void map_draw_occ(map_t *map, struct _rtk_fig_t *fig);
00120 
00121 // Draw the cspace map
00122 void map_draw_cspace(map_t *map, struct _rtk_fig_t *fig);
00123 
00124 // Draw a wifi map
00125 void map_draw_wifi(map_t *map, struct _rtk_fig_t *fig, int index);
00126 
00127 
00128 /**************************************************************************
00129  * Map manipulation macros
00130  **************************************************************************/
00131 
00132 // Convert from map index to world coords
00133 #define MAP_WXGX(map, i) (map->origin_x + ((i) - map->size_x / 2) * map->scale)
00134 #define MAP_WYGY(map, j) (map->origin_y + ((j) - map->size_y / 2) * map->scale)
00135 
00136 // Convert from world coords to map coords
00137 #define MAP_GXWX(map, x) (floor((x - map->origin_x) / map->scale + 0.5) + map->size_x / 2)
00138 #define MAP_GYWY(map, y) (floor((y - map->origin_y) / map->scale + 0.5) + map->size_y / 2)
00139 
00140 // Test to see if the given map coords lie within the absolute map bounds.
00141 #define MAP_VALID(map, i, j) ((i >= 0) && (i < map->size_x) && (j >= 0) && (j < map->size_y))
00142 
00143 // Compute the cell index for the given map coords.
00144 #define MAP_INDEX(map, i, j) ((i) + (j) * map->size_x)
00145 
00146 #ifdef __cplusplus
00147 }
00148 #endif
00149 
00150 #endif


amcl
Author(s): Brian P. Gerkey
autogenerated on Mon Oct 6 2014 02:49:04