mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
bac6d6f644
commit
a71585b9b8
|
@ -201,42 +201,42 @@ void AP_Camera::init()
|
|||
switch ((CameraType)_params[instance].type.get()) {
|
||||
#if AP_CAMERA_SERVO_ENABLED
|
||||
case CameraType::SERVO:
|
||||
_backends[instance] = new AP_Camera_Servo(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_Servo(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_RELAY_ENABLED
|
||||
case CameraType::RELAY:
|
||||
_backends[instance] = new AP_Camera_Relay(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_Relay(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_SOLOGIMBAL_ENABLED
|
||||
// check for GoPro in Solo camera
|
||||
case CameraType::SOLOGIMBAL:
|
||||
_backends[instance] = new AP_Camera_SoloGimbal(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_SoloGimbal(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_MOUNT_ENABLED
|
||||
// check for Mount camera
|
||||
case CameraType::MOUNT:
|
||||
_backends[instance] = new AP_Camera_Mount(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_Mount(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_MAVLINK_ENABLED
|
||||
// check for MAVLink enabled camera driver
|
||||
case CameraType::MAVLINK:
|
||||
_backends[instance] = new AP_Camera_MAVLink(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_MAVLink(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_MAVLINKCAMV2_ENABLED
|
||||
// check for MAVLink Camv2 driver
|
||||
case CameraType::MAVLINK_CAMV2:
|
||||
_backends[instance] = new AP_Camera_MAVLinkCamV2(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_MAVLinkCamV2(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||
// check for Scripting driver
|
||||
case CameraType::SCRIPTING:
|
||||
_backends[instance] = new AP_Camera_Scripting(*this, _params[instance], instance);
|
||||
_backends[instance] = NEW_NOTHROW AP_Camera_Scripting(*this, _params[instance], instance);
|
||||
break;
|
||||
#endif
|
||||
case CameraType::NONE:
|
||||
|
|
Loading…
Reference in New Issue