mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
5ca4bdbd8d
commit
5e88d67571
|
@ -99,7 +99,7 @@ bool NavEKF2_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
|
|||
}
|
||||
|
||||
// try to instantiate
|
||||
yawEstimator = new EKFGSF_yaw();
|
||||
yawEstimator = NEW_NOTHROW EKFGSF_yaw();
|
||||
if (yawEstimator == nullptr) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF2 IMU%uGSF: allocation failed",(unsigned)imu_index);
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue