From 4e1b2b95d480e4816f020c15e311aa6798111d5d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 May 2024 11:24:16 +1000 Subject: [PATCH] SITL: use NEW_NOTHROW for new(std::nothrow) --- libraries/SITL/SIM_AirSim.h | 2 +- libraries/SITL/SIM_BalanceBot.h | 2 +- libraries/SITL/SIM_Balloon.h | 2 +- libraries/SITL/SIM_Blimp.h | 2 +- libraries/SITL/SIM_CRRCSim.h | 2 +- libraries/SITL/SIM_Calibration.h | 2 +- libraries/SITL/SIM_FlightAxis.cpp | 2 +- libraries/SITL/SIM_FlightAxis.h | 2 +- libraries/SITL/SIM_GPS.cpp | 16 ++++++++-------- libraries/SITL/SIM_GPS_FILE.cpp | 2 +- libraries/SITL/SIM_Gazebo.h | 2 +- libraries/SITL/SIM_Glider.h | 2 +- libraries/SITL/SIM_Helicopter.cpp | 2 +- libraries/SITL/SIM_Helicopter.h | 2 +- libraries/SITL/SIM_JSBSim.h | 2 +- libraries/SITL/SIM_JSON.h | 2 +- libraries/SITL/SIM_JSON_Master.cpp | 2 +- libraries/SITL/SIM_LM2755.cpp | 6 +++--- libraries/SITL/SIM_LP5562.cpp | 6 +++--- libraries/SITL/SIM_Morse.cpp | 4 ++-- libraries/SITL/SIM_Morse.h | 2 +- libraries/SITL/SIM_MotorBoat.h | 2 +- libraries/SITL/SIM_Multicopter.h | 2 +- libraries/SITL/SIM_NoVehicle.h | 2 +- libraries/SITL/SIM_Plane.h | 2 +- libraries/SITL/SIM_QuadPlane.h | 2 +- libraries/SITL/SIM_RGBLED.cpp | 2 +- libraries/SITL/SIM_Rover.h | 2 +- libraries/SITL/SIM_Sailboat.h | 2 +- libraries/SITL/SIM_Scrimmage.h | 2 +- libraries/SITL/SIM_SerialDevice.cpp | 4 ++-- libraries/SITL/SIM_SilentWings.h | 2 +- libraries/SITL/SIM_SingleCopter.h | 2 +- libraries/SITL/SIM_StratoBlimp.h | 2 +- libraries/SITL/SIM_Submarine.h | 2 +- libraries/SITL/SIM_Tracker.h | 2 +- libraries/SITL/SIM_Webots.cpp | 2 +- libraries/SITL/SIM_Webots.h | 2 +- libraries/SITL/SIM_Webots_Python.h | 2 +- libraries/SITL/SIM_XPlane.cpp | 6 +++--- libraries/SITL/SIM_XPlane.h | 2 +- libraries/SITL/SIM_last_letter.h | 2 +- libraries/SITL/ServoModel.cpp | 2 +- 43 files changed, 58 insertions(+), 58 deletions(-) diff --git a/libraries/SITL/SIM_AirSim.h b/libraries/SITL/SIM_AirSim.h index 1e9b75c0e6..151a4fcb32 100644 --- a/libraries/SITL/SIM_AirSim.h +++ b/libraries/SITL/SIM_AirSim.h @@ -44,7 +44,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new AirSim(frame_str); + return NEW_NOTHROW AirSim(frame_str); } /* Create and set in/out socket for Airsim simulator */ diff --git a/libraries/SITL/SIM_BalanceBot.h b/libraries/SITL/SIM_BalanceBot.h index be7e88ebb8..705edfd3b4 100644 --- a/libraries/SITL/SIM_BalanceBot.h +++ b/libraries/SITL/SIM_BalanceBot.h @@ -31,7 +31,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new BalanceBot(frame_str); + return NEW_NOTHROW BalanceBot(frame_str); } private: diff --git a/libraries/SITL/SIM_Balloon.h b/libraries/SITL/SIM_Balloon.h index 081bb36be3..77e0d18207 100644 --- a/libraries/SITL/SIM_Balloon.h +++ b/libraries/SITL/SIM_Balloon.h @@ -34,7 +34,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Balloon(frame_str); + return NEW_NOTHROW Balloon(frame_str); } private: diff --git a/libraries/SITL/SIM_Blimp.h b/libraries/SITL/SIM_Blimp.h index 1cdfc504df..0a01cd3a74 100644 --- a/libraries/SITL/SIM_Blimp.h +++ b/libraries/SITL/SIM_Blimp.h @@ -51,7 +51,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Blimp(frame_str); + return NEW_NOTHROW Blimp(frame_str); } protected: diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index b3a5699f99..47e91ed020 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -44,7 +44,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new CRRCSim(frame_str); + return NEW_NOTHROW CRRCSim(frame_str); } private: diff --git a/libraries/SITL/SIM_Calibration.h b/libraries/SITL/SIM_Calibration.h index f2ded133fb..a60d31826d 100644 --- a/libraries/SITL/SIM_Calibration.h +++ b/libraries/SITL/SIM_Calibration.h @@ -69,7 +69,7 @@ public: void update(const struct sitl_input &input) override; static Aircraft *create(const char *frame_str) { - return new Calibration(frame_str); + return NEW_NOTHROW Calibration(frame_str); } private: diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index d60793c006..b2aff331f8 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -592,7 +592,7 @@ void FlightAxis::socket_creator(void) pthread_cond_wait(&sockcond2, &sockmtx); } pthread_mutex_unlock(&sockmtx); - auto *sck = new SocketAPM_native(false); + auto *sck = NEW_NOTHROW SocketAPM_native(false); if (sck == nullptr) { usleep(500); continue; diff --git a/libraries/SITL/SIM_FlightAxis.h b/libraries/SITL/SIM_FlightAxis.h index 0567997e1f..c8fcd97c19 100644 --- a/libraries/SITL/SIM_FlightAxis.h +++ b/libraries/SITL/SIM_FlightAxis.h @@ -44,7 +44,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new FlightAxis(frame_str); + return NEW_NOTHROW FlightAxis(frame_str); } struct state { diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 15eafb90b0..f95d5922c3 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -234,49 +234,49 @@ void GPS::check_backend_allocation() #if AP_SIM_GPS_UBLOX_ENABLED case Type::UBLOX: - backend = new GPS_UBlox(*this, instance); + backend = NEW_NOTHROW GPS_UBlox(*this, instance); break; #endif #if AP_SIM_GPS_NMEA_ENABLED case Type::NMEA: - backend = new GPS_NMEA(*this, instance); + backend = NEW_NOTHROW GPS_NMEA(*this, instance); break; #endif #if AP_SIM_GPS_SBP_ENABLED case Type::SBP: - backend = new GPS_SBP(*this, instance); + backend = NEW_NOTHROW GPS_SBP(*this, instance); break; #endif #if AP_SIM_GPS_SBP2_ENABLED case Type::SBP2: - backend = new GPS_SBP2(*this, instance); + backend = NEW_NOTHROW GPS_SBP2(*this, instance); break; #endif #if AP_SIM_GPS_NOVA_ENABLED case Type::NOVA: - backend = new GPS_NOVA(*this, instance); + backend = NEW_NOTHROW GPS_NOVA(*this, instance); break; #endif #if AP_SIM_GPS_MSP_ENABLED case Type::MSP: - backend = new GPS_MSP(*this, instance); + backend = NEW_NOTHROW GPS_MSP(*this, instance); break; #endif #if AP_SIM_GPS_TRIMBLE_ENABLED case Type::TRIMBLE: - backend = new GPS_Trimble(*this, instance); + backend = NEW_NOTHROW GPS_Trimble(*this, instance); break; #endif #if AP_SIM_GPS_FILE_ENABLED case Type::FILE: - backend = new GPS_FILE(*this, instance); + backend = NEW_NOTHROW GPS_FILE(*this, instance); break; #endif }; diff --git a/libraries/SITL/SIM_GPS_FILE.cpp b/libraries/SITL/SIM_GPS_FILE.cpp index 60868d4355..94a970960b 100644 --- a/libraries/SITL/SIM_GPS_FILE.cpp +++ b/libraries/SITL/SIM_GPS_FILE.cpp @@ -50,7 +50,7 @@ void GPS_FILE::publish(const GPS_Data *d) ::lseek(fd[instance], -sizeof(header), SEEK_CUR); return; } - buf = new uint8_t[header.n]; + buf = NEW_NOTHROW uint8_t[header.n]; if (buf != nullptr && ::read(fd[instance], buf, header.n) == ssize_t(header.n)) { write_to_autopilot((const char *)buf, header.n); delete[] buf; diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index 6a13d8b8e5..9b76b3da23 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -43,7 +43,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Gazebo(frame_str); + return NEW_NOTHROW Gazebo(frame_str); } /* Create and set in/out socket for Gazebo simulator */ diff --git a/libraries/SITL/SIM_Glider.h b/libraries/SITL/SIM_Glider.h index 0c0aa3fa5e..8c373c2f9f 100644 --- a/libraries/SITL/SIM_Glider.h +++ b/libraries/SITL/SIM_Glider.h @@ -39,7 +39,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Glider(frame_str); + return NEW_NOTHROW Glider(frame_str); } bool on_ground() const override; diff --git a/libraries/SITL/SIM_Helicopter.cpp b/libraries/SITL/SIM_Helicopter.cpp index 81143f3e3d..f1ba61dc57 100644 --- a/libraries/SITL/SIM_Helicopter.cpp +++ b/libraries/SITL/SIM_Helicopter.cpp @@ -104,7 +104,7 @@ void Helicopter::update(const struct sitl_input &input) } } else if (servos_stored_buffer == nullptr) { uint16_t buffer_size = constrain_int16(_time_delay, 1, 100) * 0.001f / dt; - servos_stored_buffer = new ObjectBuffer(buffer_size); + servos_stored_buffer = NEW_NOTHROW ObjectBuffer(buffer_size); while (servos_stored_buffer->space() != 0) { push_to_buffer(input.servos); } diff --git a/libraries/SITL/SIM_Helicopter.h b/libraries/SITL/SIM_Helicopter.h index 4410b19dec..f1a4450543 100644 --- a/libraries/SITL/SIM_Helicopter.h +++ b/libraries/SITL/SIM_Helicopter.h @@ -34,7 +34,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Helicopter(frame_str); + return NEW_NOTHROW Helicopter(frame_str); } protected: diff --git a/libraries/SITL/SIM_JSBSim.h b/libraries/SITL/SIM_JSBSim.h index bbb2c1a46a..ca5fa9c099 100644 --- a/libraries/SITL/SIM_JSBSim.h +++ b/libraries/SITL/SIM_JSBSim.h @@ -44,7 +44,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new JSBSim(frame_str); + return NEW_NOTHROW JSBSim(frame_str); } private: diff --git a/libraries/SITL/SIM_JSON.h b/libraries/SITL/SIM_JSON.h index b168219d9d..048378eae6 100644 --- a/libraries/SITL/SIM_JSON.h +++ b/libraries/SITL/SIM_JSON.h @@ -36,7 +36,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new JSON(frame_str); + return NEW_NOTHROW JSON(frame_str); } /* Create and set in/out socket for JSON generic simulator */ diff --git a/libraries/SITL/SIM_JSON_Master.cpp b/libraries/SITL/SIM_JSON_Master.cpp index 0130a7067d..9b8c3b5906 100644 --- a/libraries/SITL/SIM_JSON_Master.cpp +++ b/libraries/SITL/SIM_JSON_Master.cpp @@ -49,7 +49,7 @@ void JSON_Master::init(const int32_t num_slaves) } printf("Slave %u: listening on %u\n", list->instance, port); - list->next = new socket_list; + list->next = NEW_NOTHROW socket_list; list = list->next; initialized = true; diff --git a/libraries/SITL/SIM_LM2755.cpp b/libraries/SITL/SIM_LM2755.cpp index 719e5bd392..f34b60789b 100644 --- a/libraries/SITL/SIM_LM2755.cpp +++ b/libraries/SITL/SIM_LM2755.cpp @@ -70,7 +70,7 @@ void LM2755::init() // create objects for each of the channels to handle the dynamics // of updating each. The channel gets references to the relevant // configuration bytes. - d1 = new LEDChannel( + d1 = NEW_NOTHROW LEDChannel( byte[(uint8_t)LM2755DevReg::D1_HIGH_LEVEL], byte[(uint8_t)LM2755DevReg::D1_LOW_LEVEL], byte[(uint8_t)LM2755DevReg::D1_DELAY], @@ -79,7 +79,7 @@ void LM2755::init() byte[(uint8_t)LM2755DevReg::D1_RAMP_DOWN_STEP_TIME], byte[(uint8_t)LM2755DevReg::D1_TIMING] ); - d2 = new LEDChannel( + d2 = NEW_NOTHROW LEDChannel( byte[(uint8_t)LM2755DevReg::D2_HIGH_LEVEL], byte[(uint8_t)LM2755DevReg::D2_LOW_LEVEL], byte[(uint8_t)LM2755DevReg::D2_DELAY], @@ -88,7 +88,7 @@ void LM2755::init() byte[(uint8_t)LM2755DevReg::D2_RAMP_DOWN_STEP_TIME], byte[(uint8_t)LM2755DevReg::D2_TIMING] ); - d3 = new LEDChannel( + d3 = NEW_NOTHROW LEDChannel( byte[(uint8_t)LM2755DevReg::D3_HIGH_LEVEL], byte[(uint8_t)LM2755DevReg::D3_LOW_LEVEL], byte[(uint8_t)LM2755DevReg::D3_DELAY], diff --git a/libraries/SITL/SIM_LP5562.cpp b/libraries/SITL/SIM_LP5562.cpp index 7d0e88087a..feb8e7eac4 100644 --- a/libraries/SITL/SIM_LP5562.cpp +++ b/libraries/SITL/SIM_LP5562.cpp @@ -34,13 +34,13 @@ void LP5562::init() // currently use this device but is a structure we use elsewhere. // Note that this assumed that the LED Map register is set to its // default value. - b = new LEDChannel( + b = NEW_NOTHROW LEDChannel( byte[(uint8_t)LP5562DevReg::B_PWM] ); - g = new LEDChannel( + g = NEW_NOTHROW LEDChannel( byte[(uint8_t)LP5562DevReg::G_PWM] ); - r = new LEDChannel( + r = NEW_NOTHROW LEDChannel( byte[(uint8_t)LP5562DevReg::R_PWM] ); diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index c680072ca3..5d530318c4 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -260,7 +260,7 @@ bool Morse::parse_sensors(const char *json) bool Morse::connect_sockets(void) { if (!sensors_sock) { - sensors_sock = new SocketAPM_native(false); + sensors_sock = NEW_NOTHROW SocketAPM_native(false); if (!sensors_sock) { AP_HAL::panic("Out of memory for sensors socket"); } @@ -279,7 +279,7 @@ bool Morse::connect_sockets(void) printf("Sensors connected\n"); } if (!control_sock) { - control_sock = new SocketAPM_native(false); + control_sock = NEW_NOTHROW SocketAPM_native(false); if (!control_sock) { AP_HAL::panic("Out of memory for control socket"); } diff --git a/libraries/SITL/SIM_Morse.h b/libraries/SITL/SIM_Morse.h index 9445c26d58..10cff3eea2 100644 --- a/libraries/SITL/SIM_Morse.h +++ b/libraries/SITL/SIM_Morse.h @@ -43,7 +43,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Morse(frame_str); + return NEW_NOTHROW Morse(frame_str); } private: diff --git a/libraries/SITL/SIM_MotorBoat.h b/libraries/SITL/SIM_MotorBoat.h index 66d979d334..66c6367d11 100644 --- a/libraries/SITL/SIM_MotorBoat.h +++ b/libraries/SITL/SIM_MotorBoat.h @@ -34,7 +34,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new MotorBoat(frame_str); + return NEW_NOTHROW MotorBoat(frame_str); } }; diff --git a/libraries/SITL/SIM_Multicopter.h b/libraries/SITL/SIM_Multicopter.h index fa9a869358..289aac3182 100644 --- a/libraries/SITL/SIM_Multicopter.h +++ b/libraries/SITL/SIM_Multicopter.h @@ -36,7 +36,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new MultiCopter(frame_str); + return NEW_NOTHROW MultiCopter(frame_str); } protected: diff --git a/libraries/SITL/SIM_NoVehicle.h b/libraries/SITL/SIM_NoVehicle.h index 0d37392b0f..3482a1ee9d 100644 --- a/libraries/SITL/SIM_NoVehicle.h +++ b/libraries/SITL/SIM_NoVehicle.h @@ -33,7 +33,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new NoVehicle(frame_str); + return NEW_NOTHROW NoVehicle(frame_str); } }; diff --git a/libraries/SITL/SIM_Plane.h b/libraries/SITL/SIM_Plane.h index 1779bff8cc..2a49de12be 100644 --- a/libraries/SITL/SIM_Plane.h +++ b/libraries/SITL/SIM_Plane.h @@ -36,7 +36,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Plane(frame_str); + return NEW_NOTHROW Plane(frame_str); } protected: diff --git a/libraries/SITL/SIM_QuadPlane.h b/libraries/SITL/SIM_QuadPlane.h index f111b4040c..1915e5aa97 100644 --- a/libraries/SITL/SIM_QuadPlane.h +++ b/libraries/SITL/SIM_QuadPlane.h @@ -36,7 +36,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new QuadPlane(frame_str); + return NEW_NOTHROW QuadPlane(frame_str); } private: diff --git a/libraries/SITL/SIM_RGBLED.cpp b/libraries/SITL/SIM_RGBLED.cpp index 6e64c47c4b..a36ee06e06 100644 --- a/libraries/SITL/SIM_RGBLED.cpp +++ b/libraries/SITL/SIM_RGBLED.cpp @@ -17,7 +17,7 @@ void SIM_RGBLED::update_thread(void) sf::RenderWindow *w = nullptr; { WITH_SEMAPHORE(AP::notify().sf_window_mutex); - w = new sf::RenderWindow(sf::VideoMode(width, height), name); + w = NEW_NOTHROW sf::RenderWindow(sf::VideoMode(width, height), name); } if (w == nullptr) { diff --git a/libraries/SITL/SIM_Rover.h b/libraries/SITL/SIM_Rover.h index ede3b3a732..42009a48a1 100644 --- a/libraries/SITL/SIM_Rover.h +++ b/libraries/SITL/SIM_Rover.h @@ -34,7 +34,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new SimRover(frame_str); + return NEW_NOTHROW SimRover(frame_str); } private: diff --git a/libraries/SITL/SIM_Sailboat.h b/libraries/SITL/SIM_Sailboat.h index 62d0b3781d..4cb70e0448 100644 --- a/libraries/SITL/SIM_Sailboat.h +++ b/libraries/SITL/SIM_Sailboat.h @@ -34,7 +34,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Sailboat(frame_str); + return NEW_NOTHROW Sailboat(frame_str); } bool on_ground() const override {return true;}; diff --git a/libraries/SITL/SIM_Scrimmage.h b/libraries/SITL/SIM_Scrimmage.h index 2fa8dfcbaf..c7bfbd972b 100644 --- a/libraries/SITL/SIM_Scrimmage.h +++ b/libraries/SITL/SIM_Scrimmage.h @@ -46,7 +46,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Scrimmage(frame_str); + return NEW_NOTHROW Scrimmage(frame_str); } /* Create and set in/out socket for extenal simulator */ diff --git a/libraries/SITL/SIM_SerialDevice.cpp b/libraries/SITL/SIM_SerialDevice.cpp index 19065b7152..fe5943d5de 100644 --- a/libraries/SITL/SIM_SerialDevice.cpp +++ b/libraries/SITL/SIM_SerialDevice.cpp @@ -29,8 +29,8 @@ using namespace SITL; SerialDevice::SerialDevice(uint16_t tx_bufsize, uint16_t rx_bufsize) { - to_autopilot = new ByteBuffer{tx_bufsize}; - from_autopilot = new ByteBuffer{rx_bufsize}; + to_autopilot = NEW_NOTHROW ByteBuffer{tx_bufsize}; + from_autopilot = NEW_NOTHROW ByteBuffer{rx_bufsize}; } bool SerialDevice::init_sitl_pointer() diff --git a/libraries/SITL/SIM_SilentWings.h b/libraries/SITL/SIM_SilentWings.h index 75fdd3984f..161597eb49 100644 --- a/libraries/SITL/SIM_SilentWings.h +++ b/libraries/SITL/SIM_SilentWings.h @@ -41,7 +41,7 @@ public: /* Static object creator */ static Aircraft *create(const char *frame_str) { - return new SilentWings(frame_str); + return NEW_NOTHROW SilentWings(frame_str); } private: diff --git a/libraries/SITL/SIM_SingleCopter.h b/libraries/SITL/SIM_SingleCopter.h index 1ab8fb2027..a7ace87fd5 100644 --- a/libraries/SITL/SIM_SingleCopter.h +++ b/libraries/SITL/SIM_SingleCopter.h @@ -35,7 +35,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new SingleCopter(frame_str); + return NEW_NOTHROW SingleCopter(frame_str); } private: diff --git a/libraries/SITL/SIM_StratoBlimp.h b/libraries/SITL/SIM_StratoBlimp.h index 9165770aa6..683e567970 100644 --- a/libraries/SITL/SIM_StratoBlimp.h +++ b/libraries/SITL/SIM_StratoBlimp.h @@ -40,7 +40,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new StratoBlimp(frame_str); + return NEW_NOTHROW StratoBlimp(frame_str); } static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/SITL/SIM_Submarine.h b/libraries/SITL/SIM_Submarine.h index 6c562cd496..ea0e311760 100644 --- a/libraries/SITL/SIM_Submarine.h +++ b/libraries/SITL/SIM_Submarine.h @@ -51,7 +51,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Submarine(frame_str); + return NEW_NOTHROW Submarine(frame_str); } diff --git a/libraries/SITL/SIM_Tracker.h b/libraries/SITL/SIM_Tracker.h index 028fee4217..2ff7ecaba4 100644 --- a/libraries/SITL/SIM_Tracker.h +++ b/libraries/SITL/SIM_Tracker.h @@ -33,7 +33,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Tracker(frame_str); + return NEW_NOTHROW Tracker(frame_str); } private: diff --git a/libraries/SITL/SIM_Webots.cpp b/libraries/SITL/SIM_Webots.cpp index 80a8583c41..3e896d845a 100644 --- a/libraries/SITL/SIM_Webots.cpp +++ b/libraries/SITL/SIM_Webots.cpp @@ -290,7 +290,7 @@ bool Webots::parse_sensors(const char *json) bool Webots::connect_sockets(void) { if (!sim_sock) { - sim_sock = new SocketAPM_native(false); + sim_sock = NEW_NOTHROW SocketAPM_native(false); if (!sim_sock) { AP_HAL::panic("Out of memory for sensors socket"); } diff --git a/libraries/SITL/SIM_Webots.h b/libraries/SITL/SIM_Webots.h index 5457d6cd96..d82a9a3605 100644 --- a/libraries/SITL/SIM_Webots.h +++ b/libraries/SITL/SIM_Webots.h @@ -47,7 +47,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new Webots(frame_str); + return NEW_NOTHROW Webots(frame_str); } diff --git a/libraries/SITL/SIM_Webots_Python.h b/libraries/SITL/SIM_Webots_Python.h index ec3e8ba4b5..e1fde3b63c 100644 --- a/libraries/SITL/SIM_Webots_Python.h +++ b/libraries/SITL/SIM_Webots_Python.h @@ -43,7 +43,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new WebotsPython(frame_str); + return NEW_NOTHROW WebotsPython(frame_str); } /* Create and set in/out socket for Webots simulator */ diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index 24af0c6bab..3633bb4b1a 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -125,7 +125,7 @@ XPlane::XPlane(const char *frame_str) : */ void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dref) { - struct DRef *d = new struct DRef; + struct DRef *d = NEW_NOTHROW struct DRef; if (d == nullptr) { AP_HAL::panic("out of memory for DRef %s", name); } @@ -151,7 +151,7 @@ void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dre void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value &d) { if (strncmp(label, "axis", 4) == 0) { - struct JoyInput *j = new struct JoyInput; + struct JoyInput *j = NEW_NOTHROW struct JoyInput; if (j == nullptr) { AP_HAL::panic("out of memory for JoyInput %s", label); } @@ -164,7 +164,7 @@ void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value joyinputs = j; } if (strncmp(label, "button", 6) == 0) { - struct JoyInput *j = new struct JoyInput; + struct JoyInput *j = NEW_NOTHROW struct JoyInput; if (j == nullptr) { AP_HAL::panic("out of memory for JoyInput %s", label); } diff --git a/libraries/SITL/SIM_XPlane.h b/libraries/SITL/SIM_XPlane.h index 2e711de5a1..4d4cd37724 100644 --- a/libraries/SITL/SIM_XPlane.h +++ b/libraries/SITL/SIM_XPlane.h @@ -46,7 +46,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new XPlane(frame_str); + return NEW_NOTHROW XPlane(frame_str); } private: diff --git a/libraries/SITL/SIM_last_letter.h b/libraries/SITL/SIM_last_letter.h index d8afa83ba0..a32fa79f72 100644 --- a/libraries/SITL/SIM_last_letter.h +++ b/libraries/SITL/SIM_last_letter.h @@ -44,7 +44,7 @@ public: /* static object creator */ static Aircraft *create(const char *frame_str) { - return new last_letter(frame_str); + return NEW_NOTHROW last_letter(frame_str); } private: diff --git a/libraries/SITL/ServoModel.cpp b/libraries/SITL/ServoModel.cpp index deaff68b70..03d6bd0a22 100644 --- a/libraries/SITL/ServoModel.cpp +++ b/libraries/SITL/ServoModel.cpp @@ -81,7 +81,7 @@ float ServoModel::apply_filter(float v, float dt) if (sitl->servo.servo_delay > 0) { uint32_t delay_len = MAX(1,sitl->servo.servo_delay * sitl->loop_rate_hz); if (!delay) { - delay = new ObjectBuffer(); + delay = NEW_NOTHROW ObjectBuffer(); } if (delay->get_size() != delay_len) { delay->set_size(delay_len);