mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: add and use HAL_SITL &hal_sitl
analogous to our normal "extern hal" stuff but removes need for casting
This commit is contained in:
parent
dd49d79798
commit
402669f269
@ -31,6 +31,8 @@
|
|||||||
|
|
||||||
using namespace HALSITL;
|
using namespace HALSITL;
|
||||||
|
|
||||||
|
HAL_SITL& hal_sitl = (HAL_SITL&)AP_HAL::get_HAL();
|
||||||
|
|
||||||
static Storage sitlStorage;
|
static Storage sitlStorage;
|
||||||
static SITL_State sitlState;
|
static SITL_State sitlState;
|
||||||
static Scheduler sitlScheduler(&sitlState);
|
static Scheduler sitlScheduler(&sitlState);
|
||||||
|
@ -44,7 +44,7 @@
|
|||||||
#include <time.h>
|
#include <time.h>
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern HAL_SITL& hal;
|
||||||
|
|
||||||
using namespace HALSITL;
|
using namespace HALSITL;
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
@ -556,8 +556,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
AP::sitl()->start_time_UTC = start_time_UTC;
|
AP::sitl()->start_time_UTC = start_time_UTC;
|
||||||
}
|
}
|
||||||
|
|
||||||
((HAL_SITL&)hal).set_storage_posix_enabled(storage_posix_enabled);
|
hal.set_storage_posix_enabled(storage_posix_enabled);
|
||||||
((HAL_SITL&)hal).set_storage_flash_enabled(storage_flash_enabled);
|
hal.set_storage_flash_enabled(storage_flash_enabled);
|
||||||
|
|
||||||
if (erase_all_storage) {
|
if (erase_all_storage) {
|
||||||
AP_Param::erase_all();
|
AP_Param::erase_all();
|
||||||
|
@ -23,7 +23,7 @@
|
|||||||
|
|
||||||
using namespace HALSITL;
|
using namespace HALSITL;
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern HAL_SITL& hal;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
emulate flash sector sizes
|
emulate flash sector sizes
|
||||||
@ -56,7 +56,7 @@ void Storage::_storage_open(void)
|
|||||||
_dirty_mask.clearall();
|
_dirty_mask.clearall();
|
||||||
|
|
||||||
#if STORAGE_USE_FLASH
|
#if STORAGE_USE_FLASH
|
||||||
if (((HAL_SITL&)hal).get_storage_flash_enabled()) {
|
if (hal.get_storage_flash_enabled()) {
|
||||||
// load from storage backend
|
// load from storage backend
|
||||||
_flash_load();
|
_flash_load();
|
||||||
_initialisedType = StorageBackend::Flash;
|
_initialisedType = StorageBackend::Flash;
|
||||||
@ -65,7 +65,7 @@ void Storage::_storage_open(void)
|
|||||||
#endif // STORAGE_USE_FLASH
|
#endif // STORAGE_USE_FLASH
|
||||||
|
|
||||||
#if STORAGE_USE_POSIX
|
#if STORAGE_USE_POSIX
|
||||||
if (((HAL_SITL&)hal).get_storage_posix_enabled()) {
|
if (hal.get_storage_posix_enabled()) {
|
||||||
// if we have failed filesystem init don't try again (this is
|
// if we have failed filesystem init don't try again (this is
|
||||||
// initialised to zero in the constructor)
|
// initialised to zero in the constructor)
|
||||||
if (log_fd == -1) {
|
if (log_fd == -1) {
|
||||||
@ -168,7 +168,7 @@ void Storage::_timer_tick(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if STORAGE_USE_POSIX
|
#if STORAGE_USE_POSIX
|
||||||
if (((HAL_SITL&)hal).get_storage_posix_enabled()) {
|
if (hal.get_storage_posix_enabled()) {
|
||||||
if (log_fd != -1) {
|
if (log_fd != -1) {
|
||||||
const off_t offset = STORAGE_LINE_SIZE*i;
|
const off_t offset = STORAGE_LINE_SIZE*i;
|
||||||
if (lseek(log_fd, offset, SEEK_SET) != offset) {
|
if (lseek(log_fd, offset, SEEK_SET) != offset) {
|
||||||
@ -184,7 +184,7 @@ void Storage::_timer_tick(void)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if STORAGE_USE_FLASH
|
#if STORAGE_USE_FLASH
|
||||||
if (((HAL_SITL&)hal).get_storage_flash_enabled()) {
|
if (hal.get_storage_flash_enabled()) {
|
||||||
// save to storage backend
|
// save to storage backend
|
||||||
_flash_write(i);
|
_flash_write(i);
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user