HAL_ESP32: allow for building with sim on hw
This commit is contained in:
parent
6c88111267
commit
d90a4654a7
@ -28,6 +28,9 @@
|
|||||||
#include "Storage.h"
|
#include "Storage.h"
|
||||||
#include "AnalogIn.h"
|
#include "AnalogIn.h"
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
|
#include <AP_HAL/SIMState.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
static ESP32::UARTDriver cons(0);
|
static ESP32::UARTDriver cons(0);
|
||||||
@ -60,15 +63,27 @@ static ESP32::AnalogIn analogIn;
|
|||||||
#else
|
#else
|
||||||
static Empty::AnalogIn analogIn;
|
static Empty::AnalogIn analogIn;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef HAL_USE_EMPTY_STORAGE
|
||||||
|
static Empty::Storage storageDriver;
|
||||||
|
#else
|
||||||
static ESP32::Storage storageDriver;
|
static ESP32::Storage storageDriver;
|
||||||
|
#endif
|
||||||
static Empty::GPIO gpioDriver;
|
static Empty::GPIO gpioDriver;
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
|
static Empty::RCOutput rcoutDriver;
|
||||||
|
#else
|
||||||
static ESP32::RCOutput rcoutDriver;
|
static ESP32::RCOutput rcoutDriver;
|
||||||
|
#endif
|
||||||
static ESP32::RCInput rcinDriver;
|
static ESP32::RCInput rcinDriver;
|
||||||
static ESP32::Scheduler schedulerInstance;
|
static ESP32::Scheduler schedulerInstance;
|
||||||
static ESP32::Util utilInstance;
|
static ESP32::Util utilInstance;
|
||||||
static Empty::OpticalFlow opticalFlowDriver;
|
static Empty::OpticalFlow opticalFlowDriver;
|
||||||
static Empty::Flash flashDriver;
|
static Empty::Flash flashDriver;
|
||||||
|
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
|
static AP_HAL::SIMState xsimstate;
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
HAL_ESP32::HAL_ESP32() :
|
HAL_ESP32::HAL_ESP32() :
|
||||||
@ -96,6 +111,9 @@ HAL_ESP32::HAL_ESP32() :
|
|||||||
&utilInstance,
|
&utilInstance,
|
||||||
&opticalFlowDriver,
|
&opticalFlowDriver,
|
||||||
&flashDriver,
|
&flashDriver,
|
||||||
|
#if AP_SIM_ENABLED
|
||||||
|
&xsimstate,
|
||||||
|
#endif
|
||||||
#if HAL_WITH_DSP
|
#if HAL_WITH_DSP
|
||||||
&dspDriver,
|
&dspDriver,
|
||||||
#endif
|
#endif
|
||||||
|
@ -89,10 +89,10 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
|||||||
|
|
||||||
void RCInput::_timer_tick(void)
|
void RCInput::_timer_tick(void)
|
||||||
{
|
{
|
||||||
|
#if AP_RCPROTOCOL_ENABLED
|
||||||
if (!_init) {
|
if (!_init) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_RCProtocol &rcprot = AP::RC();
|
AP_RCProtocol &rcprot = AP::RC();
|
||||||
|
|
||||||
#ifdef HAL_ESP32_RCIN
|
#ifdef HAL_ESP32_RCIN
|
||||||
@ -126,4 +126,5 @@ void RCInput::_timer_tick(void)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
#endif // AP_RCPROTOCOL_ENABLED
|
||||||
}
|
}
|
||||||
|
@ -148,3 +148,4 @@
|
|||||||
|
|
||||||
#define HAL_LOGGING_BACKENDS_DEFAULT 1
|
#define HAL_LOGGING_BACKENDS_DEFAULT 1
|
||||||
|
|
||||||
|
#define AP_RCPROTOCOL_ENABLED 0
|
||||||
|
@ -44,7 +44,7 @@
|
|||||||
#define HAL_USE_ADC 0
|
#define HAL_USE_ADC 0
|
||||||
|
|
||||||
// 2 use udp, 1 use tcp... for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 port 14550
|
// 2 use udp, 1 use tcp... for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 port 14550
|
||||||
#define HAL_ESP32_WIFI 1
|
#define HAL_ESP32_WIFI 2
|
||||||
|
|
||||||
// see boards.py
|
// see boards.py
|
||||||
#ifndef ENABLE_HEAP
|
#ifndef ENABLE_HEAP
|
||||||
@ -87,3 +87,9 @@
|
|||||||
|
|
||||||
#define HAL_LOGGING_BACKENDS_DEFAULT 1
|
#define HAL_LOGGING_BACKENDS_DEFAULT 1
|
||||||
|
|
||||||
|
#define AP_RCPROTOCOL_ENABLED 0
|
||||||
|
|
||||||
|
#define AP_FILESYSTEM_ESP32_ENABLED 0
|
||||||
|
#define AP_SCRIPTING_ENABLED 0
|
||||||
|
#define HAL_USE_EMPTY_STORAGE 1
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user