AP_Terrain: fixed terrain path handling

This commit is contained in:
Andrew Tridgell 2015-06-30 14:35:52 +10:00
parent a3c7297d8e
commit 1296da56bb
2 changed files with 33 additions and 39 deletions

View File

@ -402,6 +402,8 @@ private:
// grid spacing during rally check // grid spacing during rally check
uint16_t last_rally_spacing; uint16_t last_rally_spacing;
char *file_path = NULL;
}; };
#endif // AP_TERRAIN_AVAILABLE #endif // AP_TERRAIN_AVAILABLE
#endif // __AP_TERRAIN_H__ #endif // __AP_TERRAIN_H__

View File

@ -150,56 +150,48 @@ void AP_Terrain::open_file(void)
// already open on right file // already open on right file
return; return;
} }
if (file_path == NULL) {
char *path; const char* terrain_dir = hal.util->get_custom_terrain_directory();
const char* custom_dir = hal.util->get_custom_terrain_directory(); if (terrain_dir == NULL) {
if (custom_dir != NULL){ terrain_dir = HAL_BOARD_TERRAIN_DIRECTORY;
// build the pathname from the args provided
path = (char*) malloc(strlen(custom_dir)+strlen("/NxxExxx.DAT")+1);
if (!path) {
printf("Terrain degree file, malloc() failed: insufficient memory!\n");
exit(1);
} }
strcpy(path, custom_dir); if (asprintf(&file_path, "%s/NxxExxx.DAT", terrain_dir) <= 0) {
strcat(path, "/NxxExxx.DAT"); io_failure = true;
char *p = &path[strlen(HAL_BOARD_TERRAIN_DIRECTORY)+1]; file_path = NULL;
snprintf(p, 12, "%c%02u%c%03u.DAT", return;
block.lat_degrees<0?'S':'N',
abs(block.lat_degrees),
block.lon_degrees<0?'W':'E',
abs(block.lon_degrees));
// create directory if need be
if (!directory_created) {
mkdir(custom_dir, 0755);
directory_created = true;
} }
} else { }
// build the pathname to the degree file if (file_path == NULL) {
char path_default[] = HAL_BOARD_TERRAIN_DIRECTORY "/NxxExxx.DAT"; io_failure = true;
char *p = &path_default[strlen(HAL_BOARD_TERRAIN_DIRECTORY)+1]; return;
snprintf(p, 12, "%c%02u%c%03u.DAT", }
block.lat_degrees<0?'S':'N', char *p = &file_path[strlen(file_path)-12];
abs(block.lat_degrees), if (*p != '/') {
block.lon_degrees<0?'W':'E', io_failure = true;
abs(block.lon_degrees)); return;
}
snprintf(p, 13, "/%c%02u%c%03u.DAT",
block.lat_degrees<0?'S':'N',
abs(block.lat_degrees),
block.lon_degrees<0?'W':'E',
abs(block.lon_degrees));
path = path_default; // create directory if need be
// create directory if need be if (!directory_created) {
if (!directory_created) { *p = 0;
mkdir(HAL_BOARD_TERRAIN_DIRECTORY, 0755); mkdir(file_path, 0755);
directory_created = true; directory_created = true;
} *p = '/';
} }
if (fd != -1) { if (fd != -1) {
::close(fd); ::close(fd);
} }
fd = ::open(path, O_RDWR|O_CREAT, 0644); fd = ::open(file_path, O_RDWR|O_CREAT, 0644);
if (fd == -1) { if (fd == -1) {
#if TERRAIN_DEBUG #if TERRAIN_DEBUG
hal.console->printf("Open %s failed - %s\n", hal.console->printf("Open %s failed - %s\n",
path, strerror(errno)); file_path, strerror(errno));
#endif #endif
io_failure = true; io_failure = true;
return; return;