From c831b9881ec6bd0bed9b994b3a34ea0c0c4ed5a3 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 | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index c07f4fdb32854c..a4fa2ccb8f3a8f 100644 --- a/libraries/AP_Scripting/lua/src/ldo.c +++ b/libraries/AP_Scripting/lua/src/ldo.c @@ -142,14 +142,16 @@ 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 {s0-s15}"); __asm__("vpush {s16-s31}"); #endif + LUAI_TRY(L, &lj, (*f)(L, ud); ); #ifdef ARM_MATH_CM7 __asm__("vpop {s16-s31}"); + __asm__("vpop {s0-s15}"); #endif L->errorJmp = lj.previous; /* restore old error handler */ L->nCcalls = oldnCcalls;