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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:09 +10:00
parent 4879cc24e6
commit bac6d6f644
1 changed files with 4 additions and 4 deletions

View File

@ -98,15 +98,15 @@ void AP_Beacon::init(void)
// create backend
if (_type == AP_BeaconType_Pozyx) {
_driver = new AP_Beacon_Pozyx(*this);
_driver = NEW_NOTHROW AP_Beacon_Pozyx(*this);
} else if (_type == AP_BeaconType_Marvelmind) {
_driver = new AP_Beacon_Marvelmind(*this);
_driver = NEW_NOTHROW AP_Beacon_Marvelmind(*this);
} else if (_type == AP_BeaconType_Nooploop) {
_driver = new AP_Beacon_Nooploop(*this);
_driver = NEW_NOTHROW AP_Beacon_Nooploop(*this);
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_type == AP_BeaconType_SITL) {
_driver = new AP_Beacon_SITL(*this);
_driver = NEW_NOTHROW AP_Beacon_SITL(*this);
}
#endif
}