26 #if AP_TERRAIN_AVAILABLE 35 #include <sys/types.h> 44 uint8_t AP_Terrain::grid_bitnum(uint8_t idx_x, uint8_t idx_y)
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;
59 bool AP_Terrain::check_bitmap(
const struct grid_block &grid, uint8_t idx_x, uint8_t idx_y)
61 uint8_t bitnum = grid_bitnum(idx_x, idx_y);
62 return (grid.bitmap & (((uint64_t)1U)<<bitnum)) != 0;
69 void AP_Terrain::calculate_grid_info(
const Location &loc,
struct grid_info &info)
const 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);
78 ref.
lat = info.lat_degrees*10*1000*1000L;
79 ref.
lng = info.lon_degrees*10*1000*1000L;
85 uint32_t idx_x = offset.
x / grid_spacing;
86 uint32_t idx_y = offset.
y / grid_spacing;
91 info.grid_idx_x = idx_x / TERRAIN_GRID_BLOCK_SPACING_X;
92 info.grid_idx_y = idx_y / TERRAIN_GRID_BLOCK_SPACING_Y;
95 info.idx_x = idx_x % TERRAIN_GRID_BLOCK_SPACING_X;
96 info.idx_y = idx_y % TERRAIN_GRID_BLOCK_SPACING_Y;
99 info.frac_x = (offset.
x - idx_x * grid_spacing) / grid_spacing;
100 info.frac_y = (offset.
y - idx_y * grid_spacing) / grid_spacing;
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;
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);
119 AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(
const struct grid_info &info)
121 uint16_t oldest_i = 0;
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) {
131 if (cache[i].last_access_ms < cache[oldest_i].last_access_ms) {
138 struct grid_cache &grid = cache[oldest_i];
139 memset(&grid, 0,
sizeof(grid));
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;
152 grid.state = GRID_CACHE_DISKWAIT;
160 int16_t AP_Terrain::find_io_idx(
enum GridCacheState
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) {
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) {
183 uint16_t AP_Terrain::get_block_crc(
struct grid_block &block)
185 uint16_t saved_crc = block.crc;
187 uint16_t ret =
crc16_ccitt((
const uint8_t *)&block,
sizeof(block), 0);
188 block.crc = saved_crc;
192 #endif // AP_TERRAIN_AVAILABLE
Interface definition for the various Ground Control System.
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
int32_t lat
param 3 - Latitude * 10**7
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)