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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:09 +10:00
parent 715e8346a6
commit 54017b820b
1 changed files with 1 additions and 1 deletions

View File

@ -167,7 +167,7 @@ AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)
// can only have one
return nullptr;
}
_view = new AP_AHRS_View(*this, rotation, pitch_trim_deg);
_view = NEW_NOTHROW AP_AHRS_View(*this, rotation, pitch_trim_deg);
return _view;
}