AP_TempCalibration: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
a2459c6e61
commit
93484ec81d
@ -98,7 +98,7 @@ void AP_TempCalibration::setup_learning(void)
|
||||
learn_count = 200;
|
||||
learn_i = 0;
|
||||
delete [] learn_values;
|
||||
learn_values = new float[learn_count];
|
||||
learn_values = NEW_NOTHROW float[learn_count];
|
||||
if (learn_values == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user