mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Radio: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
c681701f81
commit
5130e26f4c
@ -155,17 +155,17 @@ bool AP_Radio::init(void)
|
|||||||
switch (radio_type) {
|
switch (radio_type) {
|
||||||
#if AP_RADIO_CYRF6936_ENABLED
|
#if AP_RADIO_CYRF6936_ENABLED
|
||||||
case RADIO_TYPE_CYRF6936:
|
case RADIO_TYPE_CYRF6936:
|
||||||
driver = new AP_Radio_cypress(*this);
|
driver = NEW_NOTHROW AP_Radio_cypress(*this);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#if AP_RADIO_CC2500_ENABLED
|
#if AP_RADIO_CC2500_ENABLED
|
||||||
case RADIO_TYPE_CC2500:
|
case RADIO_TYPE_CC2500:
|
||||||
driver = new AP_Radio_cc2500(*this);
|
driver = NEW_NOTHROW AP_Radio_cc2500(*this);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#if AP_RADIO_BK2425_ENABLED
|
#if AP_RADIO_BK2425_ENABLED
|
||||||
case RADIO_TYPE_BK2425:
|
case RADIO_TYPE_BK2425:
|
||||||
driver = new AP_Radio_beken(*this);
|
driver = NEW_NOTHROW AP_Radio_beken(*this);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
|
||||||
@ -173,12 +173,12 @@ bool AP_Radio::init(void)
|
|||||||
// auto-detect between cc2500 and beken radios
|
// auto-detect between cc2500 and beken radios
|
||||||
#if AP_RADIO_CC2500_ENABLED
|
#if AP_RADIO_CC2500_ENABLED
|
||||||
if (AP_Radio_cc2500::probe()) {
|
if (AP_Radio_cc2500::probe()) {
|
||||||
driver = new AP_Radio_cc2500(*this);
|
driver = NEW_NOTHROW AP_Radio_cc2500(*this);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if AP_RADIO_BK2425_ENABLED
|
#if AP_RADIO_BK2425_ENABLED
|
||||||
if (driver == nullptr) {
|
if (driver == nullptr) {
|
||||||
driver = new AP_Radio_beken(*this);
|
driver = NEW_NOTHROW AP_Radio_beken(*this);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user