AP_Scripting: add checksum of running and loaded scripts with arming check

This commit is contained in:
Iampete1 2023-11-25 17:18:37 +00:00 committed by Andrew Tridgell
parent 423a218643
commit 2a3a5b2804
4 changed files with 125 additions and 3 deletions

View File

@ -84,7 +84,12 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = {
// @Param: DEBUG_OPTS
// @DisplayName: Scripting Debug Level
// @Description: Debugging options
// @Bitmask: 0:No Scripts to run message if all scripts have stopped, 1:Runtime messages for memory usage and execution time, 2:Suppress logging scripts to dataflash, 3:log runtime memory usage and execution time, 4:Disable pre-arm check
// @Bitmask: 0: No Scripts to run message if all scripts have stopped
// @Bitmask: 1: Runtime messages for memory usage and execution time
// @Bitmask: 2: Suppress logging scripts to dataflash
// @Bitmask: 3: log runtime memory usage and execution time
// @Bitmask: 4: Disable pre-arm check
// @Bitmask: 5: Save CRC of current scripts to loaded and running checksum parameters enabling pre-arm
// @User: Advanced
AP_GROUPINFO("DEBUG_OPTS", 4, AP_Scripting, _debug_options, 0),
@ -132,6 +137,18 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = {
// @User: Advanced
AP_GROUPINFO("DIR_DISABLE", 9, AP_Scripting, _dir_disable, 0),
// @Param: LD_CHECKSUM
// @DisplayName: Loaded script checksum
// @Description: Required XOR of CRC32 checksum of loaded scripts, vehicle will not arm with incorrect scripts loaded, -1 disables
// @User: Advanced
AP_GROUPINFO("LD_CHECKSUM", 12, AP_Scripting, _required_loaded_checksum, -1),
// @Param: RUN_CHECKSUM
// @DisplayName: Running script checksum
// @Description: Required XOR of CRC32 checksum of running scripts, vehicle will not arm with incorrect scripts running, -1 disables
// @User: Advanced
AP_GROUPINFO("RUN_CHECKSUM", 13, AP_Scripting, _required_running_checksum, -1),
AP_GROUPEND
};
@ -357,6 +374,25 @@ bool AP_Scripting::arming_checks(size_t buflen, char *buffer) const
}
lua_scripts::get_last_error_semaphore()->give();
// Use -1 for disabled, this means we don't have to avoid 0 in the CRC, the sign bit is masked off anyway
if (_required_loaded_checksum != -1) {
const uint32_t expected_loaded = (uint32_t)_required_loaded_checksum.get() & checksum_param_mask;
const uint32_t loaded = lua_scripts::get_loaded_checksum() & checksum_param_mask;
if (expected_loaded != loaded) {
hal.util->snprintf(buffer, buflen, "Scripting: loaded CRC incorrect want: 0x%x", (unsigned int)loaded);
return false;
}
}
if (_required_running_checksum != -1) {
const uint32_t expected_running = (uint32_t)_required_running_checksum.get() & checksum_param_mask;
const uint32_t running = lua_scripts::get_running_checksum() & checksum_param_mask;
if (expected_running != running) {
hal.util->snprintf(buffer, buflen, "Scripting: running CRC incorrect want: 0x%x", (unsigned int)running);
return false;
}
}
return true;
}
@ -403,6 +439,34 @@ bool AP_Scripting::is_handling_command(uint16_t cmd_id)
}
#endif // HAL_GCS_ENABLED
// Update called at 1Hz from AP_Vehicle
void AP_Scripting::update() {
save_checksum();
}
// Check if DEBUG_OPTS bit has been set to save current checksum values to params
void AP_Scripting::save_checksum() {
const uint8_t opts = _debug_options.get();
const uint8_t save_bit = uint8_t(lua_scripts::DebugLevel::SAVE_CHECKSUM);
if ((opts & save_bit) == 0) {
// Bit not set, nothing to do
return;
}
// Save two checksum parameters to there current values
_required_loaded_checksum.set_and_save(lua_scripts::get_loaded_checksum() & checksum_param_mask);
_required_running_checksum.set_and_save(lua_scripts::get_running_checksum() & checksum_param_mask);
// Un-set debug option bit
_debug_options.set_and_save(opts & ~save_bit);
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "saved checksums");
}
AP_Scripting *AP_Scripting::_singleton = nullptr;
namespace AP {

View File

@ -41,6 +41,8 @@ public:
void init(void);
void update();
bool enabled(void) const { return _enable != 0; };
bool should_run(void) const { return enabled() && !_stop; }
@ -134,15 +136,23 @@ private:
bool repl_start(void);
void repl_stop(void);
void load_script(const char *filename); // load a script from a file
void thread(void); // main script execution thread
// Check if DEBUG_OPTS bit has been set to save current checksum values to params
void save_checksum();
// Mask down to 23 bits for comparison with parameters, this the length of the a float mantissa, to deal with the float transport of parameters over MAVLink
// The full range of uint32 integers cannot be represented by a float.
const uint32_t checksum_param_mask = 0x007FFFFF;
AP_Int8 _enable;
AP_Int32 _script_vm_exec_count;
AP_Int32 _script_heap_size;
AP_Int8 _debug_options;
AP_Int16 _dir_disable;
AP_Int32 _required_loaded_checksum;
AP_Int32 _required_running_checksum;
bool _thread_failed; // thread allocation failed
bool _init_failed; // true if memory allocation failed

View File

@ -36,6 +36,10 @@ HAL_Semaphore lua_scripts::error_msg_buf_sem;
uint8_t lua_scripts::print_error_count;
uint32_t lua_scripts::last_print_ms;
uint32_t lua_scripts::loaded_checksum;
uint32_t lua_scripts::running_checksum;
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, struct AP_Scripting::terminal_s &_terminal)
: _vm_steps(vm_steps),
_debug_options(debug_options),
@ -199,6 +203,19 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *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
// Get checksum of file
uint32_t crc = 0;
if (AP::FS().crc32(filename, crc)) {
// Record crc of this script
new_script->crc = crc;
{
// Apply crc to checksum of all scripts
WITH_SEMAPHORE(crc_sem);
loaded_checksum ^= crc;
running_checksum ^= crc;
}
}
return new_script;
}
@ -391,6 +408,13 @@ void lua_scripts::remove_script(lua_State *L, script_info *script) {
}
_heap.deallocate(script->name);
_heap.deallocate(script);
{
// Remove from running checksum
WITH_SEMAPHORE(crc_sem);
running_checksum ^= script->crc;
}
}
void lua_scripts::reschedule_script(script_info *script) {
@ -606,4 +630,17 @@ void lua_scripts::run(void) {
error_msg_buf_sem.give();
}
// Return the file checksums of running and loaded scripts
uint32_t lua_scripts::get_loaded_checksum()
{
WITH_SEMAPHORE(crc_sem);
return loaded_checksum;
}
uint32_t lua_scripts::get_running_checksum()
{
WITH_SEMAPHORE(crc_sem);
return running_checksum;
}
#endif // AP_SCRIPTING_ENABLED

View File

@ -54,6 +54,7 @@ public:
SUPPRESS_SCRIPT_LOG = 1U << 2,
LOG_RUNTIME = 1U << 3,
DISABLE_PRE_ARM = 1U << 4,
SAVE_CHECKSUM = 1U << 5,
};
private:
@ -64,6 +65,7 @@ private:
typedef struct script_info {
int lua_ref; // reference to the loaded script object
uint64_t next_run_ms; // time (in milliseconds) the script should next be run at
uint32_t crc; // crc32 checksum
char *name; // filename for the script // FIXME: This information should be available from Lua
script_info *next;
} script_info;
@ -125,6 +127,11 @@ private:
static uint32_t last_print_ms;
int current_ref;
// XOR of crc32 of running scripts
static uint32_t loaded_checksum;
static uint32_t running_checksum;
static HAL_Semaphore crc_sem;
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);
@ -135,6 +142,10 @@ public:
// get semaphore for above error buffer
static AP_HAL::Semaphore* get_last_error_semaphore() { return &error_msg_buf_sem; }
// Return the file checksums of running and loaded scripts
static uint32_t get_loaded_checksum();
static uint32_t get_running_checksum();
};
#endif // AP_SCRIPTING_ENABLED