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
This commit is contained in:
Andrew Tridgell 2024-05-13 20:55:55 +10:00
parent 228725a976
commit e2041b0ae7
1 changed files with 1 additions and 1 deletions

View File

@ -142,10 +142,10 @@ int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) {
lj.status = LUA_OK; lj.status = LUA_OK;
lj.previous = L->errorJmp; /* chain new error handler */ lj.previous = L->errorJmp; /* chain new error handler */
L->errorJmp = &lj; L->errorJmp = &lj;
LUAI_TRY(L, &lj,
#ifdef ARM_MATH_CM7 #ifdef ARM_MATH_CM7
__asm__("vpush {s16-s31}"); __asm__("vpush {s16-s31}");
#endif #endif
LUAI_TRY(L, &lj,
(*f)(L, ud); (*f)(L, ud);
); );
#ifdef ARM_MATH_CM7 #ifdef ARM_MATH_CM7