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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:10 +10:00
parent b07e0bf06b
commit 5756b9a3de
2 changed files with 7 additions and 7 deletions

View File

@ -108,25 +108,25 @@ void AP_ExternalAHRS::init(void)
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED #if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
case DevType::VecNav: case DevType::VecNav:
backend = new AP_ExternalAHRS_VectorNav(this, state); backend = NEW_NOTHROW AP_ExternalAHRS_VectorNav(this, state);
return; return;
#endif #endif
#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED #if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED
case DevType::MicroStrain5: case DevType::MicroStrain5:
backend = new AP_ExternalAHRS_MicroStrain5(this, state); backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain5(this, state);
return; return;
#endif #endif
#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED #if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED
case DevType::MicroStrain7: case DevType::MicroStrain7:
backend = new AP_ExternalAHRS_MicroStrain7(this, state); backend = NEW_NOTHROW AP_ExternalAHRS_MicroStrain7(this, state);
return; return;
#endif #endif
#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED #if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED
case DevType::InertialLabs: case DevType::InertialLabs:
backend = new AP_ExternalAHRS_InertialLabs(this, state); backend = NEW_NOTHROW AP_ExternalAHRS_InertialLabs(this, state);
return; return;
#endif #endif

View File

@ -183,9 +183,9 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend,
port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);
bufsize = MAX(MAX(VN_PKT1_LENGTH, VN_PKT2_LENGTH), VN_100_PKT1_LENGTH); bufsize = MAX(MAX(VN_PKT1_LENGTH, VN_PKT2_LENGTH), VN_100_PKT1_LENGTH);
pktbuf = new uint8_t[bufsize]; pktbuf = NEW_NOTHROW uint8_t[bufsize];
last_pkt1 = new VN_packet1; last_pkt1 = NEW_NOTHROW VN_packet1;
last_pkt2 = new VN_packet2; last_pkt2 = NEW_NOTHROW VN_packet2;
if (!pktbuf || !last_pkt1 || !last_pkt2) { if (!pktbuf || !last_pkt1 || !last_pkt2) {
AP_BoardConfig::allocation_error("VectorNav ExternalAHRS"); AP_BoardConfig::allocation_error("VectorNav ExternalAHRS");