diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index 6568a2cf1c..24ae36cc97 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -1638,7 +1638,7 @@ AP_CRSF_Telem *AP_CRSF_Telem::get_singleton(void) { if (!singleton && !hal.util->get_soft_armed()) { // if telem data is requested when we are disarmed and don't // yet have a AP_CRSF_Telem object then try to allocate one - new AP_CRSF_Telem(); + NEW_NOTHROW AP_CRSF_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init(); diff --git a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp index 821742273a..801b257440 100644 --- a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp @@ -373,7 +373,7 @@ AP_GHST_Telem *AP_GHST_Telem::get_singleton(void) { if (!singleton && !hal.util->get_soft_armed()) { // if telem data is requested when we are disarmed and don't // yet have a AP_GHST_Telem object then try to allocate one - new AP_GHST_Telem(); + NEW_NOTHROW AP_GHST_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init(); diff --git a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp index 7caa87cfc9..a196574adb 100644 --- a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp @@ -618,7 +618,7 @@ bool AP_Spektrum_Telem::get_telem_data(uint8_t* data) if (!singleton && !hal.util->get_soft_armed()) { // if telem data is requested when we are disarmed and don't // yet have a AP_Spektrum_Telem object then try to allocate one - new AP_Spektrum_Telem(); + NEW_NOTHROW AP_Spektrum_Telem(); // initialize the passthrough scheduler if (singleton) { singleton->init();