mirror of https://github.com/ArduPilot/ardupilot
AP_RCTelemetry: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
51d5f85b83
commit
01f02867a6
|
@ -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();
|
||||
|
|
|
@ -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();
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue