2015-11-20 03:32:44 -04:00
|
|
|
#pragma once
|
2015-05-04 03:15:12 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-05-04 03:15:12 -03:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_SITL.h"
|
2015-05-04 03:15:12 -03:00
|
|
|
#include "AP_HAL_SITL_Namespace.h"
|
|
|
|
#include "SITL_State.h"
|
|
|
|
|
|
|
|
class HAL_SITL : public AP_HAL::HAL {
|
|
|
|
public:
|
2015-05-04 21:59:07 -03:00
|
|
|
HAL_SITL();
|
2015-10-19 11:26:18 -03:00
|
|
|
void run(int argc, char * const argv[], Callbacks* callbacks) const override;
|
2019-07-08 05:02:18 -03:00
|
|
|
static void actually_reboot();
|
2015-05-04 03:15:12 -03:00
|
|
|
|
2021-06-10 23:30:38 -03:00
|
|
|
void set_storage_posix_enabled(bool _enabled) {
|
|
|
|
storage_posix_enabled = _enabled;
|
|
|
|
}
|
|
|
|
bool get_storage_posix_enabled() const { return storage_posix_enabled; }
|
|
|
|
void set_storage_flash_enabled(bool _enabled) {
|
|
|
|
storage_flash_enabled = _enabled;
|
|
|
|
}
|
|
|
|
bool get_storage_flash_enabled() const { return storage_flash_enabled; }
|
2021-07-12 22:41:18 -03:00
|
|
|
void set_storage_fram_enabled(bool _enabled) {
|
|
|
|
storage_fram_enabled = _enabled;
|
|
|
|
}
|
|
|
|
bool get_storage_fram_enabled() const { return storage_fram_enabled; }
|
|
|
|
|
|
|
|
/*
|
|
|
|
instructs the simulation to wipe any storage as it opens it:
|
|
|
|
*/
|
|
|
|
void set_wipe_storage(bool _wipe_storage) {
|
|
|
|
wipe_storage = _wipe_storage;
|
|
|
|
}
|
|
|
|
bool get_wipe_storage() const { return wipe_storage; }
|
2021-06-10 23:30:38 -03:00
|
|
|
|
2021-10-16 00:10:40 -03:00
|
|
|
uint8_t get_instance() const;
|
|
|
|
|
2022-04-29 08:48:37 -03:00
|
|
|
#if defined(HAL_BUILD_AP_PERIPH)
|
|
|
|
bool run_in_maintenance_mode() const;
|
|
|
|
#endif
|
|
|
|
|
2024-06-08 04:42:26 -03:00
|
|
|
uint32_t get_uart_output_full_queue_count() const;
|
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
private:
|
|
|
|
HALSITL::SITL_State *_sitl_state;
|
2019-09-22 21:39:42 -03:00
|
|
|
|
|
|
|
void setup_signal_handlers() const;
|
|
|
|
static void exit_signal_handler(int);
|
2021-06-10 23:30:38 -03:00
|
|
|
|
2023-04-09 18:32:11 -03:00
|
|
|
bool storage_posix_enabled = true;
|
2021-06-10 23:30:38 -03:00
|
|
|
bool storage_flash_enabled;
|
2021-07-12 22:41:18 -03:00
|
|
|
bool storage_fram_enabled;
|
2021-06-10 23:30:38 -03:00
|
|
|
|
2021-07-12 22:41:18 -03:00
|
|
|
// set to true if simulation is to wipe storage as it is opened:
|
|
|
|
bool wipe_storage;
|
2015-05-04 03:15:12 -03:00
|
|
|
};
|
|
|
|
|
2020-05-31 09:32:19 -03:00
|
|
|
#if HAL_NUM_CAN_IFACES
|
|
|
|
typedef HALSITL::CANIface HAL_CANIface;
|
|
|
|
#endif
|
|
|
|
|
2017-01-09 08:23:23 -04:00
|
|
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|