diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index d5435047f9..c3f2fba101 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -338,15 +338,15 @@ void Frame::load_frame_params(const char *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); + AP_HAL::panic("%s failed to load", model_json); } } if (fname == nullptr) { - AP_HAL::panic("%s failed to load\n", model_json); + AP_HAL::panic("%s failed to load", model_json); } AP_JSON::value *obj = AP_JSON::load_json(model_json); if (obj == nullptr) { - AP_HAL::panic("%s failed to load\n", model_json); + AP_HAL::panic("%s failed to load", model_json); } enum class VarType { diff --git a/libraries/SITL/SIM_JSON_Master.cpp b/libraries/SITL/SIM_JSON_Master.cpp index 9b8c3b5906..a6b92591d4 100644 --- a/libraries/SITL/SIM_JSON_Master.cpp +++ b/libraries/SITL/SIM_JSON_Master.cpp @@ -37,15 +37,15 @@ void JSON_Master::init(const int32_t num_slaves) uint16_t port = 9002 + 10 * i; if (!list->sock_in.reuseaddress()) { - AP_HAL::panic("JSON master: socket reuseaddress failed on port: %d - %s\n", port, strerror(errno)); + AP_HAL::panic("JSON master: socket reuseaddress failed on port: %d - %s", port, strerror(errno)); } if (!list->sock_in.bind("127.0.0.1", port)) { - AP_HAL::panic("JSON master: socket reuseaddress failed on port: %d - %s\n", port, strerror(errno)); + AP_HAL::panic("JSON master: socket reuseaddress failed on port: %d - %s", port, strerror(errno)); } if (!list->sock_in.set_blocking(false)) { - AP_HAL::panic( "JSON master: socket set_blocking(false) failed on port: %d - %s\n", port, strerror(errno)); + AP_HAL::panic( "JSON master: socket set_blocking(false) failed on port: %d - %s", port, strerror(errno)); } printf("Slave %u: listening on %u\n", list->instance, port); diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index 3633bb4b1a..e9c147c633 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -116,7 +116,7 @@ XPlane::XPlane(const char *frame_str) : #endif if (!load_dref_map(XPLANE_JSON)) { - AP_HAL::panic("%s failed to load\n", XPLANE_JSON); + AP_HAL::panic("%s failed to load", XPLANE_JSON); } }