Subversion Repositories FlightCtrl

Rev

Go to most recent revision | Blame | Compare with Previous | 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 Lesser 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 and GNU Lesser General Public License for more details.
You should have received a copy of GNU General Public License (License_GPL.txt)  and
GNU Lesser General Public License (License_LGPL.txt) 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
*/

/*++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
Peter Muehlenbrock
Winkelfunktionen sin, cos und arctan in
brute-force Art: Sehr Schnell, nicht sonderlich genau, aber ausreichend
get_dist Funktion fuer Entfernungsermittlung
Stand 12.10.2007
++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
*/

#include "main.h"


// arctan Funktion: Eingabewert x,y Rueckgabe =arctan(x,y) in grad
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 == 0) && (x == 0))  wert =1; // Division durch 0 nicht erlaubt
        else wert= abs(((long)x*1000)/((long)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;
}


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


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};
//von Nick666, Stand 28.9.2007
// sinus Funktion: Eingabewert Winkel in Grad, Rueckgabe =sin(winkel)*1000
signed int sin_i(signed int winkel)
{
 short int m,n;

 if (abs(winkel) >=360) winkel = winkel % 360;
 if (winkel < 0)
 {
        m = -1;
        winkel = abs(winkel);
 }
 else m = +1;
 n =1;

 // Quadranten auswerten
 if ((winkel > 90 ) && (winkel <= 180)) winkel = 180 - winkel;
 else if ((winkel > 180 ) && (winkel <= 270))
 {
        winkel = winkel -180;
        n = -1;
 }
  else if ((winkel > 270) && (winkel <= 360))
 {
        winkel = 360 - winkel;
        n = -1;
 }
 // else //0 - 90 Grad

 winkel = pgm_read_word(&pgm_sinus[winkel]);
 return (winkel*m*n);
}

// Aus x,y und Winkel Distanz ermitteln
long get_dist(signed int x, signed int y, signed int phi)
{
        long dist;
        if (abs(x) > abs(y) )
        {
                dist = (long) x; //Groesseren Wert wegen besserer Genauigkeit nehmen
                dist = abs((dist *1000) / (long) sin_i(phi));
        }
        else
        {
                dist = (long) y;
                dist = abs((dist *1000) / (long) cos_i(phi));
        }
  return dist;
}


// noch mehr von Nick666

const uint8_t pgm_atan[270] PROGMEM = {0,1,2,3,5,6,7,8,9,10,11,12,13,15,16,17,18,19,20,21,22,23,24,25,26,27,27,28,29,30,31,32,33,33,34,35,36,37,37,38,39,39,40,41,41,42,43,43,44,44,45,46,46,47,47,48,48,49,49,50,50,51,51,52,52,52,53,53,54,54,54,55,55,56,56,56,57,57,57,58,58,58,59,59,59,60,60,60,60,61,61,61,61,62,62,62,62,63,63,63,63,64,64,64,64,65,65,65,65,65,66,66,66,66,66,67,67,67,67,67,67,68,68,68,68,68,68,69,69,69,69,69,69,69,70,70,70,70,70,70,70,70,71,71,71,71,71,71,71,71,72,72,72,72,72,72,72,72,72,73,73,73,73,73,73,73,73,73,73,74,74,74,74,74,74,74,74,74,74,74,74,75,75,75,75,75,75,75,75,75,75,75,75,75,76,76,76,76,76,76,76,76,76,76,76,76,76,76,76,77,77,77,77,77,77,77,77,77,77,77,77,77,77,77,77,77,78,78,78,78,78,78,78,78,78,78,78,78,78,78,78,78,78,78,78,78,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79,79};

// Arkustangens2 im Gradmaß
signed int atan2_i(signed int x,  signed int y)
{
        int i,angle;
        int8_t m;
       
        if (!x && !y) return 0;         //atan2 = 0 für x und y = 0
       
        if (y < 0) m=-1;
        else m=1;
       
        if (x==0) return (90*m);                // atan2 = 90° für x = 0
       
        i = abs(((float)y / x) * 50);           // Berechne i für die Lookup table (Schrittweite atan(x) ist 0.02 -> *50)

        if (i<270) angle = pgm_read_byte(&pgm_atan[i]); // Lookup für 1° bis 79°
        else if (i>5750) angle = 90;                                            // Grenzwert ist 90°
        else if (i>=1910) angle = 89;                                           // 89° bis 80° über Wertebereiche
        else if (i>=1150) angle = 88;
        else if (i>=820) angle = 87;
        else if (i>=640) angle = 86;
        else if (i>=520) angle = 85;
        else if (i>=440) angle = 84;
        else if (i>=380) angle = 83;
        else if (i>=335) angle = 82;
        else if (i>=299) angle = 81;
        else angle = 80; // (i>=270)
       
        if (x > 0) return (angle*m);    // Quadrant I und IV
        else if ((x < 0) && (y >= 0)) return ((angle*-1) + 180);        // Quadrant II
        else return (angle - 180); // x < 0 && y < 0    Quadrant III
}





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



// Sinusfunktion im Gradmaß
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);
}

// Kosinusfunktion im Gradmaß
float cos_f(signed int winkel)
{
 return (sin_f(90-winkel));
}


const uint8_t pgm_asin[201] PROGMEM = {0,0,1,1,1,1,2,2,2,3,3,3,3,4,4,4,5,5,5,5,6,6,6,7,7,7,7,8,8,8,9,9,9,9,10,10,10,11,11,11,12,12,12,12,13,13,13,14,14,14,14,15,15,15,16,16,16,17,17,17,17,18,18,18,19,19,19,20,20,20,20,21,21,21,22,22,22,23,23,23,24,24,24,25,25,25,25,26,26,26,27,27,27,28,28,28,29,29,29,30,30,30,31,31,31,32,32,32,33,33,33,34,34,34,35,35,35,36,36,37,37,37,38,38,38,39,39,39,40,40,41,41,41,42,42,42,43,43,44,44,44,45,45,46,46,46,47,47,48,48,49,49,49,50,50,51,51,52,52,53,53,54,54,55,55,56,56,57,57,58,58,59,59,60,60,61,62,62,63,64,64,65,66,66,67,68,68,69,70,71,72,73,74,75,76,77,79,80,82,84,90};

// Akurssinusfunktion im Gradmaß
int8_t asin_i(signed int i)
{
        signed char m;
       
        if (i < 0) {m=-1;i=abs(i);}
        else m=1;
       
        return (pgm_read_byte(&pgm_asin[i]) * m);
}