mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_JSON: Ensure all printf() calls end with line break
This commit is contained in:
parent
061823551a
commit
c9f4c47b42
@ -72,7 +72,7 @@ AP_JSON::value *AP_JSON::load_json(const char *filename)
|
||||
|
||||
char *start = strchr(buf, '{');
|
||||
if (!start) {
|
||||
::printf("Invalid json %s", filename);
|
||||
::printf("Invalid json %s\n", filename);
|
||||
delete[] buf;
|
||||
return nullptr;
|
||||
}
|
||||
@ -89,13 +89,13 @@ AP_JSON::value *AP_JSON::load_json(const char *filename)
|
||||
|
||||
AP_JSON::value *obj = new AP_JSON::value;
|
||||
if (obj == nullptr) {
|
||||
::printf("Invalid allocate json for %s", filename);
|
||||
::printf("Invalid allocate json for %s\n", filename);
|
||||
delete[] buf;
|
||||
return nullptr;
|
||||
}
|
||||
std::string err = AP_JSON::parse(*obj, start);
|
||||
if (!err.empty()) {
|
||||
::printf("parse failed for json %s", filename);
|
||||
::printf("parse failed for json %s\n", filename);
|
||||
delete obj;
|
||||
delete[] buf;
|
||||
return nullptr;
|
||||
|
Loading…
Reference in New Issue
Block a user