From 8554081be59bccd5526197b173a4bad2274abf85 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 May 2024 11:24:14 +1000 Subject: [PATCH] AP_RangeFinder: use NEW_NOTHROW for new(std::nothrow) --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 28 +++++++++---------- .../AP_RangeFinder_Ainstein_LR_D1.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_BLPing.h | 2 +- .../AP_RangeFinder_Backend_CAN.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_Bebop.cpp | 2 +- .../AP_RangeFinder_Benewake_TF02.h | 2 +- .../AP_RangeFinder_Benewake_TF03.h | 2 +- .../AP_RangeFinder_Benewake_TFMini.h | 2 +- .../AP_RangeFinder_Benewake_TFMiniPlus.cpp | 2 +- .../AP_RangeFinder_DroneCAN.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_GYUS42v2.h | 2 +- .../AP_RangeFinder_JRE_Serial.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_Lanbao.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_LeddarOne.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_LeddarVu8.h | 2 +- .../AP_RangeFinder_LightWareI2C.cpp | 2 +- .../AP_RangeFinder_LightWareSerial.h | 2 +- .../AP_RangeFinder_MaxsonarI2CXL.cpp | 2 +- .../AP_RangeFinder_MaxsonarSerialLV.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_NMEA.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_NoopLoop.h | 2 +- .../AP_RangeFinder_PulsedLightLRF.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_RDS02UF.h | 2 +- .../AP_RangeFinder_TOFSenseF_I2C.cpp | 2 +- .../AP_RangeFinder_TeraRangerI2C.cpp | 2 +- .../AP_RangeFinder_TeraRanger_Serial.h | 2 +- .../AP_RangeFinder_USD1_Serial.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_Wasp.h | 2 +- 30 files changed, 43 insertions(+), 43 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 0da1912c84..6f1f4a6c26 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -386,14 +386,14 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) // to ease moving from PX4 to ChibiOS we'll lie a little about // the backend driver... if (AP_RangeFinder_PWM::detect()) { - _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } break; #endif #if AP_RANGEFINDER_BBB_PRU_ENABLED case Type::BBB_PRU: if (AP_RangeFinder_BBB_PRU::detect()) { - _add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); } break; #endif @@ -415,14 +415,14 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_BEBOP_ENABLED case Type::BEBOP: if (AP_RangeFinder_Bebop::detect()) { - _add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_Bebop(state[instance], params[instance]), instance); } break; #endif #if AP_RANGEFINDER_MAVLINK_ENABLED case Type::MAVLink: if (AP_RangeFinder_MAVLink::detect()) { - _add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); } break; #endif @@ -435,7 +435,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) case Type::ANALOG: // note that analog will always come back as present if the pin is valid if (AP_RangeFinder_analog::detect(params[instance])) { - _add_backend(new AP_RangeFinder_analog(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_analog(state[instance], params[instance]), instance); } break; #endif @@ -443,7 +443,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) case Type::HC_SR04: // note that this will always come back as present if the pin is valid if (AP_RangeFinder_HC_SR04::detect(params[instance])) { - _add_backend(new AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance); } break; #endif @@ -480,7 +480,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_PWM_ENABLED case Type::PWM: if (AP_RangeFinder_PWM::detect()) { - _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } break; #endif @@ -519,32 +519,32 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_SIM_ENABLED case Type::SIM: - _add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); break; #endif #if HAL_MSP_RANGEFINDER_ENABLED case Type::MSP: if (AP_RangeFinder_MSP::detect()) { - _add_backend(new AP_RangeFinder_MSP(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_MSP(state[instance], params[instance]), instance); } break; #endif // HAL_MSP_RANGEFINDER_ENABLED #if AP_RANGEFINDER_USD1_CAN_ENABLED case Type::USD1_CAN: - _add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED case Type::Benewake_CAN: - _add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_LUA_ENABLED case Type::Lua_Scripting: - _add_backend(new AP_RangeFinder_Lua(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_Lua(state[instance], params[instance]), instance); break; #endif @@ -562,12 +562,12 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED case Type::TOFSenseP_CAN: - _add_backend(new AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_NRA24_CAN_ENABLED case Type::NRA24_CAN: - _add_backend(new AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance); + _add_backend(NEW_NOTHROW AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance); break; #endif #if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h index f39bdea95b..3bf2d348c5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Ainstein_LR_D1.h @@ -22,7 +22,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Ainstein_LR_D1(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Ainstein_LR_D1(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h index 04fccaae4e..c96830997b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h @@ -124,7 +124,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_BLPing(_state, _params); + return NEW_NOTHROW AP_RangeFinder_BLPing(_state, _params); } /** diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp index 659a4af199..ebc60dc2d1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp @@ -45,7 +45,7 @@ AP_RangeFinder_Backend_CAN::AP_RangeFinder_Backend_CAN( { AP_Param::setup_object_defaults(this, var_info); state.var_info = var_info; - multican_rangefinder = new MultiCAN{FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Backend_CAN::handle_frame, bool, AP_HAL::CANFrame &), can_type, driver_name}; + multican_rangefinder = NEW_NOTHROW MultiCAN{FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Backend_CAN::handle_frame, bool, AP_HAL::CANFrame &), can_type, driver_name}; if (multican_rangefinder == nullptr) { AP_BoardConfig::allocation_error("Failed to create rangefinder multican"); } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp index 5d1dd73ff4..043397d1e3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp @@ -64,7 +64,7 @@ static const uint16_t waveform_mode1[32] = { AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : AP_RangeFinder_Backend(_state, _params), - _thread(new Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void))) + _thread(NEW_NOTHROW Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void))) { _init(); _freq = RNFD_BEBOP_DEFAULT_FREQ; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h index f6b62d4ac2..785bbdf0c1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h @@ -13,7 +13,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Benewake_TF02(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Benewake_TF02(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h index 2e2318ae22..82790796a8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h @@ -13,7 +13,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Benewake_TF03(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Benewake_TF03(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h index 451cdfe525..71cd0e8932 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h @@ -13,7 +13,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Benewake_TFMini(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Benewake_TFMini(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp index fc4e227c74..0e3e954816 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp @@ -56,7 +56,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_Benewake_TFMiniPlus::detect( } AP_RangeFinder_Benewake_TFMiniPlus *sensor - = new AP_RangeFinder_Benewake_TFMiniPlus(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_Benewake_TFMiniPlus(_state, _params, std::move(dev)); if (!sensor || !sensor->init()) { delete sensor; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index 4db29571be..94c3aead5a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -60,7 +60,7 @@ AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_dronecan_backend(AP_DroneC //it up as UAVCAN type return nullptr; } - frontend.drivers[i] = new AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]); + frontend.drivers[i] = NEW_NOTHROW AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]); driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i]; if (driver == nullptr) { break; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h index 7347e649e1..4a4363ab1f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h @@ -15,7 +15,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_GYUS42v2(_state, _params); + return NEW_NOTHROW AP_RangeFinder_GYUS42v2(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h index e37030a971..ea44688440 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h @@ -70,7 +70,7 @@ public: RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_JRE_Serial(_state, _params); + return NEW_NOTHROW AP_RangeFinder_JRE_Serial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h index 0a655c5183..8ca44d30f5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h @@ -15,7 +15,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Lanbao(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Lanbao(_state, _params); } // Lanbao is always 115200: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h index 43ee3f09ba..8053c7b496 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h @@ -49,7 +49,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_LeddarOne(_state, _params); + return NEW_NOTHROW AP_RangeFinder_LeddarOne(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h index 68db11394e..b3d71b9098 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h @@ -17,7 +17,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_LeddarVu8(_state, _params); + return NEW_NOTHROW AP_RangeFinder_LeddarVu8(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 725b76f4f6..5e600ca463 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -81,7 +81,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder::RangeFi } AP_RangeFinder_LightWareI2C *sensor - = new AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev)); if (!sensor) { return nullptr; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index 13f4e776cd..632f9534c7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -15,7 +15,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_LightWareSerial(_state, _params); + return NEW_NOTHROW AP_RangeFinder_LightWareSerial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index 1cb7cdc5af..a5aedb1758 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -54,7 +54,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeF } AP_RangeFinder_MaxsonarI2CXL *sensor - = new AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev)); if (!sensor) { return nullptr; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h index b0693c11e3..62ac3de22f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -15,7 +15,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_MaxsonarSerialLV(_state, _params); + return NEW_NOTHROW AP_RangeFinder_MaxsonarSerialLV(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h index d8c7ff3d14..7f18c05916 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h @@ -30,7 +30,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_NMEA(_state, _params); + return NEW_NOTHROW AP_RangeFinder_NMEA(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h index e40fe11dd6..eeedf71cec 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h @@ -14,7 +14,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_NoopLoop(_state, _params); + return NEW_NOTHROW AP_RangeFinder_NoopLoop(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index 608f2492ef..5ceb1925c0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -62,7 +62,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_PulsedLightLRF::detect(uint8_t bus, RangeFinder::Type rftype) { AP_RangeFinder_PulsedLightLRF *sensor - = new AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype); + = NEW_NOTHROW AP_RangeFinder_PulsedLightLRF(bus, _state, _params, rftype); if (!sensor || !sensor->init()) { delete sensor; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h b/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h index e4fc161c09..6b480a1776 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_RDS02UF.h @@ -35,7 +35,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_RDS02UF(_state, _params); + return NEW_NOTHROW AP_RangeFinder_RDS02UF(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp index 55f0e497d6..9c81e4e0c1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp @@ -47,7 +47,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TOFSenseF_I2C::detect(RangeFinder::RangeF } AP_RangeFinder_TOFSenseF_I2C *sensor - = new AP_RangeFinder_TOFSenseF_I2C(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_TOFSenseF_I2C(_state, _params, std::move(dev)); if (!sensor) { return nullptr; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index c1772bfbad..ab63b192dd 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -53,7 +53,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(RangeFinder::RangeF return nullptr; } - AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev)); + AP_RangeFinder_TeraRangerI2C *sensor = NEW_NOTHROW AP_RangeFinder_TeraRangerI2C(_state, _params, std::move(i2c_dev)); if (!sensor) { return nullptr; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h index aba2d08df8..90b65af283 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h @@ -15,7 +15,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_TeraRanger_Serial(_state, _params); + return NEW_NOTHROW AP_RangeFinder_TeraRanger_Serial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h index 3c48c38628..02cbb6e704 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h @@ -15,7 +15,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_USD1_Serial(_state, _params); + return NEW_NOTHROW AP_RangeFinder_USD1_Serial(_state, _params); } protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp index 51c10dec8c..a5f32ce06b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp @@ -229,7 +229,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_VL53L0X::detect(RangeFinder::RangeFinder_ return nullptr; } AP_RangeFinder_VL53L0X *sensor - = new AP_RangeFinder_VL53L0X(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_VL53L0X(_state, _params, std::move(dev)); if (!sensor) { delete sensor; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp index e0eba359ee..c444546239 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp @@ -48,7 +48,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_VL53L1X::detect(RangeFinder::RangeFinder_ } AP_RangeFinder_VL53L1X *sensor - = new AP_RangeFinder_VL53L1X(_state, _params, std::move(dev)); + = NEW_NOTHROW AP_RangeFinder_VL53L1X(_state, _params, std::move(dev)); if (!sensor) { delete sensor; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h index e0a3e15ca2..f70d1b3f4e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h @@ -17,7 +17,7 @@ public: static AP_RangeFinder_Backend_Serial *create( RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) { - return new AP_RangeFinder_Wasp(_state, _params); + return NEW_NOTHROW AP_RangeFinder_Wasp(_state, _params); } void update(void) override;