AP_Math: use NEW_NOTHROW for new(std::nothrow)

This commit is contained in:
Andrew Tridgell 2024-05-27 11:24:12 +10:00
parent 20070b7e37
commit 72c77b3453
3 changed files with 8 additions and 8 deletions

View File

@ -35,7 +35,7 @@
template<typename T> template<typename T>
static T* matrix_multiply(const T *A, const T *B, uint16_t n) 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)); memset(ret,0.0f,n*n*sizeof(T));
for(uint16_t i = 0; i < n; i++) { 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; T *L, *U, *P;
bool ret = true; bool ret = true;
L = new T[n*n]; L = NEW_NOTHROW T[n*n];
U = new T[n*n]; U = NEW_NOTHROW T[n*n];
P = new T[n*n]; P = NEW_NOTHROW T[n*n];
mat_LU_decompose(A,L,U,P,n); mat_LU_decompose(A,L,U,P,n);
T *L_inv = new T[n*n]; T *L_inv = NEW_NOTHROW T[n*n];
T *U_inv = new T[n*n]; T *U_inv = NEW_NOTHROW T[n*n];
memset(L_inv,0,n*n*sizeof(T)); memset(L_inv,0,n*n*sizeof(T));
mat_forward_sub(L,L_inv,n); mat_forward_sub(L,L_inv,n);

View File

@ -31,7 +31,7 @@ template <uint8_t order, typename xtype, typename vtype>
bool PolyFit<order,xtype,vtype>::get_polynomial(vtype res[order]) const bool PolyFit<order,xtype,vtype>::get_polynomial(vtype res[order]) const
{ {
// we dynamically allocate the inverse matrix to keep stack usage low // 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) { if (inv_mat == nullptr) {
return false; return false;
} }

View File

@ -241,7 +241,7 @@ bool Vector2<T>::circle_segment_intersection(const Vector2<T>& seg_start, const
// -> o o -> | -> | // -> o o -> | -> |
// FallShort (t1>1,t2>1), Past (t1<0,t2<0), CompletelyInside(t1<0, t2>1) // 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.x = seg_start.x + t1 * seg_end_minus_start.x;
// intersection.y = seg_start.y + t1 * seg_end_minus_start.y; // intersection.y = seg_start.y + t1 * seg_end_minus_start.y;