26 #if AP_TERRAIN_AVAILABLE 36 #include <sys/types.h> 43 void AP_Terrain::check_disk_read(
void)
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;
57 void AP_Terrain::check_disk_write(
void)
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;
71 void AP_Terrain::schedule_disk_io(
void)
73 if (enable == 0 || !allocate()) {
82 switch (disk_io_state) {
86 if (disk_io_state == DiskIoIdle) {
92 case DiskIoDoneRead: {
94 int16_t cache_idx = find_io_idx(GRID_CACHE_DISKWAIT);
95 if (cache_idx != -1) {
96 if (disk_block.block.bitmap != 0) {
98 cache[cache_idx].grid = disk_block.block;
100 cache[cache_idx].state = GRID_CACHE_VALID;
103 disk_io_state = DiskIoIdle;
107 case DiskIoDoneWrite: {
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) {
113 cache[cache_idx].state = GRID_CACHE_VALID;
116 disk_io_state = DiskIoIdle;
120 case DiskIoWaitWrite:
145 void AP_Terrain::open_file(
void)
147 struct grid_block &block = disk_block.block;
149 block.lat_degrees == file_lat_degrees &&
150 block.lon_degrees == file_lon_degrees) {
154 if (file_path ==
nullptr) {
156 if (terrain_dir ==
nullptr) {
159 if (
asprintf(&file_path,
"%s/NxxExxx.DAT", terrain_dir) <= 0) {
165 if (file_path ==
nullptr) {
169 char *p = &file_path[strlen(file_path)-12];
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));
181 if (!directory_created) {
183 directory_created = !
mkdir(file_path, 0755);
186 if (!directory_created) {
187 if (
errno == EEXIST) {
189 directory_created =
true;
202 fd =
::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC, 0644);
204 fd =
::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC);
215 file_lat_degrees = block.lat_degrees;
216 file_lon_degrees = block.lon_degrees;
222 void AP_Terrain::seek_offset(
void)
224 struct grid_block &block = disk_block.block;
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;
235 uint16_t east_blocks = offset.
y / (grid_spacing*TERRAIN_GRID_BLOCK_SIZE_Y);
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) {
253 void AP_Terrain::write_block(
void)
260 disk_block.block.crc = get_block_crc(disk_block.block);
262 ssize_t ret =
::write(fd, &disk_block,
sizeof(disk_block));
263 if (ret !=
sizeof(disk_block)) {
273 printf(
"wrote block at %ld %ld ret=%d mask=%07llx\n",
274 (
long)disk_block.block.lat,
275 (
long)disk_block.block.lon,
277 (
unsigned long long)disk_block.block.bitmap);
280 disk_io_state = DiskIoDoneWrite;
286 void AP_Terrain::read_block(
void)
292 int32_t lat = disk_block.block.lat;
293 int32_t lon = disk_block.block.lon;
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)) {
304 printf(
"read empty block at %ld %ld ret=%d\n",
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;
317 printf(
"read block at %ld %ld ret=%d mask=%07llx\n",
321 (
unsigned long long)disk_block.block.bitmap);
324 disk_io_state = DiskIoDoneRead;
330 void AP_Terrain::io_timer(
void)
338 switch (disk_io_state) {
341 case DiskIoDoneWrite:
345 case DiskIoWaitWrite:
365 #endif // AP_TERRAIN_AVAILABLE int printf(const char *fmt,...)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
Interface definition for the various Ground Control System.
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
int32_t lat
param 3 - Latitude * 10**7
virtual void printf(const char *,...) FMT_PRINTF(2
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
virtual const char * get_custom_terrain_directory() const
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
int close(int fileno)
POSIX Close a file with fileno handel.
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
virtual void register_io_process(AP_HAL::MemberProc)=0
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int snprintf(char *str, size_t size, const char *fmt,...)
int asprintf(char **strp, const char *fmt,...)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
#define HAL_BOARD_TERRAIN_DIRECTORY
AP_HAL::Scheduler * scheduler