diff --git a/ArduPlane/GCS_Plane.h b/ArduPlane/GCS_Plane.h index aa5d507b91..9d5ca814e5 100644 --- a/ArduPlane/GCS_Plane.h +++ b/ArduPlane/GCS_Plane.h @@ -25,7 +25,7 @@ protected: GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Plane(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Plane(params, uart); } AP_GPS::GPS_Status min_status_for_gps_healthy() const override { diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 9a90a8f70c..03f7f78fb9 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -745,23 +745,23 @@ bool QuadPlane::setup(void) switch ((AP_Motors::motor_frame_class)frame_class) { case AP_Motors::MOTOR_FRAME_TRI: - motors = new AP_MotorsTri(rc_speed); + motors = NEW_NOTHROW AP_MotorsTri(rc_speed); motors_var_info = AP_MotorsTri::var_info; break; case AP_Motors::MOTOR_FRAME_TAILSITTER: // this is a duo-motor tailsitter - tailsitter.tailsitter_motors = new AP_MotorsTailsitter(rc_speed); + tailsitter.tailsitter_motors = NEW_NOTHROW AP_MotorsTailsitter(rc_speed); motors = tailsitter.tailsitter_motors; motors_var_info = AP_MotorsTailsitter::var_info; break; case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: #if AP_SCRIPTING_ENABLED - motors = new AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info; #endif // AP_SCRIPTING_ENABLED break; default: - motors = new AP_MotorsMatrix(rc_speed); + motors = NEW_NOTHROW AP_MotorsMatrix(rc_speed); motors_var_info = AP_MotorsMatrix::var_info; break; } @@ -778,30 +778,30 @@ bool QuadPlane::setup(void) AP_BoardConfig::allocation_error("ahrs_view"); } - attitude_control = new AC_AttitudeControl_TS(*ahrs_view, aparm, *motors); + attitude_control = NEW_NOTHROW AC_AttitudeControl_TS(*ahrs_view, aparm, *motors); if (!attitude_control) { AP_BoardConfig::allocation_error("attitude_control"); } AP_Param::load_object_from_eeprom(attitude_control, attitude_control->var_info); - pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); + pos_control = NEW_NOTHROW AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); if (!pos_control) { AP_BoardConfig::allocation_error("pos_control"); } AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info); - wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + wp_nav = NEW_NOTHROW AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control); if (!wp_nav) { AP_BoardConfig::allocation_error("wp_nav"); } AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info); - loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control); + loiter_nav = NEW_NOTHROW AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control); if (!loiter_nav) { AP_BoardConfig::allocation_error("loiter_nav"); } AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info); - weathervane = new AC_WeatherVane(); + weathervane = NEW_NOTHROW AC_WeatherVane(); if (!weathervane) { AP_BoardConfig::allocation_error("weathervane"); } @@ -843,7 +843,7 @@ bool QuadPlane::setup(void) tiltrotor.setup(); if (!transition) { - transition = new SLT_Transition(*this, motors); + transition = NEW_NOTHROW SLT_Transition(*this, motors); } if (!transition) { AP_BoardConfig::allocation_error("transition"); diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index bac8e4d9f7..b530dacce5 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -241,7 +241,7 @@ void Tailsitter::setup() quadplane.options.set(quadplane.options.get() | int32_t(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)); } - transition = new Tailsitter_Transition(quadplane, motors, *this); + transition = NEW_NOTHROW Tailsitter_Transition(quadplane, motors, *this); if (!transition) { AP_BoardConfig::allocation_error("tailsitter transition"); } diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 7a8de87a72..9fd1f8a2cb 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -142,7 +142,7 @@ void Tiltrotor::setup() } } - transition = new Tiltrotor_Transition(quadplane, motors, *this); + transition = NEW_NOTHROW Tiltrotor_Transition(quadplane, motors, *this); if (!transition) { AP_BoardConfig::allocation_error("tiltrotor transition"); }