AP_DAL: add 10k to SITL memory available

this is needed as the SITL data structures are larger than on STM32
due to pointer size. This means we sometimes fail to replay in SITL as
we refuse to allocate an EKF core
This commit is contained in:
Andrew Tridgell 2021-01-18 09:16:40 +11:00
parent c02c546077
commit 53326a08ed
1 changed files with 4 additions and 0 deletions

View File

@ -103,7 +103,11 @@ public:
// ramifications of being out of memory are that you don't start // ramifications of being out of memory are that you don't start
// the EKF, so the simplicity of having one value for the entire // the EKF, so the simplicity of having one value for the entire
// frame is worthwhile. // frame is worthwhile.
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
uint32_t available_memory() const { return _RFRN.available_memory + 10240; }
#else
uint32_t available_memory() const { return _RFRN.available_memory; } uint32_t available_memory() const { return _RFRN.available_memory; }
#endif
int8_t get_ekf_type(void) const { int8_t get_ekf_type(void) const {
return _RFRN.ekf_type; return _RFRN.ekf_type;