mirror of https://github.com/ArduPilot/ardupilot
HAL_Empty: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
aff9175328
commit
6233bc0e10
|
@ -77,7 +77,7 @@ public:
|
||||||
SPIDeviceManager() { }
|
SPIDeviceManager() { }
|
||||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name) override
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name) override
|
||||||
{
|
{
|
||||||
return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice());
|
return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(NEW_NOTHROW SPIDevice());
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue