SITL: remove superfluous linefeed from panic strings

panic adds this within the HAL layer.
This commit is contained in:
Peter Barker 2024-12-13 20:15:45 +11:00 committed by Peter Barker
parent 6fb3e27b8d
commit fea17e6f59
3 changed files with 7 additions and 7 deletions

View File

@ -338,15 +338,15 @@ void Frame::load_frame_params(const char *model_json)
} else { } else {
IGNORE_RETURN(asprintf(&fname, "@ROMFS/models/%s", model_json)); IGNORE_RETURN(asprintf(&fname, "@ROMFS/models/%s", model_json));
if (AP::FS().stat(model_json, &st) != 0) { 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) { 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); AP_JSON::value *obj = AP_JSON::load_json(model_json);
if (obj == nullptr) { 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 { enum class VarType {

View File

@ -37,15 +37,15 @@ void JSON_Master::init(const int32_t num_slaves)
uint16_t port = 9002 + 10 * i; uint16_t port = 9002 + 10 * i;
if (!list->sock_in.reuseaddress()) { 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)) { 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)) { 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); printf("Slave %u: listening on %u\n", list->instance, port);

View File

@ -116,7 +116,7 @@ XPlane::XPlane(const char *frame_str) :
#endif #endif
if (!load_dref_map(XPLANE_JSON)) { 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);
} }
} }