mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Add a debug level param
This commit is contained in:
parent
200870e7a0
commit
d7e71f85b8
|
@ -63,6 +63,8 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = {
|
|||
// @RebootRequired: True
|
||||
AP_GROUPINFO("HEAP_SIZE", 3, AP_Scripting, _script_heap_size, 32*1024),
|
||||
|
||||
AP_GROUPINFO("DEBUG_LVL", 4, AP_Scripting, _debug_level, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -92,7 +94,7 @@ bool AP_Scripting::init(void) {
|
|||
}
|
||||
|
||||
void AP_Scripting::thread(void) {
|
||||
lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size);
|
||||
lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_level);
|
||||
if (lua == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Unable to allocate scripting memory");
|
||||
return;
|
||||
|
|
|
@ -42,6 +42,7 @@ private:
|
|||
AP_Int8 _enable;
|
||||
AP_Int32 _script_vm_exec_count;
|
||||
AP_Int32 _script_heap_size;
|
||||
AP_Int8 _debug_level;
|
||||
|
||||
static AP_Scripting *_singleton;
|
||||
|
||||
|
|
|
@ -41,8 +41,9 @@ 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, const AP_Int32 &heap_size)
|
||||
: _vm_steps(vm_steps) {
|
||||
lua_scripts::lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, const AP_Int8 &debug_level)
|
||||
: _vm_steps(vm_steps),
|
||||
_debug_level(debug_level) {
|
||||
_heap = hal.util->allocate_heap_memory(heap_size);
|
||||
}
|
||||
|
||||
|
@ -375,7 +376,9 @@ void lua_scripts::run(void) {
|
|||
hal.scheduler->delay(scripts->next_run_ms - now_ms);
|
||||
}
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name);
|
||||
if (_debug_level > 1) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name);
|
||||
}
|
||||
|
||||
const uint32_t startMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0);
|
||||
const uint32_t loadEnd = AP_HAL::micros();
|
||||
|
@ -384,7 +387,9 @@ void lua_scripts::run(void) {
|
|||
|
||||
const uint32_t runEnd = AP_HAL::micros();
|
||||
const uint32_t endMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0);
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Time: %d Mem: %d", runEnd - loadEnd, endMem - startMem);
|
||||
if (_debug_level > 1) {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Time: %d Mem: %d", runEnd - loadEnd, endMem - startMem);
|
||||
}
|
||||
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: No scripts to run");
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
class lua_scripts
|
||||
{
|
||||
public:
|
||||
lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size);
|
||||
lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, const AP_Int8 &debug_level);
|
||||
|
||||
/* Do not allow copies */
|
||||
lua_scripts(const lua_scripts &other) = delete;
|
||||
|
@ -66,6 +66,7 @@ private:
|
|||
lua_State *lua_state;
|
||||
|
||||
const AP_Int32 & _vm_steps;
|
||||
const AP_Int8 & _debug_level;
|
||||
|
||||
static void *alloc(void *ud, void *ptr, size_t osize, size_t nsize);
|
||||
|
||||
|
|
Loading…
Reference in New Issue