APM:Libraries
TerrainUtil.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  handle disk IO for terrain code
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include <AP_Common/AP_Common.h>
21 #include <AP_Math/AP_Math.h>
23 #include <GCS_MAVLink/GCS.h>
24 #include "AP_Terrain.h"
25 
26 #if AP_TERRAIN_AVAILABLE
27 
28 #include <assert.h>
29 #include <stdio.h>
30 #if HAL_OS_POSIX_IO
31 #include <unistd.h>
32 #include <sys/stat.h>
33 #include <fcntl.h>
34 #endif
35 #include <sys/types.h>
36 #include <errno.h>
37 
38 extern const AP_HAL::HAL& hal;
39 
40 /*
41  calculate bit number in grid_block bitmap. This corresponds to a
42  bit representing a 4x4 mavlink transmitted block
43 */
44 uint8_t AP_Terrain::grid_bitnum(uint8_t idx_x, uint8_t idx_y)
45 {
46  ASSERT_RANGE(idx_x,0,27);
47  ASSERT_RANGE(idx_y,0,31);
48  uint8_t subgrid_x = idx_x / TERRAIN_GRID_MAVLINK_SIZE;
49  uint8_t subgrid_y = idx_y / TERRAIN_GRID_MAVLINK_SIZE;
50  ASSERT_RANGE(subgrid_x,0,TERRAIN_GRID_BLOCK_MUL_X-1);
51  ASSERT_RANGE(subgrid_y,0,TERRAIN_GRID_BLOCK_MUL_Y-1);
52  return subgrid_y + TERRAIN_GRID_BLOCK_MUL_Y*subgrid_x;
53 }
54 
55 /*
56  given a grid_info check that a given idx_x/idx_y is available (set
57  in the bitmap)
58  */
59 bool AP_Terrain::check_bitmap(const struct grid_block &grid, uint8_t idx_x, uint8_t idx_y)
60 {
61  uint8_t bitnum = grid_bitnum(idx_x, idx_y);
62  return (grid.bitmap & (((uint64_t)1U)<<bitnum)) != 0;
63 }
64 
65 /*
66  given a location, calculate the 32x28 grid SW corner, plus the
67  grid indices
68 */
69 void AP_Terrain::calculate_grid_info(const Location &loc, struct grid_info &info) const
70 {
71  // grids start on integer degrees. This makes storing terrain data
72  // on the SD card a bit easier
73  info.lat_degrees = (loc.lat<0?(loc.lat-9999999L):loc.lat) / (10*1000*1000L);
74  info.lon_degrees = (loc.lng<0?(loc.lng-9999999L):loc.lng) / (10*1000*1000L);
75 
76  // create reference position for this rounded degree position
77  Location ref;
78  ref.lat = info.lat_degrees*10*1000*1000L;
79  ref.lng = info.lon_degrees*10*1000*1000L;
80 
81  // find offset from reference
82  Vector2f offset = location_diff(ref, loc);
83 
84  // get indices in terms of grid_spacing elements
85  uint32_t idx_x = offset.x / grid_spacing;
86  uint32_t idx_y = offset.y / grid_spacing;
87 
88  // find indexes into 32*28 grids for this degree reference. Note
89  // the use of TERRAIN_GRID_BLOCK_SPACING_{X,Y} which gives a one square
90  // overlap between grids
91  info.grid_idx_x = idx_x / TERRAIN_GRID_BLOCK_SPACING_X;
92  info.grid_idx_y = idx_y / TERRAIN_GRID_BLOCK_SPACING_Y;
93 
94  // find the indices within the 32*28 grid
95  info.idx_x = idx_x % TERRAIN_GRID_BLOCK_SPACING_X;
96  info.idx_y = idx_y % TERRAIN_GRID_BLOCK_SPACING_Y;
97 
98  // find the fraction (0..1) within the square
99  info.frac_x = (offset.x - idx_x * grid_spacing) / grid_spacing;
100  info.frac_y = (offset.y - idx_y * grid_spacing) / grid_spacing;
101 
102  // calculate lat/lon of SW corner of 32*28 grid_block
103  location_offset(ref,
104  info.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * (float)grid_spacing,
105  info.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * (float)grid_spacing);
106  info.grid_lat = ref.lat;
107  info.grid_lon = ref.lng;
108 
109  ASSERT_RANGE(info.idx_x,0,TERRAIN_GRID_BLOCK_SPACING_X-1);
110  ASSERT_RANGE(info.idx_y,0,TERRAIN_GRID_BLOCK_SPACING_Y-1);
111  ASSERT_RANGE(info.frac_x,0,1);
112  ASSERT_RANGE(info.frac_y,0,1);
113 }
114 
115 
116 /*
117  find a grid structure given a grid_info
118  */
119 AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info)
120 {
121  uint16_t oldest_i = 0;
122 
123  // see if we have that grid
124  for (uint16_t i=0; i<cache_size; i++) {
125  if (cache[i].grid.lat == info.grid_lat &&
126  cache[i].grid.lon == info.grid_lon &&
127  cache[i].grid.spacing == grid_spacing) {
128  cache[i].last_access_ms = AP_HAL::millis();
129  return cache[i];
130  }
131  if (cache[i].last_access_ms < cache[oldest_i].last_access_ms) {
132  oldest_i = i;
133  }
134  }
135 
136  // Not found. Use the oldest grid and make it this grid,
137  // initially unpopulated
138  struct grid_cache &grid = cache[oldest_i];
139  memset(&grid, 0, sizeof(grid));
140 
141  grid.grid.lat = info.grid_lat;
142  grid.grid.lon = info.grid_lon;
143  grid.grid.spacing = grid_spacing;
144  grid.grid.grid_idx_x = info.grid_idx_x;
145  grid.grid.grid_idx_y = info.grid_idx_y;
146  grid.grid.lat_degrees = info.lat_degrees;
147  grid.grid.lon_degrees = info.lon_degrees;
148  grid.grid.version = TERRAIN_GRID_FORMAT_VERSION;
149  grid.last_access_ms = AP_HAL::millis();
150 
151  // mark as waiting for disk read
152  grid.state = GRID_CACHE_DISKWAIT;
153 
154  return grid;
155 }
156 
157 /*
158  find cache index of disk_block
159  */
160 int16_t AP_Terrain::find_io_idx(enum GridCacheState state)
161 {
162  // try first with given state
163  for (uint16_t i=0; i<cache_size; i++) {
164  if (disk_block.block.lat == cache[i].grid.lat &&
165  disk_block.block.lon == cache[i].grid.lon &&
166  cache[i].state == state) {
167  return i;
168  }
169  }
170  // then any state
171  for (uint16_t i=0; i<cache_size; i++) {
172  if (disk_block.block.lat == cache[i].grid.lat &&
173  disk_block.block.lon == cache[i].grid.lon) {
174  return i;
175  }
176  }
177  return -1;
178 }
179 
180 /*
181  get CRC for a block
182  */
183 uint16_t AP_Terrain::get_block_crc(struct grid_block &block)
184 {
185  uint16_t saved_crc = block.crc;
186  block.crc = 0;
187  uint16_t ret = crc16_ccitt((const uint8_t *)&block, sizeof(block), 0);
188  block.crc = saved_crc;
189  return ret;
190 }
191 
192 #endif // AP_TERRAIN_AVAILABLE
Interface definition for the various Ground Control System.
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
T y
Definition: vector2.h:37
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
Common definitions and utility routines for the ArduPilot libraries.
T x
Definition: vector2.h:37
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
Definition: edc.cpp:52