Subversion Repositories FlightCtrl

Rev

Rev 226 | Go to most recent revision | Blame | Last modification | View Log | RSS feed

/*
This program (files math.c and math.h) is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by the Free Software Foundation;
either version 3 of the License, or (at your option) any later version.  
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
GNU General Public License for more details. You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.

Please note: All the other files for the project "Mikrokopter" by H.Buss are under the license (license_buss.txt) published by www.mikrokopter.de
*/


#include "main.h"

//-----------------------------------------------
// Fast arctan2 with max error of .07 rads
// http://www.dspguru.com/comp.dsp/tricks/alg/fxdatan2.htm
//-----------------------------------------------
signed int arctan_f(signed int x, signed int y)
{  
        float rad,r;
        short int m;
        #define coeff_1         0.7854
        #define coeff_2         2.3562
        #define rad2grad        57.2958  
   
   if (!x && !y) return 0;
   
   if (y < 0) {y = abs(y); m = -1;}
   else m = 1;
   
   if (x>=0)
   {
      r = (float)(x - y) / (float)(x + y);
      rad = coeff_1 - coeff_1*r;
   }
   else
   {
      r = (float)(x + y) / (float)(y - x);
      rad = coeff_2 - coeff_1*r;
   }
   
   rad *= rad2grad;
   
   return(rad*m);
}

/*++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
Peter Muehlenbrock
arctan in brute-force Art
Stand 1.10.2007
++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
*/

// arctan Funktion: Eingabewert x,y Rueckgabe =arctan(x,y) in grad
signed int arctan_i(signed int x,  signed int y)
{
        short int change_xy = 0;
        signed int i;
        long signed int wert;
        int return_value;

        if ((abs(x)) > (abs(y)))  // x,y Werte vertauschen damit arctan <45 grad bleibt
        {      
                change_xy       = 1;
                i                       = x;
                x                       = y;
                y                       = i;
        }
       
        // Quadranten ermitteln

        // Wert durch lineare Interpolation ermitteln
        if (!y && !x)  return 0; // Division durch 0 nicht erlaubt
       
        else wert= abs((x*1000)/y);

        if (wert <=268) //0...0.0,268  entsprechend 0..15 Grad
        {
                return_value = (signed int)((wert*100)/(268-0)*(15-0)/100) +0;
        }
        else if (wert <=578) //0,268...0.0,568  entsprechend 15..30 Grad
        {      
                return_value = (signed int)((((wert-268)*100)/(578-268)*(30-15))/100) +15;             
        }
        else //0,568...1  entsprechend 30..45 Grad
        {      
                return_value = (signed int)((((wert-578)*50)/(1000-578)*(45-30))/50) +30;              
        }

        if (change_xy == 0)  return_value = 90-return_value; //Quadrant 45..90 Grad
        if ((x >= 0) && (y <0)) return_value = - return_value;
        else if ((x < 0) && (y >= 0)) return_value = - return_value;

return return_value;
}





const float pgm_sinus_f [91] PROGMEM = {0.000,0.017,0.035,0.052,0.070,0.087,0.105,0.122,0.139,0.156,0.174,0.191,0.208,0.225,0.242,0.259,0.276,0.292,0.309,0.326,0.342,0.358,0.375,0.391,0.407,0.423,0.438,0.454,0.469,0.485,0.500,0.515,0.530,0.545,0.559,0.574,0.588,0.602,0.616,0.629,0.643,0.656,0.669,0.682,0.695,0.707,0.719,0.731,0.743,0.755,0.766,0.777,0.788,0.799,0.809,0.819,0.829,0.839,0.848,0.857,0.866,0.875,0.883,0.891,0.899,0.906,0.914,0.921,0.927,0.934,0.940,0.946,0.951,0.956,0.961,0.966,0.970,0.974,0.978,0.982,0.985,0.988,0.990,0.993,0.995,0.996,0.998,0.999,0.999,1.000,1.000};

inline float pgm_read_float(const float *addr)
{      
        union
        {
                uint16_t i[2];  // 2 16-bit-Worte
                float f;
        } u;
       
        u.i[0]=pgm_read_word((PGM_P)addr);
        u.i[1]=pgm_read_word((PGM_P)addr+2);
       
        return u.f;
}

// cosinus Funktion: Eingabewert Winkel in Grad
float cos_f(signed int winkel)
{
 return (sin_f(90-winkel));
}

// sinus Funktion: Eingabewert Winkel in Grad
float sin_f(signed int winkel)
{
 short int m,n;
 float sinus;
 
 //winkel = winkel % 360;
 
 if (winkel < 0)
 {
        m = -1;
        winkel = abs(winkel);
 }
 else m = +1;
 
 // Quadranten auswerten
 if ((winkel > 90 ) && (winkel <= 180)) {winkel = 180 - winkel; n = 1;}
 else if ((winkel > 180 ) && (winkel <= 270)) {winkel = winkel - 180; n = -1;}
 else if ((winkel > 270) && (winkel <= 360)) {winkel = 360 - winkel; n = -1;}
 else n = 1; //0 - 90 Grad

sinus = pgm_read_float(&pgm_sinus_f[winkel]);

return (sinus*m*n);
}






const unsigned int pgm_sinus[91] PROGMEM = {0,17,35,52,70,87,105,122,139,156,174,191,208,225,242,259,276,292,309,326,342,358,375,391,407,423,438,454,469,485,500,515,530,545,559,574,588,602,616,629,643,656,669,682,695,707,719,731,743,755,766,777,788,799,809,819,829,839,848,857,866,875,883,891,899,906,914,921,927,934,940,946,951,956,961,966,970,974,978,982,985,988,990,993,995,996,998,999,999,1000,1000};

// cosinus Funktion: Eingabewert Winkel in Grad, Rueckgabe =cos(winkel)*1000
signed int cos_i(signed int winkel)
{
  return (sin_i(90-winkel));
}

// sinus Funktion: Eingabewert Winkel in Grad, Rueckgabe =sin(winkel)*1000
signed int sin_i(signed int winkel)
{
 short int m,n;
 
 //winkel = winkel % 360;
 
 if (winkel < 0)
 {
        m = -1;
        winkel = abs(winkel);
 }
 else m = +1;
 
 // Quadranten auswerten
 if ((winkel > 90 ) && (winkel <= 180)) {winkel = 180 - winkel; n = 1;}
 else if ((winkel > 180 ) && (winkel <= 270)) {winkel = winkel - 180; n = -1;}
 else if ((winkel > 270) && (winkel <= 360)) {winkel = 360 - winkel; n = -1;}
 else n = 1; //0 - 90 Grad

winkel = pgm_read_word(&pgm_sinus[winkel]);

return (winkel*m*n);
}