mirror of https://github.com/ArduPilot/ardupilot
AP_ONVIF: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
530cbf1eca
commit
cead1ee264
|
@ -63,13 +63,13 @@ bool AP_ONVIF::start(const char *user, const char *pass, const char *hostname)
|
||||||
soap->connect_timeout = soap->recv_timeout = soap->send_timeout = 30; // 30 sec
|
soap->connect_timeout = soap->recv_timeout = soap->send_timeout = 30; // 30 sec
|
||||||
|
|
||||||
if (proxy_device == nullptr) {
|
if (proxy_device == nullptr) {
|
||||||
proxy_device = new DeviceBindingProxy(soap);
|
proxy_device = NEW_NOTHROW DeviceBindingProxy(soap);
|
||||||
}
|
}
|
||||||
if (proxy_media == nullptr) {
|
if (proxy_media == nullptr) {
|
||||||
proxy_media = new MediaBindingProxy(soap);
|
proxy_media = NEW_NOTHROW MediaBindingProxy(soap);
|
||||||
}
|
}
|
||||||
if (proxy_ptz == nullptr) {
|
if (proxy_ptz == nullptr) {
|
||||||
proxy_ptz = new PTZBindingProxy(soap);
|
proxy_ptz = NEW_NOTHROW PTZBindingProxy(soap);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (proxy_device == nullptr ||
|
if (proxy_device == nullptr ||
|
||||||
|
|
Loading…
Reference in New Issue