Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: correct use-after-free in script statistics #27362

Merged
merged 2 commits into from
Jun 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
44 changes: 44 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -5400,6 +5400,49 @@ def GuidedAttitudeNoGPS(self):
self.context_pop()
self.fly_home_land_and_disarm()

def ScriptStats(self):
'''test script stats logging'''
self.context_push()
self.set_parameters({
'SCR_ENABLE': 1,
'SCR_DEBUG_OPTS': 8, # runtime memory usage and time
})
self.install_test_scripts_context([
"math.lua",
"strings.lua",
])
self.install_example_script_context('simple_loop.lua')
self.context_collect('STATUSTEXT')

self.reboot_sitl()

self.wait_statustext('hello, world')
delay = 20
self.delay_sim_time(delay, reason='gather some stats')
self.wait_statustext("math.lua exceeded time limit", check_context=True, timeout=0)

dfreader = self.dfreader_for_current_onboard_log()
seen_hello_world = False
# runtime = None
while True:
m = dfreader.recv_match(type=['SCR'])
if m is None:
break
if m.Name == "simple_loop.lua":
seen_hello_world = True
# if m.Name == "math.lua":
# runtime = m.Runtime

if not seen_hello_world:
raise NotAchievedException("Did not see simple_loop.lua script")

# self.progress(f"math took {runtime} seconds to run over {delay} seconds")
# if runtime == 0:
# raise NotAchievedException("Expected non-zero runtime for math")

self.context_pop()
self.reboot_sitl()

def tests(self):
'''return list of all tests'''
ret = super(AutoTestPlane, self).tests()
Expand Down Expand Up @@ -5511,6 +5554,7 @@ def tests(self):
self.MinThrottle,
self.ClimbThrottleSaturation,
self.GuidedAttitudeNoGPS,
self.ScriptStats,
])
return ret

Expand Down
11 changes: 9 additions & 2 deletions libraries/AP_Scripting/lua_scripts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -550,8 +550,11 @@ void lua_scripts::run(void) {
if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) {
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name);
}
// copy name for logging, cant do it after as script reschedule moves the pointers
const char * script_name = scripts->name;
// take a copy of the script name for the purposes of
// logging statistics. "scripts" may become invalid
// during the "run_next_script" call, below.
char script_name[128+1] {};
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We only log to a 16 char space, I don't think you need to copy the full thing.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We only log to a 16 char space, I don't think you need to copy the full thing.

Yeah, I thought that too. But the trimming of the directory off the path happens closer to where we log it.

strncpy_noterm(script_name, scripts->name, 128);

#if DISABLE_INTERRUPTS_FOR_SCRIPT_RUN
void *istate = hal.scheduler->disable_interrupts_save();
Expand All @@ -560,6 +563,10 @@ void lua_scripts::run(void) {
const int startMem = lua_gc(L, LUA_GCCOUNT, 0) * 1024 + lua_gc(L, LUA_GCCOUNTB, 0);
const uint32_t loadEnd = AP_HAL::micros();

// NOTE! the base pointer of our scripts linked list,
// *and all its contents* may become invalid as part of
// "run_next_script"! So do *NOT* attempt to access
// anything that was in *scripts after this call.
run_next_script(L);

const uint32_t runEnd = AP_HAL::micros();
Expand Down
Loading