diff --git a/Blimp/GCS_Blimp.h b/Blimp/GCS_Blimp.h index 830e0abc20..315d122498 100644 --- a/Blimp/GCS_Blimp.h +++ b/Blimp/GCS_Blimp.h @@ -41,7 +41,7 @@ protected: GCS_MAVLINK_Blimp *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms, AP_HAL::UARTDriver &uart) override { - return new GCS_MAVLINK_Blimp(params, uart); + return NEW_NOTHROW GCS_MAVLINK_Blimp(params, uart); } }; diff --git a/Blimp/system.cpp b/Blimp/system.cpp index 7370ebbcad..e32fa10a04 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -33,7 +33,7 @@ void Blimp::init_ardupilot() // allocate the motors class allocate_motors(); - loiter = new Loiter(blimp.scheduler.get_loop_rate_hz()); + loiter = NEW_NOTHROW Loiter(blimp.scheduler.get_loop_rate_hz()); // initialise rc channels including setting mode rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); @@ -240,7 +240,7 @@ void Blimp::allocate_motors(void) switch ((Fins::motor_frame_class)g2.frame_class.get()) { case Fins::MOTOR_FRAME_AIRFISH: default: - motors = new Fins(blimp.scheduler.get_loop_rate_hz()); + motors = NEW_NOTHROW Fins(blimp.scheduler.get_loop_rate_hz()); break; } if (motors == nullptr) {