AP_Declination: Updated test to run in 5 degree increments. Changed to only print failures and also print total pass vs total fail.

This commit is contained in:
Adam M Rivera 2012-03-20 16:44:09 -05:00 committed by Andrew Tridgell
parent 230ca1ddca
commit 076192db51
1 changed files with 10 additions and 5 deletions

View File

@ -52,25 +52,30 @@ static const int16_t dec_tbl[37][73] = \
void setup(void)
{
float declination, declination_test;
uint16_t pass = 0, fail = 0;
Serial.begin(115200);
for(int i = -90; i <= 90; i+=10)
for(int i = -90; i <= 90; i+=5)
{
for(int j = -180; j <= 180; j+=10)
for(int j = -180; j <= 180; j+=5)
{
declination = AP_Declination::get_declination(i, j);
declination_test = get_declination(i, j);
if(declination == declination_test)
{
Serial.printf("Pass: %i, %i : %f, %f\n", i, j, declination, declination_test);
//Serial.printf("Pass: %i, %i : %f, %f\n", i, j, declination, declination_test);
pass++;
}
else
{
Serial.printf("Fail: %i, %i : %f, %f\n", i, j, declination, declination_test);
Serial.printf("FAIL: %i, %i : %f, %f\n", i, j, declination, declination_test);
fail++;
}
}
}
Serial.printf("Total Pass: %i\n", pass);
Serial.printf("Total Fail: %i\n", fail);
}
void loop(void)
@ -101,4 +106,4 @@ float get_declination(float lat, float lon)
decmin = (lon - lonmin) / 5 * (decSE - decSW) + decSW;
decmax = (lon - lonmin) / 5 * (decNE - decNW) + decNW;
return (lat - latmin) / 5 * (decmax - decmin) + decmin;
}
}