mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: reference script environment directly
Referencing the original function to run is of questionable value and the only user uses it to grab the script environent from the upvalues. Instead, use a reference to the script environment table directly.
This commit is contained in:
parent
15255a36e4
commit
3a834e83c7
|
@ -122,8 +122,8 @@ public:
|
|||
// PWMSource storage
|
||||
uint8_t num_pwm_source;
|
||||
AP_HAL::PWMSource *_pwm_source[SCRIPTING_MAX_NUM_PWM_SOURCE];
|
||||
int get_current_ref() { return current_ref; }
|
||||
void set_current_ref(int ref) { current_ref = ref; }
|
||||
int get_current_env_ref() { return current_env_ref; }
|
||||
void set_current_env_ref(int ref) { current_env_ref = ref; }
|
||||
|
||||
#if AP_NETWORKING_ENABLED
|
||||
// SocketAPM storage
|
||||
|
@ -193,7 +193,7 @@ private:
|
|||
bool _stop; // true if scripts should be stopped
|
||||
|
||||
static AP_Scripting *_singleton;
|
||||
int current_ref;
|
||||
int current_env_ref;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
|
@ -622,26 +622,25 @@ static void findloader (lua_State *L, const char *name) {
|
|||
static int ll_require (lua_State *L) {
|
||||
const char *name = luaL_checkstring(L, 1);
|
||||
lua_settop(L, 1);
|
||||
lua_rawgeti(L, LUA_REGISTRYINDEX, lua_get_current_ref()); /* get the current script */
|
||||
lua_getupvalue(L, 2, 1); /* get the environment of the script */
|
||||
lua_getfield(L, 3, LUA_LOADED_TABLE); /* get _LOADED */
|
||||
lua_getfield(L, 4, name); /* LOADED[name] */
|
||||
lua_rawgeti(L, LUA_REGISTRYINDEX, lua_get_current_env_ref()); /* get the environment of the current script */
|
||||
lua_getfield(L, 2, LUA_LOADED_TABLE); /* get _LOADED */
|
||||
lua_getfield(L, 3, name); /* LOADED[name] */
|
||||
if (lua_toboolean(L, -1)) /* is it there? */
|
||||
return 1; /* package is already loaded */
|
||||
/* else must load package */
|
||||
lua_pop(L, 1); /* remove 'getfield' result */
|
||||
findloader(L, name);
|
||||
lua_pushvalue(L, 3); /* push current script's environment */
|
||||
lua_pushvalue(L, 2); /* push current script's environment */
|
||||
lua_setupvalue(L, -3, 1); /* set the environment of the module */
|
||||
lua_pushstring(L, name); /* pass name as argument to module loader */
|
||||
lua_insert(L, -2); /* name is 1st argument (before search data) */
|
||||
lua_call(L, 2, 1); /* run loader to load module */
|
||||
if (!lua_isnil(L, -1)) /* non-nil return? */
|
||||
lua_setfield(L, 4, name); /* LOADED[name] = returned value */
|
||||
if (lua_getfield(L, 4, name) == LUA_TNIL) { /* module set no value? */
|
||||
lua_setfield(L, 3, name); /* LOADED[name] = returned value */
|
||||
if (lua_getfield(L, 3, name) == LUA_TNIL) { /* module set no value? */
|
||||
lua_pushboolean(L, 1); /* use true as result */
|
||||
lua_pushvalue(L, -1); /* extra copy to be returned */
|
||||
lua_setfield(L, 4, name); /* LOADED[name] = true */
|
||||
lua_setfield(L, 3, name); /* LOADED[name] = true */
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
|
|
@ -1040,10 +1040,10 @@ int SocketAPM_accept(lua_State *L) {
|
|||
#endif // AP_NETWORKING_ENABLED
|
||||
|
||||
|
||||
int lua_get_current_ref()
|
||||
int lua_get_current_env_ref()
|
||||
{
|
||||
auto *scripting = AP::scripting();
|
||||
return scripting->get_current_ref();
|
||||
return scripting->get_current_env_ref();
|
||||
}
|
||||
|
||||
// This is used when loading modules with require, lua must only look in enabled directory's
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
#endif //HAL_OS_FATFS_IO
|
||||
#endif // SCRIPTING_DIRECTORY
|
||||
|
||||
int lua_get_current_ref();
|
||||
int lua_get_current_env_ref();
|
||||
const char* lua_get_modules_path();
|
||||
void lua_abort(void) __attribute__((noreturn));
|
||||
|
||||
|
|
|
@ -191,7 +191,8 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
|
|||
|
||||
|
||||
create_sandbox(L);
|
||||
lua_setupvalue(L, -2, 1);
|
||||
lua_pushvalue(L, -1); // duplicate environment for reference below
|
||||
lua_setupvalue(L, -3, 1);
|
||||
|
||||
const uint32_t loadEnd = AP_HAL::micros();
|
||||
const int endMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0);
|
||||
|
@ -199,8 +200,7 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
|
|||
update_stats(filename, loadEnd-loadStart, endMem, loadMem);
|
||||
|
||||
new_script->name = filename;
|
||||
lua_pushvalue(L, -1);
|
||||
new_script->lua_ref = luaL_ref(L, LUA_REGISTRYINDEX); // store reference to object for environment purposes
|
||||
new_script->env_ref = luaL_ref(L, LUA_REGISTRYINDEX); // store reference to script's environment
|
||||
new_script->run_ref = luaL_ref(L, LUA_REGISTRYINDEX); // store reference to function to run
|
||||
new_script->next_run_ms = AP_HAL::millis64() - 1; // force the script to be stale
|
||||
|
||||
|
@ -328,8 +328,8 @@ void lua_scripts::run_next_script(lua_State *L) {
|
|||
|
||||
// pop the function to the top of the stack
|
||||
lua_rawgeti(L, LUA_REGISTRYINDEX, script->run_ref);
|
||||
// set object for environment purposes
|
||||
AP::scripting()->set_current_ref(script->lua_ref);
|
||||
// set current environment for other users
|
||||
AP::scripting()->set_current_env_ref(script->env_ref);
|
||||
|
||||
if(lua_pcall(L, 0, LUA_MULTRET, 0)) {
|
||||
if (overtime) {
|
||||
|
@ -412,7 +412,7 @@ void lua_scripts::remove_script(lua_State *L, script_info *script) {
|
|||
|
||||
if (L != nullptr) {
|
||||
// state could be null if we are force killing all scripts
|
||||
luaL_unref(L, LUA_REGISTRYINDEX, script->lua_ref);
|
||||
luaL_unref(L, LUA_REGISTRYINDEX, script->env_ref);
|
||||
luaL_unref(L, LUA_REGISTRYINDEX, script->run_ref);
|
||||
}
|
||||
_heap.deallocate(script->name);
|
||||
|
|
|
@ -62,7 +62,7 @@ private:
|
|||
void create_sandbox(lua_State *L);
|
||||
|
||||
typedef struct script_info {
|
||||
int lua_ref; // reference to the loaded script object
|
||||
int env_ref; // reference to the script's environment table
|
||||
int run_ref; // reference to the function to run
|
||||
uint64_t next_run_ms; // time (in milliseconds) the script should next be run at
|
||||
uint32_t crc; // crc32 checksum
|
||||
|
@ -111,7 +111,6 @@ private:
|
|||
static HAL_Semaphore error_msg_buf_sem;
|
||||
static uint8_t print_error_count;
|
||||
static uint32_t last_print_ms;
|
||||
int current_ref;
|
||||
|
||||
// XOR of crc32 of running scripts
|
||||
static uint32_t loaded_checksum;
|
||||
|
|
Loading…
Reference in New Issue