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

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:13 +10:00
parent 72c77b3453
commit ad6502c9f1
3 changed files with 3 additions and 3 deletions

View File

@ -412,7 +412,7 @@ void AP_PitchController::convert_pid()
void AP_PitchController::autotune_start(void) void AP_PitchController::autotune_start(void)
{ {
if (autotune == nullptr) { if (autotune == nullptr) {
autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid); autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid);
if (autotune == nullptr) { if (autotune == nullptr) {
if (!failed_autotune_alloc) { if (!failed_autotune_alloc) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed pitch allocation"); GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed pitch allocation");

View File

@ -313,7 +313,7 @@ void AP_RollController::convert_pid()
void AP_RollController::autotune_start(void) void AP_RollController::autotune_start(void)
{ {
if (autotune == nullptr) { if (autotune == nullptr) {
autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_ROLL, aparm, rate_pid); autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_ROLL, aparm, rate_pid);
if (autotune == nullptr) { if (autotune == nullptr) {
if (!failed_autotune_alloc) { if (!failed_autotune_alloc) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed roll allocation"); GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed roll allocation");

View File

@ -391,7 +391,7 @@ void AP_YawController::autotune_start(void)
gains.tau.set(0.5); gains.tau.set(0.5);
gains.rmax_pos.set(90); gains.rmax_pos.set(90);
autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_YAW, aparm, rate_pid); autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_YAW, aparm, rate_pid);
if (autotune == nullptr) { if (autotune == nullptr) {
if (!failed_autotune_alloc) { if (!failed_autotune_alloc) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed yaw allocation"); GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed yaw allocation");