AP_Scripting: Catch lua panics
This commit is contained in:
parent
686abb5e61
commit
0ede7b7d39
@ -26,7 +26,7 @@ int lua_servo_set_output_pwm(lua_State *state) {
|
||||
return luaL_error(state, "Servo function (%d) is not a scriptable output", servo_function);
|
||||
}
|
||||
|
||||
if (output_value > UINT16_MAX) {
|
||||
if (output_value > (int)UINT16_MAX) {
|
||||
return luaL_error(state, "Servo range (%d) is out of range", output_value);
|
||||
}
|
||||
|
||||
|
@ -37,6 +37,7 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
bool lua_scripts::overtime;
|
||||
jmp_buf lua_scripts::panic_jmp;
|
||||
|
||||
lua_scripts::lua_scripts(const AP_Int32 &vm_steps)
|
||||
: _vm_steps(vm_steps) {
|
||||
@ -53,6 +54,13 @@ void lua_scripts::hook(lua_State *L, lua_Debug *ar) {
|
||||
luaL_error(L, "Exceeded CPU time");
|
||||
}
|
||||
|
||||
int lua_scripts::atpanic(lua_State *L) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Panic: %s", lua_tostring(L, -1));
|
||||
hal.console->printf("Lua: Panic: %s\n", lua_tostring(L, -1));
|
||||
longjmp(panic_jmp, 1);
|
||||
return 0;
|
||||
}
|
||||
|
||||
lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename) {
|
||||
if (int error = luaL_loadfile(L, filename)) {
|
||||
switch (error) {
|
||||
@ -62,13 +70,17 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
|
||||
case LUA_ERRMEM:
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Insufficent memory loading %s", filename);
|
||||
return nullptr;
|
||||
case LUA_ERRFILE:
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Unable to load the file: %s", lua_tostring(L, -1));
|
||||
hal.console->printf("Lua: File error: %s\n", lua_tostring(L, -1));
|
||||
return nullptr;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Unknown error (%d) loading %s", error, filename);
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
script_info *new_script = (script_info *)luaM_malloc(L, sizeof(script_info));
|
||||
script_info *new_script = (script_info *)malloc(sizeof(script_info));
|
||||
if (new_script == nullptr) {
|
||||
// No memory, shouldn't happen, we even attempted to do a GC
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Insufficent memory loading %s", filename);
|
||||
@ -120,7 +132,7 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) {
|
||||
|
||||
// FIXME: because chunk name fetching is not working we are allocating and storing an extra string we shouldn't need to
|
||||
size_t size = strlen(dirname) + strlen(de->d_name) + 2;
|
||||
char * filename = (char *)luaM_malloc(L, size);
|
||||
char * filename = (char *)malloc(size);
|
||||
if (filename == nullptr) {
|
||||
continue;
|
||||
}
|
||||
@ -129,12 +141,13 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) {
|
||||
// we have something that looks like a lua file, attempt to load it
|
||||
script_info * script = load_script(L, filename);
|
||||
if (script == nullptr) {
|
||||
luaM_free(L, filename);
|
||||
free(filename);
|
||||
continue;
|
||||
}
|
||||
reschedule_script(script);
|
||||
|
||||
}
|
||||
closedir(d);
|
||||
}
|
||||
|
||||
void lua_scripts::run_next_script(lua_State *L) {
|
||||
@ -219,6 +232,10 @@ void lua_scripts::run_next_script(lua_State *L) {
|
||||
}
|
||||
|
||||
void lua_scripts::remove_script(lua_State *L, script_info *script) {
|
||||
if (script == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
// ensure that the script isn't in the loaded list for any reason
|
||||
if (scripts == nullptr) {
|
||||
// nothing to do, already not in the list
|
||||
@ -233,9 +250,12 @@ void lua_scripts::remove_script(lua_State *L, script_info *script) {
|
||||
}
|
||||
}
|
||||
|
||||
luaL_unref(L, LUA_REGISTRYINDEX, script->lua_ref);
|
||||
luaM_free(L, script->name);
|
||||
luaM_free(L, script);
|
||||
if (L != nullptr) {
|
||||
// state could be null if we are force killing all scripts
|
||||
luaL_unref(L, LUA_REGISTRYINDEX, script->lua_ref);
|
||||
}
|
||||
free(script->name);
|
||||
free(script);
|
||||
}
|
||||
|
||||
void lua_scripts::reschedule_script(script_info *script) {
|
||||
@ -274,7 +294,26 @@ void lua_scripts::reschedule_script(script_info *script) {
|
||||
}
|
||||
|
||||
void lua_scripts::run(void) {
|
||||
lua_State *L = luaL_newstate();
|
||||
// panic should be hooked first
|
||||
if (setjmp(panic_jmp)) {
|
||||
if (lua_state != nullptr) {
|
||||
lua_close(lua_state); // shutdown the old state
|
||||
}
|
||||
// remove all the old scheduled scripts
|
||||
for (script_info *script = scripts; script != nullptr; script = scripts) {
|
||||
remove_script(nullptr, script);
|
||||
}
|
||||
scripts = nullptr;
|
||||
overtime = false;
|
||||
}
|
||||
|
||||
lua_state = luaL_newstate();
|
||||
lua_State *L = lua_state;
|
||||
if (L == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Couldn't allocate a lua state");
|
||||
return;
|
||||
}
|
||||
lua_atpanic(L, atpanic);
|
||||
luaL_openlibs(L);
|
||||
load_lua_bindings(L);
|
||||
|
||||
@ -296,6 +335,12 @@ void lua_scripts::run(void) {
|
||||
load_all_scripts_in_dir(L, SCRIPTING_DIRECTORY);
|
||||
|
||||
while (true) {
|
||||
#if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1
|
||||
if (lua_gettop(L) != 0) {
|
||||
AP_HAL::panic("Lua: Stack should be empty before running scripts");
|
||||
}
|
||||
#endif // defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1
|
||||
|
||||
if (scripts != nullptr) {
|
||||
#if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1
|
||||
// Sanity check that the scripts list is ordered correctly
|
||||
@ -327,7 +372,7 @@ void lua_scripts::run(void) {
|
||||
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: No scripts to run");
|
||||
hal.scheduler->delay(100);
|
||||
hal.scheduler->delay(10000);
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -16,6 +16,7 @@
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <setjmp.h>
|
||||
|
||||
#include "lua_bindings.h"
|
||||
|
||||
@ -58,6 +59,12 @@ private:
|
||||
// it must be static to be passed to the C API
|
||||
static void hook(lua_State *L, lua_Debug *ar);
|
||||
|
||||
// lua panic handler, will jump back to the start of run
|
||||
static int atpanic(lua_State *L);
|
||||
static jmp_buf panic_jmp;
|
||||
|
||||
lua_State *lua_state;
|
||||
|
||||
const AP_Int32 & _vm_steps;
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user