mirror of https://github.com/ArduPilot/ardupilot
AP_Terrain: added support for AP_Terrain for ChibiOS
This commit is contained in:
parent
2773b17fad
commit
f8542c86b6
|
@ -25,10 +25,12 @@
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
#if HAL_OS_POSIX_IO
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <sys/types.h>
|
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
|
#endif
|
||||||
|
#include <sys/types.h>
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <DataFlash/DataFlash.h>
|
#include <DataFlash/DataFlash.h>
|
||||||
|
|
||||||
#if HAL_OS_POSIX_IO && defined(HAL_BOARD_TERRAIN_DIRECTORY)
|
#if (HAL_OS_POSIX_IO || HAL_OS_FATFS_IO) && defined(HAL_BOARD_TERRAIN_DIRECTORY)
|
||||||
#define AP_TERRAIN_AVAILABLE 1
|
#define AP_TERRAIN_AVAILABLE 1
|
||||||
#else
|
#else
|
||||||
#define AP_TERRAIN_AVAILABLE 0
|
#define AP_TERRAIN_AVAILABLE 0
|
||||||
|
|
|
@ -27,11 +27,13 @@
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
#if HAL_OS_POSIX_IO
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <sys/types.h>
|
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
|
#endif
|
||||||
|
#include <sys/types.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -196,7 +198,11 @@ void AP_Terrain::open_file(void)
|
||||||
if (fd != -1) {
|
if (fd != -1) {
|
||||||
::close(fd);
|
::close(fd);
|
||||||
}
|
}
|
||||||
|
#if HAL_OS_POSIX_IO
|
||||||
fd = ::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC, 0644);
|
fd = ::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC, 0644);
|
||||||
|
#else
|
||||||
|
fd = ::open(file_path, O_RDWR|O_CREAT|O_CLOEXEC);
|
||||||
|
#endif
|
||||||
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",
|
||||||
|
|
|
@ -27,10 +27,12 @@
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
#if HAL_OS_POSIX_IO
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <sys/types.h>
|
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
|
#endif
|
||||||
|
#include <sys/types.h>
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
Loading…
Reference in New Issue