localization/amcl/map/map.h
1 /*
2  * Player - One Hell of a Robot Server
3  * Copyright (C) 2003
4  * Andrew Howard
5  * Brian Gerkey
6  *
7  * This program is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program; if not, write to the Free Software
19  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
20  *
21  */
22 
23 
24 /**************************************************************************
25  * Desc: Global map (grid-based)
26  * Author: Andrew Howard
27  * Date: 6 Feb 2003
28  * CVS: $Id: map.h 8466 2009-12-16 00:51:26Z gbiggs $
29  **************************************************************************/
30 
31 #ifndef MAP_H
32 #define MAP_H
33 
34 #if !defined (WIN32)
35  #include <stdint.h>
36 #endif
37 
38 #ifdef __cplusplus
39 extern "C" {
40 #endif
41 
42 // Forward declarations
43 struct _rtk_fig_t;
44 
45 
46 // Limits
47 #define MAP_WIFI_MAX_LEVELS 8
48 
49 
50 // Description for a single map cell.
51 typedef struct
52 {
53  // Occupancy state (-1 = free, 0 = unknown, +1 = occ)
54  int occ_state;
55 
56  // Distance to the nearest occupied cell
57  double occ_dist;
58 
59  // Wifi levels
60  int wifi_levels[MAP_WIFI_MAX_LEVELS];
61 
62 } map_cell_t;
63 
64 
65 // Description for a map
66 typedef struct
67 {
68  // Map origin; the map is a viewport onto a conceptual larger map.
69  double origin_x, origin_y;
70 
71  // Map scale (m/cell)
72  double scale;
73 
74  // Max occupancy distance value
75  double max_occ_dist;
76 
77  // Map dimensions (number of cells)
78  int size_x, size_y;
79 
80  // The map data, stored as a grid
81  map_cell_t *cells;
82 
83 } map_t;
84 
85 
86 
87 /**************************************************************************
88  * Basic map functions
89  **************************************************************************/
90 
91 // Create a new (empty) map
92 map_t *map_alloc(void);
93 
94 // Destroy a map
95 void map_free(map_t *map);
96 
97 // Get the cell at the given point
98 map_cell_t *map_get_cell(map_t *map, double ox, double oy, double oa);
99 
100 // Load an occupancy map
101 int map_load_occ(map_t *map, const char *filename, double scale, int negate);
102 
103 // Load a wifi signal strength map
104 int map_load_wifi(map_t *map, const char *filename, int index);
105 
106 // Update the cspace distances
107 void map_update_cspace(map_t *map, double max_occ_dist);
108 
109 
110 /**************************************************************************
111  * Range functions
112  **************************************************************************/
113 
114 // Extract a single range reading from the map
115 double map_calc_range(map_t *map, double ox, double oy, double oa, double max_range);
116 
117 
118 /**************************************************************************
119  * GUI/diagnostic functions
120  **************************************************************************/
121 
122 // Draw the occupancy grid
123 void map_draw_occ(map_t *map, struct _rtk_fig_t *fig);
124 
125 // Draw the cspace map
126 void map_draw_cspace(map_t *map, struct _rtk_fig_t *fig);
127 
128 // Draw a wifi map
129 void map_draw_wifi(map_t *map, struct _rtk_fig_t *fig, int index);
130 
131 
132 /**************************************************************************
133  * Map manipulation macros
134  **************************************************************************/
135 
136 // Convert from map index to world coords
137 #define MAP_WXGX(map, i) (map->origin_x + ((i) - map->size_x / 2) * map->scale)
138 #define MAP_WYGY(map, j) (map->origin_y + ((j) - map->size_y / 2) * map->scale)
139 
140 // Convert from world coords to map coords
141 #define MAP_GXWX(map, x) (floor((x - map->origin_x) / map->scale + 0.5) + map->size_x / 2)
142 #define MAP_GYWY(map, y) (floor((y - map->origin_y) / map->scale + 0.5) + map->size_y / 2)
143 
144 // Test to see if the given map coords lie within the absolute map bounds.
145 #define MAP_VALID(map, i, j) ((i >= 0) && (i < map->size_x) && (j >= 0) && (j < map->size_y))
146 
147 // Compute the cell index for the given map coords.
148 #define MAP_INDEX(map, i, j) ((i) + (j) * map->size_x)
149 
150 #ifdef __cplusplus
151 }
152 #endif
153 
154 #endif
Definition: localization/amcl/map/map.h:51
Definition: localization/amcl/map/map.h:66

Last updated 12 September 2005 21:38:45