diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index fe8dadc58d..ff1e1e052c 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -216,6 +216,15 @@ void AP_Scripting::repl_stop(void) { // can't do any more cleanup here, closing the open FD's is the REPL's responsibility } +/* + avoid optimisation of the thread function. This avoids nasty traps + where setjmp/longjmp does not properly handle save/restore of + floating point registers on exceptions. This is an extra protection + over the top of the fix in luaD_rawrunprotected() for the same issue + */ +#pragma GCC push_options +#pragma GCC optimize ("O0") + void AP_Scripting::thread(void) { while (true) { // reset flags @@ -264,6 +273,7 @@ void AP_Scripting::thread(void) { } } } +#pragma GCC pop_options void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd_in) { diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index 951a5b5223..9a5ef40874 100644 --- a/libraries/AP_Scripting/lua/src/ldo.c +++ b/libraries/AP_Scripting/lua/src/ldo.c @@ -133,7 +133,9 @@ l_noret luaD_throw (lua_State *L, int errcode) { } } - +// remove optimization +#pragma GCC push_options +#pragma GCC optimize ("O0") int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) { unsigned short oldnCcalls = L->nCcalls; struct lua_longjmp lj; @@ -141,13 +143,19 @@ int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) { lj.previous = L->errorJmp; /* chain new error handler */ L->errorJmp = &lj; LUAI_TRY(L, &lj, +#ifdef ARM_MATH_CM7 + __asm__("vpush {s16-s31}"); +#endif (*f)(L, ud); ); +#ifdef ARM_MATH_CM7 + __asm__("vpop {s16-s31}"); +#endif L->errorJmp = lj.previous; /* restore old error handler */ L->nCcalls = oldnCcalls; return lj.status; } - +#pragma GCC pop_options /* }====================================================== */