Browse Source

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.
zr-v5.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
0661a27400
  1. 3
      libraries/SITL/SIM_Frame.cpp

3
libraries/SITL/SIM_Frame.cpp

@ -333,6 +333,9 @@ void Frame::load_frame_params(const char *model_json) @@ -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…
Cancel
Save