mirror of https://github.com/ArduPilot/ardupilot
AP_KDECAN: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
6962c4080d
commit
98697ba5d3
|
@ -63,7 +63,7 @@ void AP_KDECAN::init()
|
|||
|
||||
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
|
||||
if (CANSensor::get_driver_type(i) == AP_CAN::Protocol::KDECAN) {
|
||||
_driver = new AP_KDECAN_Driver();
|
||||
_driver = NEW_NOTHROW AP_KDECAN_Driver();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue