From da65814ece6a5bd30ba11bd1a5ea14f27de09de7 Mon Sep 17 00:00:00 2001 From: DrZiplok Date: Sat, 27 Nov 2010 09:50:03 +0000 Subject: [PATCH] Use fabs() rather than abs() for floating-point values. git-svn-id: https://arducopter.googlecode.com/svn/trunk@958 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/APM_Compass/APM_Compass.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/APM_Compass/APM_Compass.cpp b/libraries/APM_Compass/APM_Compass.cpp index d596805cef..2baf20c913 100644 --- a/libraries/APM_Compass/APM_Compass.cpp +++ b/libraries/APM_Compass/APM_Compass.cpp @@ -115,9 +115,9 @@ bool APM_Compass_Class::Init(int initialiseWireLib) // calibrate if( abs(Mag_X) > 500 && abs(Mag_X) < 1000 && abs(Mag_Y) > 500 && abs(Mag_Y) < 1000 && abs(Mag_Z) > 500 && abs(Mag_Z) < 1000) { - calibration[0] = abs(715.0 / Mag_X); - calibration[1] = abs(715.0 / Mag_Y); - calibration[2] = abs(715.0 / Mag_Z); + calibration[0] = fabs(715.0 / Mag_X); + calibration[1] = fabs(715.0 / Mag_Y); + calibration[2] = fabs(715.0 / Mag_Z); // mark success success = 1; @@ -269,9 +269,9 @@ bool APM_Compass_HIL_Class::Init(int initialiseWireLib) // calibrate if( abs(Mag_X) > 500 && abs(Mag_X) < 1000 && abs(Mag_Y) > 500 && abs(Mag_Y) < 1000 && abs(Mag_Z) > 500 && abs(Mag_Z) < 1000) { - calibration[0] = abs(715.0 / Mag_X); - calibration[1] = abs(715.0 / Mag_Y); - calibration[2] = abs(715.0 / Mag_Z); + calibration[0] = fabs(715.0 / Mag_X); + calibration[1] = fabs(715.0 / Mag_Y); + calibration[2] = fabs(715.0 / Mag_Z); // mark success success = 1;