Skip to content

Commit

Permalink
AP_Scripting: fixed float register save/restore in setjmp/longjmp
Browse files Browse the repository at this point in the history
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
  • Loading branch information
tridge committed May 13, 2024
1 parent 08d8922 commit c831b98
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion libraries/AP_Scripting/lua/src/ldo.c
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit c831b98

Please sign in to comment.