diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index b61db7fc7c..4e24bfded2 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -247,7 +247,7 @@ void AP_Logger::init(const AP_Int32 &log_bitmask, const struct LogStructure *str return; } LoggerMessageWriter_DFLogStart *message_writer = - new LoggerMessageWriter_DFLogStart(); + NEW_NOTHROW LoggerMessageWriter_DFLogStart(); if (message_writer == nullptr) { AP_BoardConfig::allocation_error("message writer"); } @@ -714,7 +714,7 @@ void AP_Logger::save_format_Replay(const void *pBuffer) { if (((uint8_t *)pBuffer)[2] == LOG_FORMAT_MSG) { struct log_Format *fmt = (struct log_Format *)pBuffer; - struct log_write_fmt *f = new log_write_fmt; + struct log_write_fmt *f = NEW_NOTHROW log_write_fmt; f->msg_type = fmt->type; f->msg_len = fmt->length; f->name = strndup(fmt->name, sizeof(fmt->name)); @@ -1639,13 +1639,13 @@ void AP_Logger::log_file_content(const char *filename) void AP_Logger::log_file_content(FileContent &file_content, const char *filename) { WITH_SEMAPHORE(file_content.sem); - auto *file = new file_list; + auto *file = NEW_NOTHROW file_list; if (file == nullptr) { return; } // make copy to allow original to go out of scope const size_t len = strlen(filename)+1; - char * tmp_filename = new char[len]; + char * tmp_filename = NEW_NOTHROW char[len]; if (tmp_filename == nullptr) { delete file; return; diff --git a/libraries/AP_Logger/AP_Logger_Block.cpp b/libraries/AP_Logger/AP_Logger_Block.cpp index c0966f7ec6..7472290727 100644 --- a/libraries/AP_Logger/AP_Logger_Block.cpp +++ b/libraries/AP_Logger/AP_Logger_Block.cpp @@ -314,7 +314,7 @@ void AP_Logger_Block::periodic_1Hz() _front._params.disarm_ratemax > 0 || _front._log_pause)) { // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested - rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.blk_ratemax, _front._params.disarm_ratemax); + rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.blk_ratemax, _front._params.disarm_ratemax); } if (!io_thread_alive()) { diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 3208f8cf6e..e4db560c71 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -173,7 +173,7 @@ void AP_Logger_File::periodic_1Hz() _front._params.disarm_ratemax > 0 || _front._log_pause)) { // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested - rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.file_ratemax, _front._params.disarm_ratemax); + rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.file_ratemax, _front._params.disarm_ratemax); } } diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 038324e92e..8ca4259a1f 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -26,7 +26,7 @@ public: static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_File(front, ls); + return NEW_NOTHROW AP_Logger_File(front, ls); } // initialisation diff --git a/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h b/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h index 43c0b37665..c51ae1b3d2 100644 --- a/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h +++ b/libraries/AP_Logger/AP_Logger_Flash_JEDEC.h @@ -15,7 +15,7 @@ public: AP_Logger_Block(front, writer) {} static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_Flash_JEDEC(front, ls); + return NEW_NOTHROW AP_Logger_Flash_JEDEC(front, ls); } void Init(void) override; bool CardInserted() const override { return !flash_died && df_NumPages > 0; } diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.cpp b/libraries/AP_Logger/AP_Logger_MAVLink.cpp index 7d48b4afca..5c41ae2d3b 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLink.cpp @@ -545,7 +545,7 @@ void AP_Logger_MAVLink::periodic_1Hz() _front._params.disarm_ratemax > 0 || _front._log_pause)) { // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested - rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.mav_ratemax, _front._params.disarm_ratemax); + rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.mav_ratemax, _front._params.disarm_ratemax); } if (_sending_to_client && diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.h b/libraries/AP_Logger/AP_Logger_MAVLink.h index 4ae7202ff4..13155e6da7 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.h +++ b/libraries/AP_Logger/AP_Logger_MAVLink.h @@ -21,7 +21,7 @@ public: static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_MAVLink(front, ls); + return NEW_NOTHROW AP_Logger_MAVLink(front, ls); } // initialisation diff --git a/libraries/AP_Logger/AP_Logger_W25NXX.h b/libraries/AP_Logger/AP_Logger_W25NXX.h index 885800e913..5e7c8d7fb4 100644 --- a/libraries/AP_Logger/AP_Logger_W25NXX.h +++ b/libraries/AP_Logger/AP_Logger_W25NXX.h @@ -15,7 +15,7 @@ public: AP_Logger_Block(front, writer) {} static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_W25NXX(front, ls); + return NEW_NOTHROW AP_Logger_W25NXX(front, ls); } void Init(void) override; bool CardInserted() const override { return !flash_died && df_NumPages > 0; }