mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Scripting: log memory cost of script load
This commit is contained in:
parent
6578c020d8
commit
815adbbc8e
@ -117,6 +117,34 @@ int lua_scripts::atpanic(lua_State *L) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// helper for print and log of runtime stats
|
||||
void lua_scripts::update_stats(const char *name, uint32_t run_time, int total_mem, int run_mem)
|
||||
{
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d",
|
||||
(unsigned int)run_time,
|
||||
(int)total_mem,
|
||||
(int)run_mem);
|
||||
}
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::LOG_RUNTIME)) != 0) {
|
||||
struct log_Scripting pkt {
|
||||
LOG_PACKET_HEADER_INIT(LOG_SCRIPTING_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
name : {},
|
||||
run_time : run_time,
|
||||
total_mem : total_mem,
|
||||
run_mem : run_mem
|
||||
};
|
||||
const char * name_short = strrchr(name, '/');
|
||||
if ((strlen(name) > sizeof(pkt.name)) && (name_short != nullptr)) {
|
||||
strncpy_noterm(pkt.name, name_short+1, sizeof(pkt.name));
|
||||
} else {
|
||||
strncpy_noterm(pkt.name, name, sizeof(pkt.name));
|
||||
}
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
}
|
||||
|
||||
lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename) {
|
||||
if (int error = luaL_loadfile(L, filename)) {
|
||||
switch (error) {
|
||||
@ -139,6 +167,9 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
|
||||
}
|
||||
}
|
||||
|
||||
const int loadMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0);
|
||||
const uint32_t loadStart = AP_HAL::micros();
|
||||
|
||||
script_info *new_script = (script_info *)hal.util->heap_realloc(_heap, nullptr, sizeof(script_info));
|
||||
if (new_script == nullptr) {
|
||||
// No memory, shouldn't happen, we even attempted to do a GC
|
||||
@ -147,12 +178,16 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
new_script->name = filename;
|
||||
new_script->next = nullptr;
|
||||
|
||||
create_sandbox(L);
|
||||
lua_setupvalue(L, -2, 1);
|
||||
|
||||
const uint32_t loadEnd = AP_HAL::micros();
|
||||
const int endMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0);
|
||||
|
||||
update_stats(filename, loadEnd-loadStart, endMem, loadMem);
|
||||
|
||||
new_script->name = filename;
|
||||
new_script->lua_ref = luaL_ref(L, LUA_REGISTRYINDEX); // cache the reference
|
||||
new_script->next_run_ms = AP_HAL::millis64() - 1; // force the script to be stale
|
||||
|
||||
@ -503,29 +538,7 @@ void lua_scripts::run(void) {
|
||||
hal.scheduler->restore_interrupts(istate);
|
||||
#endif
|
||||
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d",
|
||||
(unsigned int)(runEnd - loadEnd),
|
||||
(int)endMem,
|
||||
(int)(endMem - startMem));
|
||||
}
|
||||
if ((_debug_options.get() & uint8_t(DebugLevel::LOG_RUNTIME)) != 0) {
|
||||
struct log_Scripting pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_SCRIPTING_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
name : {},
|
||||
run_time : runEnd - loadEnd,
|
||||
total_mem : endMem,
|
||||
run_mem : endMem - startMem,
|
||||
};
|
||||
const char * name_short = strrchr(script_name, '/');
|
||||
if ((strlen(script_name) > sizeof(pkt.name)) && (name_short != nullptr)) {
|
||||
strncpy_noterm(pkt.name, name_short+1, sizeof(pkt.name));
|
||||
} else {
|
||||
strncpy_noterm(pkt.name, script_name, sizeof(pkt.name));
|
||||
}
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
update_stats(script_name, runEnd - loadEnd, endMem, endMem - startMem);
|
||||
|
||||
|
||||
// garbage collect after each script, this shouldn't matter, but seems to resolve a memory leak
|
||||
|
@ -133,6 +133,9 @@ private:
|
||||
|
||||
static void *_heap;
|
||||
|
||||
// helper for print and log of runtime stats
|
||||
void update_stats(const char *name, uint32_t run_time, int total_mem, int run_mem);
|
||||
|
||||
// must be static for use in atpanic
|
||||
static void print_error(MAV_SEVERITY severity);
|
||||
static char *error_msg_buf;
|
||||
|
Loading…
Reference in New Issue
Block a user