mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_NavEKF3: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
5e88d67571
commit
94cbd7cbfb
@ -43,7 +43,7 @@ void NavEKF3_core::BeaconFusion::InitialiseVariables()
|
|||||||
auto *beacon = AP::dal().beacon();
|
auto *beacon = AP::dal().beacon();
|
||||||
if (beacon != nullptr) {
|
if (beacon != nullptr) {
|
||||||
const uint8_t count = beacon->count();
|
const uint8_t count = beacon->count();
|
||||||
fusionReport = new BeaconFusion::FusionReport[count];
|
fusionReport = NEW_NOTHROW BeaconFusion::FusionReport[count];
|
||||||
if (fusionReport != nullptr) {
|
if (fusionReport != nullptr) {
|
||||||
numFusionReports = count;
|
numFusionReports = count;
|
||||||
}
|
}
|
||||||
|
@ -172,7 +172,7 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// try to instantiate
|
// try to instantiate
|
||||||
yawEstimator = new EKFGSF_yaw();
|
yawEstimator = NEW_NOTHROW EKFGSF_yaw();
|
||||||
if (yawEstimator == nullptr) {
|
if (yawEstimator == nullptr) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 IMU%uGSF: allocation failed",(unsigned)imu_index);
|
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "EKF3 IMU%uGSF: allocation failed",(unsigned)imu_index);
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user