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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:13 +10:00
parent ad6502c9f1
commit e180359757
1 changed files with 2 additions and 2 deletions

View File

@ -261,11 +261,11 @@ Menu::_allocate_buffers(void)
{
/* only allocate if the buffers are nullptr */
if (_inbuf == nullptr) {
_inbuf = new char[_commandline_max];
_inbuf = NEW_NOTHROW char[_commandline_max];
memset(_inbuf, 0, _commandline_max);
}
if (_argv == nullptr) {
_argv = new arg[_args_max+1];
_argv = NEW_NOTHROW arg[_args_max+1];
memset(_argv, 0, (_args_max+1) * sizeof(_argv[0]));
}
}