AP_Scripting: cleanup debug option handling

This commit is contained in:
Andrew Tridgell 2024-03-13 17:36:57 +11:00
parent 79b596d229
commit 66752996e4
4 changed files with 33 additions and 23 deletions

View File

@ -380,7 +380,7 @@ void AP_Scripting::thread(void) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted"); GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted");
break; break;
} }
if ((_debug_options.get() & uint8_t(lua_scripts::DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) { if (option_is_set(DebugOption::NO_SCRIPTS_TO_RUN)) {
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped"); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped");
} }
} }
@ -420,7 +420,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd
bool AP_Scripting::arming_checks(size_t buflen, char *buffer) const bool AP_Scripting::arming_checks(size_t buflen, char *buffer) const
{ {
if (!enabled() || ((_debug_options.get() & uint8_t(lua_scripts::DebugLevel::DISABLE_PRE_ARM)) != 0)) { if (!enabled() || option_is_set(DebugOption::DISABLE_PRE_ARM)) {
return true; return true;
} }
@ -518,9 +518,7 @@ void AP_Scripting::update() {
// Check if DEBUG_OPTS bit has been set to save current checksum values to params // Check if DEBUG_OPTS bit has been set to save current checksum values to params
void AP_Scripting::save_checksum() { void AP_Scripting::save_checksum() {
const uint8_t opts = _debug_options.get(); if (!option_is_set(DebugOption::SAVE_CHECKSUM)) {
const uint8_t save_bit = uint8_t(lua_scripts::DebugLevel::SAVE_CHECKSUM);
if ((opts & save_bit) == 0) {
// Bit not set, nothing to do // Bit not set, nothing to do
return; return;
} }
@ -530,7 +528,7 @@ void AP_Scripting::save_checksum() {
_required_running_checksum.set_and_save(lua_scripts::get_running_checksum() & checksum_param_mask); _required_running_checksum.set_and_save(lua_scripts::get_running_checksum() & checksum_param_mask);
// Un-set debug option bit // Un-set debug option bit
_debug_options.set_and_save(opts & ~save_bit); option_clear(DebugOption::SAVE_CHECKSUM);
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "saved checksums"); GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "saved checksums");

View File

@ -152,6 +152,15 @@ public:
AP_Scripting_SerialDevice _serialdevice; AP_Scripting_SerialDevice _serialdevice;
#endif #endif
enum class DebugOption : uint8_t {
NO_SCRIPTS_TO_RUN = 1U << 0,
RUNTIME_MSG = 1U << 1,
SUPPRESS_SCRIPT_LOG = 1U << 2,
LOG_RUNTIME = 1U << 3,
DISABLE_PRE_ARM = 1U << 4,
SAVE_CHECKSUM = 1U << 5,
};
private: private:
void thread(void); // main script execution thread void thread(void); // main script execution thread
@ -185,6 +194,14 @@ private:
AP_Enum<ThreadPriority> _thd_priority; AP_Enum<ThreadPriority> _thd_priority;
bool option_is_set(DebugOption option) const {
return (uint8_t(_debug_options.get()) & uint8_t(option)) != 0;
}
void option_clear(DebugOption option) {
_debug_options.set_and_save(_debug_options.get() & ~uint8_t(option));
}
bool _thread_failed; // thread allocation failed bool _thread_failed; // thread allocation failed
bool _init_failed; // true if memory allocation failed bool _init_failed; // true if memory allocation failed
bool _restart; // true if scripts should be restarted bool _restart; // true if scripts should be restarted

View File

@ -40,7 +40,7 @@ uint32_t lua_scripts::loaded_checksum;
uint32_t lua_scripts::running_checksum; uint32_t lua_scripts::running_checksum;
HAL_Semaphore lua_scripts::crc_sem; HAL_Semaphore lua_scripts::crc_sem;
lua_scripts::lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, const AP_Int8 &debug_options) lua_scripts::lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, AP_Int8 &debug_options)
: _vm_steps(vm_steps), : _vm_steps(vm_steps),
_debug_options(debug_options) _debug_options(debug_options)
{ {
@ -129,14 +129,14 @@ int lua_scripts::atpanic(lua_State *L) {
// helper for print and log of runtime stats // 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) 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) { if (option_is_set(AP_Scripting::DebugOption::RUNTIME_MSG)) {
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d", GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d",
(unsigned int)run_time, (unsigned int)run_time,
(int)total_mem, (int)total_mem,
(int)run_mem); (int)run_mem);
} }
#if HAL_LOGGING_ENABLED #if HAL_LOGGING_ENABLED
if ((_debug_options.get() & uint8_t(DebugLevel::LOG_RUNTIME)) != 0) { if (option_is_set(AP_Scripting::DebugOption::LOG_RUNTIME)) {
struct log_Scripting pkt { struct log_Scripting pkt {
LOG_PACKET_HEADER_INIT(LOG_SCRIPTING_MSG), LOG_PACKET_HEADER_INIT(LOG_SCRIPTING_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
@ -295,7 +295,7 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) {
reschedule_script(script); reschedule_script(script);
#if HAL_LOGGER_FILE_CONTENTS_ENABLED #if HAL_LOGGER_FILE_CONTENTS_ENABLED
if ((_debug_options.get() & uint8_t(DebugLevel::SUPPRESS_SCRIPT_LOG)) == 0) { if (!option_is_set(AP_Scripting::DebugOption::SUPPRESS_SCRIPT_LOG)) {
AP::logger().log_file_content(filename); AP::logger().log_file_content(filename);
} }
#endif #endif
@ -564,7 +564,7 @@ void lua_scripts::run(void) {
hal.scheduler->delay(scripts->next_run_ms - now_ms); hal.scheduler->delay(scripts->next_run_ms - now_ms);
} }
if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) { if (option_is_set(AP_Scripting::DebugOption::RUNTIME_MSG)) {
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name);
} }
// take a copy of the script name for the purposes of // take a copy of the script name for the purposes of
@ -600,7 +600,7 @@ void lua_scripts::run(void) {
lua_gc(L, LUA_GCCOLLECT, 0); lua_gc(L, LUA_GCCOLLECT, 0);
} else { } else {
if ((_debug_options.get() & uint8_t(DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) { if (option_is_set(AP_Scripting::DebugOption::NO_SCRIPTS_TO_RUN)) {
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: No scripts to run"); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: No scripts to run");
} }
hal.scheduler->delay(1000); hal.scheduler->delay(1000);

View File

@ -34,7 +34,7 @@
class lua_scripts class lua_scripts
{ {
public: public:
lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, const AP_Int8 &debug_options); lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, AP_Int8 &debug_options);
~lua_scripts(); ~lua_scripts();
@ -48,15 +48,6 @@ public:
static bool overtime; // script exceeded it's execution slot, and we are bailing out static bool overtime; // script exceeded it's execution slot, and we are bailing out
enum class DebugLevel {
NO_SCRIPTS_TO_RUN = 1U << 0,
RUNTIME_MSG = 1U << 1,
SUPPRESS_SCRIPT_LOG = 1U << 2,
LOG_RUNTIME = 1U << 3,
DISABLE_PRE_ARM = 1U << 4,
SAVE_CHECKSUM = 1U << 5,
};
private: private:
void create_sandbox(lua_State *L); void create_sandbox(lua_State *L);
@ -96,7 +87,11 @@ private:
lua_State *lua_state; lua_State *lua_state;
const AP_Int32 & _vm_steps; const AP_Int32 & _vm_steps;
const AP_Int8 & _debug_options; AP_Int8 & _debug_options;
bool option_is_set(AP_Scripting::DebugOption option) const {
return (uint8_t(_debug_options.get()) & uint8_t(option)) != 0;
}
static void *alloc(void *ud, void *ptr, size_t osize, size_t nsize); static void *alloc(void *ud, void *ptr, size_t osize, size_t nsize);