From e6a8a6da076a1e1463f6b7115a412ea311f6bebc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 May 2015 12:35:25 +1000 Subject: [PATCH] AP_InertialSensor: revert AP_Math class change --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 8283847b32..ffd84950f8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -989,7 +989,7 @@ void AP_InertialSensor::_calibrate_find_delta(float dS[6], float JS[6][6], float //eliminate all nonzero entries below JS[i][i] for( j=i+1; j<6; j++ ) { mu = JS[i][j]/JS[i][i]; - if( !AP_Math::is_zero(mu) ) { + if( !is_zero(mu) ) { dS[j] -= mu*dS[i]; for( k=j; k<6; k++ ) { JS[k][j] -= mu*JS[k][i];