mirror of https://github.com/ArduPilot/ardupilot
AP_Winch: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
20a5ec4348
commit
76d16e2d78
|
@ -79,10 +79,10 @@ void AP_Winch::init()
|
|||
case WinchType::NONE:
|
||||
break;
|
||||
case WinchType::PWM:
|
||||
backend = new AP_Winch_PWM(config);
|
||||
backend = NEW_NOTHROW AP_Winch_PWM(config);
|
||||
break;
|
||||
case WinchType::DAIWA:
|
||||
backend = new AP_Winch_Daiwa(config);
|
||||
backend = NEW_NOTHROW AP_Winch_Daiwa(config);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue