mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
SITL: ensure st.size is valid when loading model json
Before this patch st.size is undefined when we use it to create a buffer on the stack - probably not a good thing.
This commit is contained in:
parent
ff02e619da
commit
0661a27400
@ -333,6 +333,9 @@ void Frame::load_frame_params(const char *model_json)
|
||||
fname = strdup(model_json);
|
||||
} else {
|
||||
IGNORE_RETURN(asprintf(&fname, "@ROMFS/models/%s", model_json));
|
||||
if (AP::FS().stat(model_json, &st) != 0) {
|
||||
AP_HAL::panic("%s failed to load\n", model_json);
|
||||
}
|
||||
}
|
||||
if (fname == nullptr) {
|
||||
AP_HAL::panic("%s failed to load\n", model_json);
|
||||
|
Loading…
Reference in New Issue
Block a user