APM:Libraries
TerrainIO.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 #include <errno.h>
35 #endif
36 #include <sys/types.h>
37 
38 extern const AP_HAL::HAL& hal;
39 
40 /*
41  check for blocks that need to be read from disk
42  */
43 void AP_Terrain::check_disk_read(void)
44 {
45  for (uint16_t i=0; i<cache_size; i++) {
46  if (cache[i].state == GRID_CACHE_DISKWAIT) {
47  disk_block.block = cache[i].grid;
48  disk_io_state = DiskIoWaitRead;
49  return;
50  }
51  }
52 }
53 
54 /*
55  check for blocks that need to be written to disk
56  */
57 void AP_Terrain::check_disk_write(void)
58 {
59  for (uint16_t i=0; i<cache_size; i++) {
60  if (cache[i].state == GRID_CACHE_DIRTY) {
61  disk_block.block = cache[i].grid;
62  disk_io_state = DiskIoWaitWrite;
63  return;
64  }
65  }
66 }
67 
68 /*
69  Check if we need to do disk IO for grids.
70  */
71 void AP_Terrain::schedule_disk_io(void)
72 {
73  if (enable == 0 || !allocate()) {
74  return;
75  }
76 
77  if (!timer_setup) {
78  timer_setup = true;
79  hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Terrain::io_timer, void));
80  }
81 
82  switch (disk_io_state) {
83  case DiskIoIdle:
84  // look for a block that needs reading or writing
85  check_disk_read();
86  if (disk_io_state == DiskIoIdle) {
87  // still idle, check for writes
88  check_disk_write();
89  }
90  break;
91 
92  case DiskIoDoneRead: {
93  // a read has completed
94  int16_t cache_idx = find_io_idx(GRID_CACHE_DISKWAIT);
95  if (cache_idx != -1) {
96  if (disk_block.block.bitmap != 0) {
97  // when bitmap is zero we read an empty block
98  cache[cache_idx].grid = disk_block.block;
99  }
100  cache[cache_idx].state = GRID_CACHE_VALID;
101  cache[cache_idx].last_access_ms = AP_HAL::millis();
102  }
103  disk_io_state = DiskIoIdle;
104  break;
105  }
106 
107  case DiskIoDoneWrite: {
108  // a write has completed
109  int16_t cache_idx = find_io_idx(GRID_CACHE_DIRTY);
110  if (cache_idx != -1) {
111  if (cache[cache_idx].grid.bitmap == disk_block.block.bitmap) {
112  // only mark valid if more grids haven't been added
113  cache[cache_idx].state = GRID_CACHE_VALID;
114  }
115  }
116  disk_io_state = DiskIoIdle;
117  break;
118  }
119 
120  case DiskIoWaitWrite:
121  case DiskIoWaitRead:
122  // waiting for io_timer()
123  break;
124  }
125 }
126 
127 
128 /********************************************************
129 All the functions below this point run in the IO timer context, which
130 is a separate thread. The code uses the state machine controlled by
131 disk_io_state to manage who has access to the structures and to
132 prevent race conditions.
133 
134 The IO timer context owns the data when disk_io_state is
135 DiskIoWaitWrite or DiskIoWaitRead. The main thread owns the data when
136 disk_io_state is DiskIoIdle, DiskIoDoneWrite or DiskIoDoneRead
137 
138 All file operations are done by the IO thread.
139 *********************************************************/
140 
141 
142 /*
143  open the current degree file
144  */
145 void AP_Terrain::open_file(void)
146 {
147  struct grid_block &block = disk_block.block;
148  if (fd != -1 &&
149  block.lat_degrees == file_lat_degrees &&
150  block.lon_degrees == file_lon_degrees) {
151  // already open on right file
152  return;
153  }
154  if (file_path == nullptr) {
155  const char* terrain_dir = hal.util->get_custom_terrain_directory();
156  if (terrain_dir == nullptr) {
157  terrain_dir = HAL_BOARD_TERRAIN_DIRECTORY;
158  }
159  if (asprintf(&file_path, "%s/NxxExxx.DAT", terrain_dir) <= 0) {
160  io_failure = true;
161  file_path = nullptr;
162  return;
163  }
164  }
165  if (file_path == nullptr) {
166  io_failure = true;
167  return;
168  }
169  char *p = &file_path[strlen(file_path)-12];
170  if (*p != '/') {
171  io_failure = true;
172  return;
173  }
174  snprintf(p, 13, "/%c%02u%c%03u.DAT",
175  block.lat_degrees<0?'S':'N',
176  (unsigned)MIN(abs((int32_t)block.lat_degrees), 99),
177  block.lon_degrees<0?'W':'E',
178  (unsigned)MIN(abs((int32_t)block.lon_degrees), 999));
179 
180  // create directory if need be
181  if (!directory_created) {
182  *p = 0;
183  directory_created = !mkdir(file_path, 0755);
184  *p = '/';
185 
186  if (!directory_created) {
187  if (errno == EEXIST) {
188  // directory already existed
189  directory_created = true;
190  } else {
191  // if we didn't succeed at making the directory, then IO failed
192  io_failure = true;
193  return;
194  }
195  }
196  }
197 
198  if (fd != -1) {
199  ::close(fd);
200  }
201 #if HAL_OS_POSIX_IO
202  fd = ::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC, 0644);
203 #else
204  fd = ::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC);
205 #endif
206  if (fd == -1) {
207 #if TERRAIN_DEBUG
208  hal.console->printf("Open %s failed - %s\n",
209  file_path, strerror(errno));
210 #endif
211  io_failure = true;
212  return;
213  }
214 
215  file_lat_degrees = block.lat_degrees;
216  file_lon_degrees = block.lon_degrees;
217 }
218 
219 /*
220  seek to the right offset for disk_block
221  */
222 void AP_Terrain::seek_offset(void)
223 {
224  struct grid_block &block = disk_block.block;
225  // work out how many longitude blocks there are at this latitude
226  Location loc1, loc2;
227  loc1.lat = block.lat_degrees*10*1000*1000L;
228  loc1.lng = block.lon_degrees*10*1000*1000L;
229  loc2.lat = block.lat_degrees*10*1000*1000L;
230  loc2.lng = (block.lon_degrees+1)*10*1000*1000L;
231 
232  // shift another two blocks east to ensure room is available
233  location_offset(loc2, 0, 2*grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
234  Vector2f offset = location_diff(loc1, loc2);
235  uint16_t east_blocks = offset.y / (grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
236 
237  uint32_t file_offset = (east_blocks * block.grid_idx_x +
238  block.grid_idx_y) * sizeof(union grid_io_block);
239  if (::lseek(fd, file_offset, SEEK_SET) != (off_t)file_offset) {
240 #if TERRAIN_DEBUG
241  hal.console->printf("Seek %lu failed - %s\n",
242  (unsigned long)file_offset, strerror(errno));
243 #endif
244  ::close(fd);
245  fd = -1;
246  io_failure = true;
247  }
248 }
249 
250 /*
251  write out disk_block
252  */
253 void AP_Terrain::write_block(void)
254 {
255  seek_offset();
256  if (io_failure) {
257  return;
258  }
259 
260  disk_block.block.crc = get_block_crc(disk_block.block);
261 
262  ssize_t ret = ::write(fd, &disk_block, sizeof(disk_block));
263  if (ret != sizeof(disk_block)) {
264 #if TERRAIN_DEBUG
265  hal.console->printf("write failed - %s\n", strerror(errno));
266 #endif
267  ::close(fd);
268  fd = -1;
269  io_failure = true;
270  } else {
271  ::fsync(fd);
272 #if TERRAIN_DEBUG
273  printf("wrote block at %ld %ld ret=%d mask=%07llx\n",
274  (long)disk_block.block.lat,
275  (long)disk_block.block.lon,
276  (int)ret,
277  (unsigned long long)disk_block.block.bitmap);
278 #endif
279  }
280  disk_io_state = DiskIoDoneWrite;
281 }
282 
283 /*
284  read in disk_block
285  */
286 void AP_Terrain::read_block(void)
287 {
288  seek_offset();
289  if (io_failure) {
290  return;
291  }
292  int32_t lat = disk_block.block.lat;
293  int32_t lon = disk_block.block.lon;
294 
295  ssize_t ret = ::read(fd, &disk_block, sizeof(disk_block));
296  if (ret != sizeof(disk_block) ||
297  disk_block.block.lat != lat ||
298  disk_block.block.lon != lon ||
299  disk_block.block.bitmap == 0 ||
300  disk_block.block.spacing != grid_spacing ||
301  disk_block.block.version != TERRAIN_GRID_FORMAT_VERSION ||
302  disk_block.block.crc != get_block_crc(disk_block.block)) {
303 #if TERRAIN_DEBUG
304  printf("read empty block at %ld %ld ret=%d\n",
305  (long)lat,
306  (long)lon,
307  (int)ret);
308 #endif
309  // a short read or bad data is not an IO failure, just a
310  // missing block on disk
311  memset(&disk_block, 0, sizeof(disk_block));
312  disk_block.block.lat = lat;
313  disk_block.block.lon = lon;
314  disk_block.block.bitmap = 0;
315  } else {
316 #if TERRAIN_DEBUG
317  printf("read block at %ld %ld ret=%d mask=%07llx\n",
318  (long)lat,
319  (long)lon,
320  (int)ret,
321  (unsigned long long)disk_block.block.bitmap);
322 #endif
323  }
324  disk_io_state = DiskIoDoneRead;
325 }
326 
327 /*
328  timer called to do disk IO
329  */
330 void AP_Terrain::io_timer(void)
331 {
332  if (io_failure) {
333  // don't keep trying io, so we don't thrash the filesystem
334  // code while flying
335  return;
336  }
337 
338  switch (disk_io_state) {
339  case DiskIoIdle:
340  case DiskIoDoneRead:
341  case DiskIoDoneWrite:
342  // nothing to do
343  break;
344 
345  case DiskIoWaitWrite:
346  // need to write out the block
347  open_file();
348  if (fd == -1) {
349  return;
350  }
351  write_block();
352  break;
353 
354  case DiskIoWaitRead:
355  // need to read in the block
356  open_file();
357  if (fd == -1) {
358  return;
359  }
360  read_block();
361  break;
362  }
363 }
364 
365 #endif // AP_TERRAIN_AVAILABLE
int printf(const char *fmt,...)
Definition: stdio.c:113
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
Interface definition for the various Ground Control System.
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
AP_HAL::Util * util
Definition: HAL.h:115
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
#define MIN(a, b)
Definition: usb_conf.h:215
T y
Definition: vector2.h:37
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
virtual const char * get_custom_terrain_directory() const
Definition: Util.h:22
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
static int state
Definition: Util.cpp:20
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
Definition: posix.c:612
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
Definition: posix.c:1620
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
virtual void register_io_process(AP_HAL::MemberProc)=0
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
int fsync(int fileno)
Definition: posix.c:2562
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define HAL_BOARD_TERRAIN_DIRECTORY
Definition: linux.h:12
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114