mirror of https://github.com/ArduPilot/ardupilot
AP_JSON: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
2e6c5157e6
commit
6962c4080d
|
@ -56,7 +56,7 @@ AP_JSON::value *AP_JSON::load_json(const char *filename)
|
||||||
::printf("failed to open json %s\n", filename);
|
::printf("failed to open json %s\n", filename);
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
char *buf = new char[st.st_size+1];
|
char *buf = NEW_NOTHROW char[st.st_size+1];
|
||||||
if (buf == nullptr) {
|
if (buf == nullptr) {
|
||||||
AP::FS().close(fd);
|
AP::FS().close(fd);
|
||||||
::printf("failed to allocate json %s\n", filename);
|
::printf("failed to allocate json %s\n", filename);
|
||||||
|
@ -87,7 +87,7 @@ AP_JSON::value *AP_JSON::load_json(const char *filename)
|
||||||
} while (*p != '\n' && *p != '\r' && *p);
|
} while (*p != '\n' && *p != '\r' && *p);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value *obj = new AP_JSON::value;
|
AP_JSON::value *obj = NEW_NOTHROW AP_JSON::value;
|
||||||
if (obj == nullptr) {
|
if (obj == nullptr) {
|
||||||
::printf("Invalid allocate json for %s\n", filename);
|
::printf("Invalid allocate json for %s\n", filename);
|
||||||
delete[] buf;
|
delete[] buf;
|
||||||
|
@ -133,9 +133,9 @@ AP_JSON::value::value(int type, bool) : type_(type), u_()
|
||||||
break
|
break
|
||||||
INIT(boolean_, false);
|
INIT(boolean_, false);
|
||||||
INIT(number_, 0.0);
|
INIT(number_, 0.0);
|
||||||
INIT(string_, new std::string());
|
INIT(string_, NEW_NOTHROW std::string());
|
||||||
INIT(array_, new array());
|
INIT(array_, NEW_NOTHROW array());
|
||||||
INIT(object_, new object());
|
INIT(object_, NEW_NOTHROW object());
|
||||||
#undef INIT
|
#undef INIT
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
|
@ -154,42 +154,42 @@ AP_JSON::value::value(double n) : type_(number_type), u_()
|
||||||
|
|
||||||
AP_JSON::value::value(const std::string &s) : type_(string_type), u_()
|
AP_JSON::value::value(const std::string &s) : type_(string_type), u_()
|
||||||
{
|
{
|
||||||
u_.string_ = new std::string(s);
|
u_.string_ = NEW_NOTHROW std::string(s);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(const array &a) : type_(array_type), u_()
|
AP_JSON::value::value(const array &a) : type_(array_type), u_()
|
||||||
{
|
{
|
||||||
u_.array_ = new array(a);
|
u_.array_ = NEW_NOTHROW array(a);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(const object &o) : type_(object_type), u_()
|
AP_JSON::value::value(const object &o) : type_(object_type), u_()
|
||||||
{
|
{
|
||||||
u_.object_ = new object(o);
|
u_.object_ = NEW_NOTHROW object(o);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(std::string &&s) : type_(string_type), u_()
|
AP_JSON::value::value(std::string &&s) : type_(string_type), u_()
|
||||||
{
|
{
|
||||||
u_.string_ = new std::string(std::move(s));
|
u_.string_ = NEW_NOTHROW std::string(std::move(s));
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(array &&a) : type_(array_type), u_()
|
AP_JSON::value::value(array &&a) : type_(array_type), u_()
|
||||||
{
|
{
|
||||||
u_.array_ = new array(std::move(a));
|
u_.array_ = NEW_NOTHROW array(std::move(a));
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(object &&o) : type_(object_type), u_()
|
AP_JSON::value::value(object &&o) : type_(object_type), u_()
|
||||||
{
|
{
|
||||||
u_.object_ = new object(std::move(o));
|
u_.object_ = NEW_NOTHROW object(std::move(o));
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(const char *s) : type_(string_type), u_()
|
AP_JSON::value::value(const char *s) : type_(string_type), u_()
|
||||||
{
|
{
|
||||||
u_.string_ = new std::string(s);
|
u_.string_ = NEW_NOTHROW std::string(s);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_JSON::value::value(const char *s, size_t len) : type_(string_type), u_()
|
AP_JSON::value::value(const char *s, size_t len) : type_(string_type), u_()
|
||||||
{
|
{
|
||||||
u_.string_ = new std::string(s, len);
|
u_.string_ = NEW_NOTHROW std::string(s, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_JSON::value::clear()
|
void AP_JSON::value::clear()
|
||||||
|
@ -220,9 +220,9 @@ AP_JSON::value::value(const value &x) : type_(x.type_), u_()
|
||||||
case p##type: \
|
case p##type: \
|
||||||
u_.p = v; \
|
u_.p = v; \
|
||||||
break
|
break
|
||||||
INIT(string_, new std::string(*x.u_.string_));
|
INIT(string_, NEW_NOTHROW std::string(*x.u_.string_));
|
||||||
INIT(array_, new array(*x.u_.array_));
|
INIT(array_, NEW_NOTHROW array(*x.u_.array_));
|
||||||
INIT(object_, new object(*x.u_.object_));
|
INIT(object_, NEW_NOTHROW object(*x.u_.object_));
|
||||||
#undef INIT
|
#undef INIT
|
||||||
default:
|
default:
|
||||||
u_ = x.u_;
|
u_ = x.u_;
|
||||||
|
@ -291,9 +291,9 @@ GET(double, u_.number_)
|
||||||
setter \
|
setter \
|
||||||
}
|
}
|
||||||
SET(bool, boolean, u_.boolean_ = _val;)
|
SET(bool, boolean, u_.boolean_ = _val;)
|
||||||
SET(std::string, string, u_.string_ = new std::string(_val);)
|
SET(std::string, string, u_.string_ = NEW_NOTHROW std::string(_val);)
|
||||||
SET(array, array, u_.array_ = new array(_val);)
|
SET(array, array, u_.array_ = NEW_NOTHROW array(_val);)
|
||||||
SET(object, object, u_.object_ = new object(_val);)
|
SET(object, object, u_.object_ = NEW_NOTHROW object(_val);)
|
||||||
SET(double, number, u_.number_ = _val;)
|
SET(double, number, u_.number_ = _val;)
|
||||||
#undef SET
|
#undef SET
|
||||||
|
|
||||||
|
@ -303,9 +303,9 @@ SET(double, number, u_.number_ = _val;)
|
||||||
type_ = jtype##_type; \
|
type_ = jtype##_type; \
|
||||||
setter \
|
setter \
|
||||||
}
|
}
|
||||||
MOVESET(std::string, string, u_.string_ = new std::string(std::move(_val));)
|
MOVESET(std::string, string, u_.string_ = NEW_NOTHROW std::string(std::move(_val));)
|
||||||
MOVESET(array, array, u_.array_ = new array(std::move(_val));)
|
MOVESET(array, array, u_.array_ = NEW_NOTHROW array(std::move(_val));)
|
||||||
MOVESET(object, object, u_.object_ = new object(std::move(_val));)
|
MOVESET(object, object, u_.object_ = NEW_NOTHROW object(std::move(_val));)
|
||||||
#undef MOVESET
|
#undef MOVESET
|
||||||
|
|
||||||
bool AP_JSON::value::evaluate_as_boolean() const
|
bool AP_JSON::value::evaluate_as_boolean() const
|
||||||
|
|
Loading…
Reference in New Issue