AP_Filesystem: use NEW_NOTHROW for new(std::nothrow)

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:11 +10:00
parent 4da9c245d1
commit a241b13f45
8 changed files with 11 additions and 11 deletions

View File

@ -208,7 +208,7 @@ AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname)
}
const Backend &backend = backend_by_path(pathname);
DirHandle *h = new DirHandle;
DirHandle *h = NEW_NOTHROW DirHandle;
if (!h) {
return nullptr;
}

View File

@ -706,7 +706,7 @@ void *AP_Filesystem_FATFS::opendir(const char *pathdir)
CHECK_REMOUNT_NULL();
debug("Opendir %s", pathdir);
struct DIR_Wrapper *ret = new DIR_Wrapper;
struct DIR_Wrapper *ret = NEW_NOTHROW DIR_Wrapper;
if (!ret) {
return nullptr;
}

View File

@ -70,7 +70,7 @@ int AP_Filesystem_Mission::open(const char *fname, int flags, bool allow_absolut
r.num_items = get_num_items(r.mtype);
if (!readonly) {
// setup for upload
r.writebuf = new ExpandingString();
r.writebuf = NEW_NOTHROW ExpandingString();
} else {
r.writebuf = nullptr;
}
@ -464,7 +464,7 @@ bool AP_Filesystem_Mission::finish_upload_fence(const struct header &hdr, const
// passing nullptr and 0 items through to Polyfence loader is
// absolutely OK:
if (hdr.num_items != 0) {
new_items = new AC_PolyFenceItem[hdr.num_items];
new_items = NEW_NOTHROW AC_PolyFenceItem[hdr.num_items];
if (new_items == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Out of memory for upload");
goto OUT;

View File

@ -50,7 +50,7 @@ int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_
}
struct rfile &r = file[idx];
if (read_only) {
r.cursors = new cursor[num_cursors];
r.cursors = NEW_NOTHROW cursor[num_cursors];
if (r.cursors == nullptr) {
errno = ENOMEM;
return -1;
@ -66,7 +66,7 @@ int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_
r.writebuf = nullptr;
if (!read_only) {
// setup for upload
r.writebuf = new ExpandingString();
r.writebuf = NEW_NOTHROW ExpandingString();
if (r.writebuf == nullptr) {
close(idx);
errno = ENOMEM;

View File

@ -245,7 +245,7 @@ bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_s
*/
FileData *AP_Filesystem_ROMFS::load_file(const char *filename)
{
FileData *fd = new FileData(this);
FileData *fd = NEW_NOTHROW FileData(this);
if (!fd) {
return nullptr;
}

View File

@ -83,7 +83,7 @@ int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_pa
return -1;
}
struct rfile &r = file[idx];
r.str = new ExpandingString;
r.str = NEW_NOTHROW ExpandingString;
if (r.str == nullptr) {
errno = ENOMEM;
return -1;
@ -229,7 +229,7 @@ void *AP_Filesystem_Sys::opendir(const char *pathname)
errno = ENOENT;
return nullptr;
}
DirReadTracker *dtracker = new DirReadTracker;
DirReadTracker *dtracker = NEW_NOTHROW DirReadTracker;
if (dtracker == nullptr) {
errno = ENOMEM;
return nullptr;

View File

@ -29,7 +29,7 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename)
if (stat(filename, &st) != 0) {
return nullptr;
}
FileData *fd = new FileData(this);
FileData *fd = NEW_NOTHROW FileData(this);
if (fd == nullptr) {
return nullptr;
}

View File

@ -70,7 +70,7 @@ static int posix_fopen_modes_to_open(const char *mode)
APFS_FILE *apfs_fopen(const char *pathname, const char *mode)
{
APFS_FILE *f = new APFS_FILE;
APFS_FILE *f = NEW_NOTHROW APFS_FILE;
if (!f) {
return nullptr;
}