Use fabs() rather than abs() for floating-point values.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@958 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2010-11-27 09:50:03 +00:00
parent 2bf62274ab
commit da65814ece
1 changed files with 6 additions and 6 deletions

View File

@ -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;