mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_MSP: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
28da263e16
commit
5ca4bdbd8d
@ -63,12 +63,12 @@ AP_MSP::AP_MSP()
|
|||||||
bool AP_MSP::init_backend(uint8_t backend_idx, AP_HAL::UARTDriver *uart, AP_SerialManager::SerialProtocol protocol)
|
bool AP_MSP::init_backend(uint8_t backend_idx, AP_HAL::UARTDriver *uart, AP_SerialManager::SerialProtocol protocol)
|
||||||
{
|
{
|
||||||
if (protocol == AP_SerialManager::SerialProtocol_MSP) {
|
if (protocol == AP_SerialManager::SerialProtocol_MSP) {
|
||||||
_backends[backend_idx] = new AP_MSP_Telem_Generic(uart);
|
_backends[backend_idx] = NEW_NOTHROW AP_MSP_Telem_Generic(uart);
|
||||||
} else if (protocol == AP_SerialManager::SerialProtocol_DJI_FPV) {
|
} else if (protocol == AP_SerialManager::SerialProtocol_DJI_FPV) {
|
||||||
_backends[backend_idx] = new AP_MSP_Telem_DJI(uart);
|
_backends[backend_idx] = NEW_NOTHROW AP_MSP_Telem_DJI(uart);
|
||||||
#if HAL_WITH_MSP_DISPLAYPORT
|
#if HAL_WITH_MSP_DISPLAYPORT
|
||||||
} else if (protocol == AP_SerialManager::SerialProtocol_MSP_DisplayPort) {
|
} else if (protocol == AP_SerialManager::SerialProtocol_MSP_DisplayPort) {
|
||||||
_backends[backend_idx] = new AP_MSP_Telem_DisplayPort(uart);
|
_backends[backend_idx] = NEW_NOTHROW AP_MSP_Telem_DisplayPort(uart);
|
||||||
#endif
|
#endif
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user