AP_Scripting: add arming check for failed scripts

This commit is contained in:
Iampete1 2022-08-28 20:24:21 +01:00 committed by Andrew Tridgell
parent c5c09860da
commit e2c29b09ab
4 changed files with 35 additions and 8 deletions

View File

@ -154,9 +154,8 @@ void AP_Scripting::init(void) {
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Scripting::thread, void),
"Scripting", SCRIPTING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_SCRIPTING, 0)) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Could not create scripting stack (%d)", SCRIPTING_STACK_SIZE);
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start");
_init_failed = true;
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start");
_thread_failed = true;
}
}
@ -222,6 +221,7 @@ void AP_Scripting::thread(void) {
// reset flags
_stop = false;
_restart = false;
_init_failed = false;
lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options, terminal);
if (lua == nullptr || !lua->heap_allocated()) {
@ -281,6 +281,31 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd
mission_data->push(cmd);
}
bool AP_Scripting::arming_checks(size_t buflen, char *buffer) const
{
if (!enabled()) {
return true;
}
if (_thread_failed) {
hal.util->snprintf(buffer, buflen, "Scripting: %s", "failed to start");
return false;
}
if (_init_failed) {
hal.util->snprintf(buffer, buflen, "Scripting: %s", "out of memory");
return false;
}
const char *error_buf = lua_scripts::get_last_error_message();
if (error_buf != nullptr) {
hal.util->snprintf(buffer, buflen, "Scripting: %s", error_buf);
return false;
}
return true;
}
AP_Scripting *AP_Scripting::_singleton = nullptr;
namespace AP {

View File

@ -38,7 +38,6 @@ public:
AP_Scripting &operator=(const AP_Scripting&) = delete;
void init(void);
bool init_failed(void) const { return _init_failed; }
bool enabled(void) const { return _enable != 0; };
bool should_run(void) const { return enabled() && !_stop; }
@ -51,6 +50,8 @@ public:
void handle_mission_command(const class AP_Mission::Mission_Command& cmd);
bool arming_checks(size_t buflen, char *buffer) const;
// User parameters for inputs into scripts
AP_Float _user[6];
@ -102,6 +103,7 @@ private:
AP_Int8 _debug_options;
AP_Int16 _dir_disable;
bool _thread_failed; // thread allocation failed
bool _init_failed; // true if memory allocation failed
bool _restart; // true if scripts should be restarted
bool _stop; // true if scripts should be stopped

View File

@ -531,12 +531,9 @@ void lua_scripts::run(void) {
// re-print the latest error message every 10 seconds 10 times
const uint8_t error_prints = 10;
if ((print_error_count < error_prints) && (AP_HAL::millis() - last_print_ms > 10000)) {
// note that we do not clear the buffer after we have finished printing, this allows it to be used for a pre-arm check
print_error(MAV_SEVERITY_DEBUG);
print_error_count++;
if ((print_error_count >= error_prints) && (error_msg_buf != nullptr)) {
hal.util->heap_realloc(_heap, error_msg_buf, 0);
error_msg_buf = nullptr;
}
}
}

View File

@ -141,4 +141,7 @@ public:
// must be static for use in atpanic, public to allow bindings to issue none fatal warnings
static void set_and_print_new_error_message(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(2,3);
// return last error message, nullptr if none
static const char* get_last_error_message() { return error_msg_buf; }
};