mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: increase default heap size in SITL and on F7/H7
if we have 500k or more memory then use 100k heap for Lua, making setup easier
This commit is contained in:
parent
d2bb387218
commit
5e0bfa9a60
|
@ -33,8 +33,8 @@
|
|||
#endif // !defined(SCRIPTING_STACK_MAX_SIZE)
|
||||
|
||||
#if !defined(SCRIPTING_HEAP_SIZE)
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#define SCRIPTING_HEAP_SIZE (64 * 1024)
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || HAL_MEM_CLASS >= HAL_MEM_CLASS_500
|
||||
#define SCRIPTING_HEAP_SIZE (100 * 1024)
|
||||
#else
|
||||
#define SCRIPTING_HEAP_SIZE (43 * 1024)
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue