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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:16 +10:00
parent 7551236854
commit 2123458112
4 changed files with 13 additions and 13 deletions

View File

@ -25,7 +25,7 @@ protected:
GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params, GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override { 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 { AP_GPS::GPS_Status min_status_for_gps_healthy() const override {

View File

@ -745,23 +745,23 @@ bool QuadPlane::setup(void)
switch ((AP_Motors::motor_frame_class)frame_class) { switch ((AP_Motors::motor_frame_class)frame_class) {
case AP_Motors::MOTOR_FRAME_TRI: 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; motors_var_info = AP_MotorsTri::var_info;
break; break;
case AP_Motors::MOTOR_FRAME_TAILSITTER: case AP_Motors::MOTOR_FRAME_TAILSITTER:
// this is a duo-motor 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 = tailsitter.tailsitter_motors;
motors_var_info = AP_MotorsTailsitter::var_info; motors_var_info = AP_MotorsTailsitter::var_info;
break; break;
case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
#if AP_SCRIPTING_ENABLED #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; motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info;
#endif // AP_SCRIPTING_ENABLED #endif // AP_SCRIPTING_ENABLED
break; break;
default: default:
motors = new AP_MotorsMatrix(rc_speed); motors = NEW_NOTHROW AP_MotorsMatrix(rc_speed);
motors_var_info = AP_MotorsMatrix::var_info; motors_var_info = AP_MotorsMatrix::var_info;
break; break;
} }
@ -778,30 +778,30 @@ bool QuadPlane::setup(void)
AP_BoardConfig::allocation_error("ahrs_view"); 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) { if (!attitude_control) {
AP_BoardConfig::allocation_error("attitude_control"); AP_BoardConfig::allocation_error("attitude_control");
} }
AP_Param::load_object_from_eeprom(attitude_control, attitude_control->var_info); 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) { if (!pos_control) {
AP_BoardConfig::allocation_error("pos_control"); AP_BoardConfig::allocation_error("pos_control");
} }
AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info); 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) { if (!wp_nav) {
AP_BoardConfig::allocation_error("wp_nav"); AP_BoardConfig::allocation_error("wp_nav");
} }
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info); 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) { if (!loiter_nav) {
AP_BoardConfig::allocation_error("loiter_nav"); AP_BoardConfig::allocation_error("loiter_nav");
} }
AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info); AP_Param::load_object_from_eeprom(loiter_nav, loiter_nav->var_info);
weathervane = new AC_WeatherVane(); weathervane = NEW_NOTHROW AC_WeatherVane();
if (!weathervane) { if (!weathervane) {
AP_BoardConfig::allocation_error("weathervane"); AP_BoardConfig::allocation_error("weathervane");
} }
@ -843,7 +843,7 @@ bool QuadPlane::setup(void)
tiltrotor.setup(); tiltrotor.setup();
if (!transition) { if (!transition) {
transition = new SLT_Transition(*this, motors); transition = NEW_NOTHROW SLT_Transition(*this, motors);
} }
if (!transition) { if (!transition) {
AP_BoardConfig::allocation_error("transition"); AP_BoardConfig::allocation_error("transition");

View File

@ -241,7 +241,7 @@ void Tailsitter::setup()
quadplane.options.set(quadplane.options.get() | int32_t(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)); 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) { if (!transition) {
AP_BoardConfig::allocation_error("tailsitter transition"); AP_BoardConfig::allocation_error("tailsitter transition");
} }

View File

@ -142,7 +142,7 @@ void Tiltrotor::setup()
} }
} }
transition = new Tiltrotor_Transition(quadplane, motors, *this); transition = NEW_NOTHROW Tiltrotor_Transition(quadplane, motors, *this);
if (!transition) { if (!transition) {
AP_BoardConfig::allocation_error("tiltrotor transition"); AP_BoardConfig::allocation_error("tiltrotor transition");
} }