From e2041b0ae7bcea8c4490566856801c6bcec78a21 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 May 2024 20:55:55 +1000 Subject: [PATCH] AP_Scripting: fixed float register save/restore in setjmp/longjmp the register save must happen before the setjmp() call, which means outside of the LUAI_TRY() macro. We also should be saving all 32 floating point registers --- libraries/AP_Scripting/lua/src/ldo.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index 9a5ef40874..7372bd3b39 100644 --- a/libraries/AP_Scripting/lua/src/ldo.c +++ b/libraries/AP_Scripting/lua/src/ldo.c @@ -142,10 +142,10 @@ int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) { lj.status = LUA_OK; lj.previous = L->errorJmp; /* chain new error handler */ L->errorJmp = &lj; - LUAI_TRY(L, &lj, #ifdef ARM_MATH_CM7 __asm__("vpush {s16-s31}"); #endif + LUAI_TRY(L, &lj, (*f)(L, ud); ); #ifdef ARM_MATH_CM7