mirror of https://github.com/ArduPilot/ardupilot
AP_Gripper: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
1e075aeb80
commit
62e3c6e5a4
|
@ -113,12 +113,12 @@ void AP_Gripper::init()
|
|||
break;
|
||||
#if AP_GRIPPER_SERVO_ENABLED
|
||||
case 1:
|
||||
backend = new AP_Gripper_Servo(config);
|
||||
backend = NEW_NOTHROW AP_Gripper_Servo(config);
|
||||
break;
|
||||
#endif
|
||||
#if AP_GRIPPER_EPM_ENABLED
|
||||
case 2:
|
||||
backend = new AP_Gripper_EPM(config);
|
||||
backend = NEW_NOTHROW AP_Gripper_EPM(config);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
|
|
Loading…
Reference in New Issue