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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:16 +10:00
parent 74dc4f961c
commit 91ff1bc028
2 changed files with 3 additions and 3 deletions

View File

@ -41,7 +41,7 @@ protected:
GCS_MAVLINK_Blimp *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override
{
return new GCS_MAVLINK_Blimp(params, uart);
return NEW_NOTHROW GCS_MAVLINK_Blimp(params, uart);
}
};

View File

@ -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) {