mirror of https://github.com/ArduPilot/ardupilot
AP_CustomRotations: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
0f08b47322
commit
98caad29f5
|
@ -139,7 +139,7 @@ AP_CustomRotation* AP_CustomRotations::get_rotation(Rotation r)
|
|||
}
|
||||
const uint8_t index = r - ROTATION_CUSTOM_1;
|
||||
if (rotations[index] == nullptr) {
|
||||
rotations[index] = new AP_CustomRotation(params[index]);
|
||||
rotations[index] = NEW_NOTHROW AP_CustomRotation(params[index]);
|
||||
// make sure param is enabled if custom rotation is used
|
||||
enable.set_and_save_ifchanged(1);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue