diff --git a/libraries/AP_Math/matrix_alg.cpp b/libraries/AP_Math/matrix_alg.cpp index cda345b21b..9b5f76ec08 100644 --- a/libraries/AP_Math/matrix_alg.cpp +++ b/libraries/AP_Math/matrix_alg.cpp @@ -35,7 +35,7 @@ template static T* matrix_multiply(const T *A, const T *B, uint16_t n) { - T* ret = new T[n*n]; + T* ret = NEW_NOTHROW T[n*n]; memset(ret,0.0f,n*n*sizeof(T)); for(uint16_t i = 0; i < n; i++) { @@ -194,13 +194,13 @@ static bool mat_inverseN(const T* A, T* inv, uint16_t n) { T *L, *U, *P; bool ret = true; - L = new T[n*n]; - U = new T[n*n]; - P = new T[n*n]; + L = NEW_NOTHROW T[n*n]; + U = NEW_NOTHROW T[n*n]; + P = NEW_NOTHROW T[n*n]; mat_LU_decompose(A,L,U,P,n); - T *L_inv = new T[n*n]; - T *U_inv = new T[n*n]; + T *L_inv = NEW_NOTHROW T[n*n]; + T *U_inv = NEW_NOTHROW T[n*n]; memset(L_inv,0,n*n*sizeof(T)); mat_forward_sub(L,L_inv,n); diff --git a/libraries/AP_Math/polyfit.cpp b/libraries/AP_Math/polyfit.cpp index 3a70267185..88a925070f 100644 --- a/libraries/AP_Math/polyfit.cpp +++ b/libraries/AP_Math/polyfit.cpp @@ -31,7 +31,7 @@ template bool PolyFit::get_polynomial(vtype res[order]) const { // we dynamically allocate the inverse matrix to keep stack usage low - xtype *inv_mat = new xtype[order*order]; + xtype *inv_mat = NEW_NOTHROW xtype[order*order]; if (inv_mat == nullptr) { return false; } diff --git a/libraries/AP_Math/vector2.cpp b/libraries/AP_Math/vector2.cpp index 0204e8d3af..149bcd08e0 100644 --- a/libraries/AP_Math/vector2.cpp +++ b/libraries/AP_Math/vector2.cpp @@ -241,7 +241,7 @@ bool Vector2::circle_segment_intersection(const Vector2& seg_start, const // -> o o -> | -> | // FallShort (t1>1,t2>1), Past (t1<0,t2<0), CompletelyInside(t1<0, t2>1) - // intersection = new Vector3(E.x + t1 * d.x, secondPoint.y, E.y + t1 * d.y); + // intersection = NEW_NOTHROW Vector3(E.x + t1 * d.x, secondPoint.y, E.y + t1 * d.y); // intersection.x = seg_start.x + t1 * seg_end_minus_start.x; // intersection.y = seg_start.y + t1 * seg_end_minus_start.y;