- 3D-Druck Einstieg und Tipps         
Ergebnis 1 bis 7 von 7

Thema: asuro lernt geregelt fahren

  1. #1
    Moderator Robotik Visionär Avatar von radbruch
    Registriert seit
    27.12.2006
    Ort
    Stuttgart
    Alter
    61
    Beiträge
    5.799
    Blog-Einträge
    8

    asuro lernt geregelt fahren

    Anzeige

    Praxistest und DIY Projekte
    Hallo

    nachdem ich nun 4 Wochen mit meinem "Baby" verbracht habe, kenne ich einige seiner Macken. Aber immer noch erliege ich seinem Scharm. *grins*

    Oki, was ich euch eigentlich zeigen wollte: Mir ist es nun endlich gelungen die Räder meines asuros in der Geschwindigkeit zu regeln. Ein Grund die Korken knallen zu lassen, denn der Weg bis hierher war mehr als nur steinig und steil..
    Code:
    /* Einfache Geschwindigkeitsregelung beider Motoren (Einfache Impulszahl mit 4er-Scheibe)
    
       Über den den zeitlichen Abstand des Hell/Dunkel-Wechsels der ODO-Scheibe wird die Geschwindigkeit
       ermittelt und geregelt. Jedes Rad für sich ohne Beeinflussung der anderen Seite.
    
       15.1.2007
       mic
    
    	Funktion der Tasten:
    
    	T6:                      mehr Speed
    	T5: Fährt endlos vor mit mittlerer Speed
    	T4:                      Weniger Speed
    
    	T3:                       grosser Geschwindigkeit
    	T2: kurze Strecke vor mit mittlerer Geschwindigkeit
    	T1:                       kleiner Geschwindigkeit
    
    	Anhalten nach T5 über T1/T2/T3
    
    	Wenn die Motoren stehen werden die ODO-Daten mit der StatusLED 
    	angezeigt. 
    
    	Die Segmentwechsel der ODO-Scheiben werden mit der StatusLED angezeigt. 
     
    */
    
    
    #include <asuro.h>
    
    unsigned char sw_data, sw0, sw1, sw2, sw3, i, tmp_char, step, power;
    unsigned int data[2], j, tmp_int, loops, strecke, delay;
    unsigned long akt, loop_count, loop_delay;
    
    unsigned int speed_l, speed_r, power_l, power_r, count_l, count_r, imp_l, imp_r;
    unsigned int speed_soll_l, speed_soll_r, speed_count_l, speed_count_r, speed_max_l, speed_max_r;
    unsigned int odo_l, odo_old_l, odo_min_l, odo_max_l, odo_bit_l, o1_l, o2_l, o3_l;
    unsigned int odo_r, odo_old_r, odo_min_r, odo_max_r, odo_bit_r, o1_r, o2_r, o3_r;
    unsigned int odo_impbit_l, odo_impbit_r, odo_implevel_l, odo_implevel_r;
    
    char getswitch(void) {
        sw3=sw2; sw2=sw1; sw1=sw0; sw0=PollSwitch();
        if ((sw0==sw1) && (sw0==sw2) && (sw0==sw3)) sw_data=sw0; else sw_data=0;
        return(sw_data);
    }
    
    void count(void) {
    
        OdometrieData(data); akt=loop_count;
        if ((data[0]<o1_l) && (o1_l<o2_l) && (o2_l<o3_l)) {
            if (!odo_bit_l) {
                count_l ++; odo_bit_l=(1==1); StatusLED(YELLOW);
                odo_max_l=data[0];
                imp_l ++; odo_implevel_l=(odo_max_l-odo_min_l)/4;
                speed_l=akt-speed_count_l; speed_count_l=akt;
                //if (speed_l<speed_max_l) speed_max_l=speed_l;
            }
            if (odo_impbit_l && (data[0] < odo_implevel_l)) {
                imp_l ++; odo_impbit_l=(1==0);
            }
        }
        if ((data[0]>o1_l) && (o1_l>o2_l) && (o2_l>o3_l)) {
            if (odo_bit_l) {
                count_l ++; odo_bit_l=(1==0); StatusLED(OFF);
                odo_min_l=data[0];
                imp_l ++; odo_implevel_l=((odo_max_l-odo_min_l)/4)*3;
                speed_l=akt-speed_count_l; speed_count_l=akt;
                //if (speed_l<speed_max_l) speed_max_l=speed_l;
            }
            if (!odo_impbit_l && (data[0] > odo_implevel_l)) {
                imp_l ++;  odo_impbit_l=(1==1);
            }
        }
    
        if ((data[1]<o1_r) && (o1_r<o2_r) && (o2_r<o3_r)) {
            if (!odo_bit_r) {
                count_r ++; odo_bit_r=(1==1); StatusLED(RED);
                odo_max_r=data[1];
                imp_r ++; odo_implevel_r=(odo_max_r-odo_min_r)/4;
                speed_r=akt-speed_count_r; speed_count_r=akt;
                //if (speed_r<speed_max_r) speed_max_r=speed_r;
            }
            if (odo_impbit_r && (data[1] < odo_implevel_r)) {
                imp_r ++; odo_impbit_r=(1==0);
            }
        }
        if ((data[1]>o1_r) && (o1_r>o2_r) && (o2_r>o3_r)) {
            if (odo_bit_r) {
                count_r ++; odo_bit_r=(1==0); StatusLED(OFF);
                odo_min_r=data[1];
                imp_r ++; odo_implevel_r=((odo_max_r-odo_min_r)/4)*3;
                speed_r=akt-speed_count_r; speed_count_r=akt;
                //if (speed_r<speed_max_r) speed_max_r=speed_r;
            }
            if (!odo_impbit_r && (data[1] > odo_implevel_r)) {
                imp_r ++;  odo_impbit_r=(1==1);
            }
        }
    
        o3_l=o2_l; o2_l=o1_l; o1_l=data[0];
        o3_r=o2_r; o2_r=o1_r; o1_r=data[1];
    }
    
    int main(void) {
    Init();
    SerWrite("\nHallo\nBatterie: ",17);
    PrintInt(Batterie());
    loop_count=0; loop_delay=0; loops=0; step=0; delay=1000; strecke=80; power=125;
    
    OdometrieData(data);
    odo_l=data[0]; odo_old_l=odo_l; odo_min_l=200; odo_max_l=500;
    odo_r=data[1]; odo_old_r=odo_r; odo_min_r=200; odo_max_r=500;
    
    power=1;
    
    do {
        loop_count ++; sw_data=getswitch();
    
        switch (sw_data) {
        case(32): speed_soll_l=speed_soll_r+=1; step=20; break;
        case(16): speed_soll_l=speed_soll_r=15; power_l=power_r=50; step=20; break;
        case (8): speed_soll_l=speed_soll_r-=1; step=20; break;
        case (4): speed_soll_l=speed_soll_r=5; power_l=power_r=50; count_l=count_r=0; step=10; break;
        case (2): speed_soll_l=speed_soll_r=10; power_l=power_r=50; count_l=count_r=0; step=10; break;
        case (1): speed_soll_l=speed_soll_r=15; power_l=power_r=50; count_l=count_r=0; step=10; break;
        }
    
        if (loop_count > loop_delay) switch (step) {
    
        case(10): if (speed_l>speed_soll_l) power_l+=power; if (speed_r>speed_soll_r) power_r+=power;
                  if (speed_l<speed_soll_l) power_l-=power; if (speed_r<speed_soll_r) power_r-=power;
                  step++; break;
    
        case(11): MotorSpeed(power_l,power_r); if ((count_l+count_r)<500) step--; else step++; break;
        case(12): MotorSpeed(0,0); step++; break;
        case(13): SerWrite("+",1); PrintInt(speed_max_l); step++; break;
        case(14): SerWrite("-",1); PrintInt(speed_max_r); step=99; break;
    
        case(20): if (speed_l>speed_soll_l) power_l+=power; if (speed_r>speed_soll_r) power_r+=power;
                  if (speed_l<speed_soll_l) power_l-=power; if (speed_r<speed_soll_r) power_r-=power;
                  step++; break;
        case(21): MotorSpeed(power_l,power_r); step--; break;
        case(99): StatusLED(GREEN); break;
        }
        count();
    }while (1);
    return 0;
    }
    (Der Code ist die orginale Version!)

    Das zuckelt und ruckelt und sieht eher wie torkeln aus. Ursache ist die extrem kleine Pulszahl der 4er-ODO-Scheibe des asuro. Ich habe in diesen Code nun noch rechnerisch eine zweite Flanke eingebaut und mit den selben Parametern sieht das nun so aus:
    Code:
    /* Einfache Geschwindigkeitsregelung beider Motoren (Doppelte(!) Impulszahl mit 4er-Scheibe)
    
       Über den den zeitlichen Abstand des Hell/Dunkel-Wechsels der ODO-Scheibe wird die Geschwindigkeit
       ermittelt und geregelt. Jedes Rad für sich ohne Beeinflussung der anderen Seite.
    
       Es wird zusätzlich auch die zweite Flanke der ODO-Scheibe erkannt.
    
       15.1.2007
       mic
    
    	Funktion der Tasten:
    
    	T6:                      mehr Speed
    	T5: Fährt endlos vor mit mittlerer Speed
    	T4:                      Weniger Speed
    
    	T3:                       grosser Geschwindigkeit
    	T2: kurze Strecke vor mit mittlerer Geschwindigkeit
    	T1:                       kleiner Geschwindigkeit
    
    	Anhalten nach T5 über T1/T2/T3
    
    	Die Segmentwechsel der ODO-Scheiben werden mit der StatusLED angezeigt. 
    
     
    */
    #include <asuro.h>
    
    unsigned char sw_data, sw0, sw1, sw2, sw3, i, tmp_char, step, power;
    unsigned int data[2], j, tmp_int, loops, strecke, delay;
    unsigned long akt, loop_count, loop_delay;
    
    unsigned int speed_l, speed_r, power_l, power_r, count_l, count_r, imp_l, imp_r;
    unsigned int speed_soll_l, speed_soll_r, speed_count_l, speed_count_r, speed_max_l, speed_max_r;
    unsigned int odo_l, odo_old_l, odo_min_l, odo_max_l, odo_bit_l, o1_l, o2_l, o3_l;
    unsigned int odo_r, odo_old_r, odo_min_r, odo_max_r, odo_bit_r, o1_r, o2_r, o3_r;
    unsigned int odo_impbit_l, odo_impbit_r, odo_implevel_l, odo_implevel_r;
    
    char getswitch(void) {
        sw3=sw2; sw2=sw1; sw1=sw0; sw0=PollSwitch();
        if ((sw0==sw1) && (sw0==sw2) && (sw0==sw3)) sw_data=sw0; else sw_data=0;
        return(sw_data);
    }
    
    void count(void) {
    
        OdometrieData(data); akt=loop_count;
        if ((data[0]<o1_l) && (o1_l<o2_l) && (o2_l<o3_l)) {
            if (!odo_bit_l) {
                count_l ++; odo_bit_l=(1==1); StatusLED(YELLOW);
                odo_max_l=data[0];
                imp_l ++; odo_implevel_l=(odo_max_l-odo_min_l)/4;
                speed_l=akt-speed_count_l; speed_count_l=akt;
                //if (speed_l<speed_max_l) speed_max_l=speed_l;        }
            }
            if (odo_impbit_l && (data[0] < odo_implevel_l)) {
                imp_l ++; odo_impbit_l=(1==0);
                speed_l=akt-speed_count_l; speed_count_l=akt;
            }
        }
        if ((data[0]>o1_l) && (o1_l>o2_l) && (o2_l>o3_l)) {
            if (odo_bit_l) {
                count_l ++; odo_bit_l=(1==0); StatusLED(OFF);
                odo_min_l=data[0];
                imp_l ++; odo_implevel_l=((odo_max_l-odo_min_l)/4)*3;
                speed_l=akt-speed_count_l; speed_count_l=akt;
                //if (speed_l<speed_max_l) speed_max_l=speed_l;        }
            }
            if (!odo_impbit_l && (data[0] > odo_implevel_l)) {
                imp_l ++;  odo_impbit_l=(1==1);
                speed_l=akt-speed_count_l; speed_count_l=akt;
            }
        }
    
        if ((data[1]<o1_r) && (o1_r<o2_r) && (o2_r<o3_r)) {
            if (!odo_bit_r) {
                count_r ++; odo_bit_r=(1==1); StatusLED(RED);
                odo_max_r=data[1];
                imp_r ++; odo_implevel_r=(odo_max_r-odo_min_r)/4;
                speed_r=akt-speed_count_r; speed_count_r=akt;
                //if (speed_r<speed_max_r) speed_max_r=speed_r;        }
            }
            if (odo_impbit_r && (data[1] < odo_implevel_r)) {
                imp_r ++; odo_impbit_r=(1==0);
                speed_r=akt-speed_count_r; speed_count_r=akt;
            }
        }
        if ((data[1]>o1_r) && (o1_r>o2_r) && (o2_r>o3_r)) {
            if (odo_bit_r) {
                count_r ++; odo_bit_r=(1==0); StatusLED(OFF);
                odo_min_r=data[1];
                imp_r ++; odo_implevel_r=((odo_max_r-odo_min_r)/4)*3;
                speed_r=akt-speed_count_r; speed_count_r=akt;
                //if (speed_r<speed_max_r) speed_max_r=speed_r;
            }
            if (!odo_impbit_r && (data[1] > odo_implevel_r)) {
                imp_r ++;  odo_impbit_r=(1==1);
                speed_r=akt-speed_count_r; speed_count_r=akt;
            }
        }
    
        o3_l=o2_l; o2_l=o1_l; o1_l=data[0];
        o3_r=o2_r; o2_r=o1_r; o1_r=data[1];
    }
    
    int main(void) {
    Init();
    SerWrite("\nHallo\nBatterie: ",17);
    PrintInt(Batterie());
    loop_count=0; loop_delay=0; loops=0; step=0; delay=1000; strecke=80; power=125;
    
    OdometrieData(data);
    odo_l=data[0]; odo_old_l=odo_l; odo_min_l=200; odo_max_l=500;
    odo_r=data[1]; odo_old_r=odo_r; odo_min_r=200; odo_max_r=500;
    
    power=1;
    
    do {
        loop_count ++; sw_data=getswitch();
    
        switch (sw_data) {
        case(32): speed_soll_l=speed_soll_r+=1; step=20; break;
        case(16): speed_soll_l=speed_soll_r=15; power_l=power_r=50; step=20; break;
        case (8): speed_soll_l=speed_soll_r-=1; step=20; break;
        case (4): speed_soll_l=speed_soll_r=5; power_l=power_r=50; count_l=count_r=0; step=10; break;
        case (2): speed_soll_l=speed_soll_r=10; power_l=power_r=50; count_l=count_r=0; step=10; break;
        case (1): speed_soll_l=speed_soll_r=15; power_l=power_r=50; count_l=count_r=0; step=10; break;
        }
    
        if (loop_count > loop_delay) switch (step) {
    
        case(10): if (speed_l>speed_soll_l) power_l+=power; if (speed_r>speed_soll_r) power_r+=power;
                  if (speed_l<speed_soll_l) power_l-=power; if (speed_r<speed_soll_r) power_r-=power;
                  step++; break;
    
        case(11): MotorSpeed(power_l,power_r); if ((count_l+count_r)<500) step--; else step++; break;
        case(12): MotorSpeed(0,0); step++; break;
        case(13): SerWrite("+",1); PrintInt(speed_max_l); step++; break;
        case(14): SerWrite("-",1); PrintInt(speed_max_r); step=99; break;
    
        case(20): if (speed_l>speed_soll_l) power_l+=power; if (speed_r>speed_soll_r) power_r+=power;
                  if (speed_l<speed_soll_l) power_l-=power; if (speed_r<speed_soll_r) power_r-=power;
                  step++; break;
        case(21): MotorSpeed(power_l,power_r); step--; break;
        case(99): StatusLED(GREEN); break;
        }
        count();
    }while (1);
    return 0;
    }
    Sieht schon besser aus. Gelegentlich spinnt das ganze zwar noch etwas, aber als Ansatz finde ich das schon recht nett.

    Gruß

    mic
    Angehängte Dateien Angehängte Dateien
    Bild hier  
    Atmel’s products are not intended, authorized, or warranted for use
    as components in applications intended to support or sustain life!

  2. #2
    Moderator Robotik Visionär Avatar von radbruch
    Registriert seit
    27.12.2006
    Ort
    Stuttgart
    Alter
    61
    Beiträge
    5.799
    Blog-Einträge
    8
    Kein Wunder, dass der so eiert, hier hat sich im Schatten der Nacht der Fehlerteufel eingeschlichen. Keine Ahnung, warum sich überhaupt was bewegt, vermutlich schwingt er irgendwie frei. Aber der Weg scheint mir richtig, ich bastle noch ein wenig weiter.
    Bild hier  
    Atmel’s products are not intended, authorized, or warranted for use
    as components in applications intended to support or sustain life!

  3. #3
    Moderator Robotik Einstein Avatar von damaltor
    Registriert seit
    28.09.2006
    Ort
    Milda
    Alter
    38
    Beiträge
    4.064
    du könntest auch die andere odo scheibe aufkleben... die wird allgemein meistens benutzt.

    wenn das ganze zwischendurch mal spinnt, dann meist weil plötzlich mehr oder weniger störlich auf dei Sensoren fällt, oder weil das zahnrad auf der achse 1-2 mm vom sensor weg und wieder hin rutschen kann. dadurch ergibt (ergab... *heul*) sich bei mir ein unterschied von fast 300 einheiten.
    Read... or die.
    ff.mud.de:7600
    Bild hier  

  4. #4
    Benutzer Stammmitglied
    Registriert seit
    29.12.2006
    Ort
    Bayern
    Alter
    69
    Beiträge
    41
    ... das mit dem axialen Spiel der ODO-Scheibe habe ich folgendermaßen in den Griff bekommen:
    Z.B. Conrad hat sog. Wellensicherungsringe (Bestellnr. 237531-00), die sich wunderbar seitlich außen auf die Achse pfriemeln lassen und so das seitliche Spiel minimieren. Kann ich nur empfehlen.
    Aber Achtung: Vorsicht, wenn Ihr die Ringe montiert, nicht dass Ihr mit der Zange die Kunststoffzahnräder zerstört - sonst **heul**

    Grüße vom Hans.

  5. #5
    Moderator Robotik Visionär Avatar von radbruch
    Registriert seit
    27.12.2006
    Ort
    Stuttgart
    Alter
    61
    Beiträge
    5.799
    Blog-Einträge
    8
    Hallo

    Das Einlesen der Odo-Werte funktioniert sehr zuverlässig, ich habe die Zahnräder axial fixiert und die Sensoren abgedeckt.

    In dieser Programmversion lese ich die Werte mehrfach hintereinander aus und wenn alle Werte auf- bzw absteigend sind, ist das der Anfang der abfallenden oder ansteigenden Flanke. Mein Min-/Max-Werte sind ca. 650/150, aber das ist eigentlich unwichtig weil ich ja nicht auf absolute Werte prüfe sondern auf die Folge der Werte.

    So kann ich allerdings nur den Beginn der Flanke auswerten was Probleme bereitet, wenn ich z.b. die Drehrichtung ändere und den Bitwechsel als Anlauferkennung verwende. Je nach Abstand zur nächsten Flanke erkenne ich früher oder später die beginnende Bewegung. Bei später ist aber der Primitiv-Regler schon so weit aufgerissen dass ein teilweise extremes Schwingen einsetzt.

    Mein größtes Problem ist aber die Regelung in Verbindung mit der geringen Impulszahl der Odometrie. Da ich kein Matheass bin und von Integralen keine Ahnung habe, versuche ich die Methoden für PI oder gar PID-Regler aus den diversen Ansätzen hier im Forum abzukupfern.

    Gruß

    mic
    Bild hier  
    Atmel’s products are not intended, authorized, or warranted for use
    as components in applications intended to support or sustain life!

  6. #6
    Moderator Robotik Visionär Avatar von radbruch
    Registriert seit
    27.12.2006
    Ort
    Stuttgart
    Alter
    61
    Beiträge
    5.799
    Blog-Einträge
    8
    Hallo

    Mit optimierter Odometrie klappts nun deutlich besser:

    Taste 1: Strecke vorwärtes
    Taste 2: Strecke rückwärts
    Taste 3: Drehen
    Taste 4: Endlos vor und drehen
    Taste 5: Regelverstärkung klein
    Taste 6: Regelverstärkung gross
    (Taste 1 ist die rechte Taste)

    Die StatusLED zeigt die Hell/Dunkel-Bereiche der Codierscheibe an:

    Gelb - Hell links
    Rot - Hell rechts
    Aus - Dunkel links/rechts

    Die FrontLED leuchtet, wenn eine aufsteigende Flanke erkannt wurde, bei einer erkannten absteigenden Flanke wird die FrontLED ausgeschaltet. Beide Seiten werden zusammen angezeigt. Sehr nett anzuschauen wenn man bei stehenden Motoren an den Rädern rumfummelt.

    Ein kleiner, aber interessanter Bug in diesem Program ist die Tatsache, dass der asuro jetzt erst losfährt, wenn sich an einem Rad ein Bit ändert. Das muss natürlich noch beseitigt werden, aber zur Demo passt dieses Verhalten sehr gut:
    Code:
    #include <asuro.h>
    
    unsigned char sw_data, sw0, sw1, sw2, sw3, i, tmp_char, step;
    unsigned int data[2], j, tmp_int, loops, delay;
    unsigned long akt, loop_count, loop_delay;
    
    unsigned int speed_l, speed_r, power_l, power_r, count_l, count_r, imp_l, imp_r, p, p_l, p_r;
    unsigned int speed_soll_l, speed_soll_r, speed_count_l, speed_count_r, speed_max_l, speed_max_r;
    unsigned int odo_l, odo_old_l, odo_min_l, odo_max_l, odo_low_l, odo_high_l;
    unsigned int odo_minmax_bit_l, odo_bit_l, o1_l, o2_l, o3_l;
    unsigned int odo_r, odo_old_r, odo_min_r, odo_max_r, odo_low_r, odo_high_r;
    unsigned int odo_minmax_bit_r, odo_bit_r, o1_r, o2_r, o3_r;
    
    char getswitch(void) {
        sw3=sw2; sw2=sw1; sw1=sw0; sw0=PollSwitch();
        if ((sw0==sw1) && (sw0==sw2) && (sw0==sw3)) sw_data=sw0; else sw_data=0;
        return(sw_data);
    }
    
    void count1(void){
        OdometrieData(data); akt=loop_count;
        if ((!odo_minmax_bit_l) && (data[0]<o1_l) && (o1_l<o2_l) && (o2_l<o3_l)) {
                odo_minmax_bit_l=(1==1);
                odo_max_l=data[0];
                FrontLED(ON);
        }
        if ((odo_minmax_bit_l) && (data[0]>o1_l) && (o1_l>o2_l) && (o2_l>o3_l)) {
                odo_minmax_bit_l=(1==0);
                odo_min_l=data[0];
                FrontLED(OFF);
        }
    
        if ((!odo_minmax_bit_r) && (data[1]<o1_r) && (o1_r<o2_r) && (o2_r<o3_r)) {
                odo_minmax_bit_r=(1==1);
                odo_max_r=data[1];
                FrontLED(OFF);
        }
        if ((odo_minmax_bit_r) && (data[1]>o1_r) && (o1_r>o2_r) && (o2_r>o3_r)) {
                odo_minmax_bit_r=(1==0);
                odo_min_r=data[1];
                FrontLED(ON);
        }
        o3_l=o2_l; o2_l=o1_l; o1_l=data[0];
        o3_r=o2_r; o2_r=o1_r; o1_r=data[1];
        odo_low_l=((odo_min_l + odo_max_l)/3);  //  je ein drittel high-nix-low
        odo_high_l=((odo_min_l + odo_max_l)/3)*2;
        odo_low_r=((odo_min_r + odo_max_r)/3);  //  je ein drittel high-nix-low
        odo_high_r=((odo_min_r + odo_max_r)/3)*2;
    
    
        if (!odo_bit_l & (data[0] > odo_high_l)) {
            odo_bit_l=1; count_l ++; StatusLED(YELLOW);
                speed_l=akt-speed_count_l; speed_count_l=akt;
        }
        if (odo_bit_l & (data[0] < odo_low_l)) {
            odo_bit_l=0; count_l ++; StatusLED(OFF);
                speed_l=akt-speed_count_l; speed_count_l=akt;
        }
        if (!odo_bit_r & (data[1] > odo_high_r)) {
            odo_bit_r=1; count_r ++; StatusLED(RED);
                speed_r=akt-speed_count_r; speed_count_r=akt;
        }
        if (odo_bit_r & (data[1] < odo_low_r)) {
            odo_bit_r=0; count_r ++; StatusLED(OFF);
                speed_r=akt-speed_count_r; speed_count_r=akt;
        }
    }
    
    int drive(int weg_l, int weg_r, int v_l, int v_r) {
    static char dstep=0;
    switch (dstep) {
    case(0): if ((weg_l==weg_r) && (v_l==v_r)) dstep=10; else dstep=10; break;
    
    case(10): count_l=count_r=0; power_l=power_r=50; p_l=p_r=p; speed_soll_l=speed_soll_r=5; dstep++; break;
    case(11): if (speed_l>speed_soll_l) power_l+=p_l; if (speed_l<speed_soll_l) power_l-=p_l;
        if (speed_r>speed_soll_r) power_r+=p_r; if (speed_r<speed_soll_r) power_r-=p_r;
        if (count_l>=1) p_l=3; if (count_r>=1) p_r=3;
        if (count_l+count_r<=5) {power_l=count_r-count_l; power_r=count_l-count_r;}
        //if (count_l>=50) speed_max_l=speed_l; if (count_r>=50) speed_max_r=speed_r;
        dstep++; break;
    case(12): MotorSpeed(power_l,power_r); if (count_l<weg_l) dstep--; else dstep++; break;
    case(13): power_l-=p; power_r-=p; MotorSpeed(power_l,power_r); if (power_l<=50) dstep++; break;
    case(14): MotorSpeed(0,0); dstep=0; break;
    }
    return(dstep>0);
    
    }
    
    int main(void) {
    Init();
    SerWrite("\nHallo\nBatterie: ",17); PrintInt(Batterie());
    
    loop_count=0; loop_delay=0; loops=0; step=99; delay=1000;
    
    OdometrieData(data);
    odo_l=data[0]; odo_old_l=odo_l; odo_min_l=200; odo_max_l=500;
    odo_r=data[1]; odo_old_r=odo_r; odo_min_r=200; odo_max_r=500;
    
    speed_max_l=speed_max_r=100;
    
    p=5;
    
    do {
        loop_count ++; sw_data=getswitch();
    
        switch (sw_data) {
        case(32): p=10; break;
        case(16): p=5; break;
        case (8): MotorDir(FWD,FWD); step=20; break;
        case (4): MotorDir(FWD,RWD); step=10; break;
        case (2): MotorDir(RWD,RWD); step=10; break;
        case (1): MotorDir(FWD,FWD); step=10; break;
        }
    
        if (loop_count > loop_delay) switch (step) {
    
        case(10): if (drive(300,300,5,5)) break; step=99; break;
        case(11): if (drive(200,200,10,10)) break; step=99; break;
        case(12): if (drive(50,50,15,15)) break; step=99; break;
        case(20): if (drive(100,100,10,10)) break; MotorDir(RWD,FWD); step++; break;
        case(21): if (drive(20,20,15,15)) break; MotorDir(FWD,FWD); step--; break;
        case(99): break;
        }
        count1();
    }while (1);
    return 0;
    }
    Den Code muss man natürlich noch putzen, aber den Ansatz finde ich nett.

    Gruss

    mic
    Angehängte Dateien Angehängte Dateien

  7. #7
    Benutzer Stammmitglied
    Registriert seit
    29.12.2006
    Ort
    Bayern
    Alter
    69
    Beiträge
    41
    Hallo,

    das Problem mit der zu niedrigen Pulsfrequenz der ODO-Scheiben habe ich natürlich auch.
    Ich erhalte je 2mm gefahrenen Weg 1 Impuls. Die P- oder PD-Regelungschleife sollte so ca alle 10/1000 (Ta=10/1000) Sekunden abgearbeitet werden um eine vernünftige Regelung zu ermöglichen.
    Bei einer Geschwindigkeit von 100 mm/sek. fährt der Asuro 1mm je 10/1000 Sekunden. Ich erhalte also keinen einzigen Impuls während der Zeit bis wieder ein Regeldurchgang nötig wird.
    Erhöht man die Geschw. auf 200 mm/ Sek. so erhält man einen Impuls. Das ist aber auch viel zu wenig für eine vernünftige Regelung.
    Selbst wenn man Ta verdoppelt, ist keine PD-Regelung möglich.
    Man braucht also mehr Impulse pro Umdrehung.
    Möglichkeiten wären:
    1. Impulsscheibe direkt auf das Motorritzel kleben und in die vorgesehenen Aufnahmepunkte bei den Motoren die selbe ODO-Maschinerie (Diode+Phototransistor) aufbauen. So hat man die 5-fache Impulsanzahl (Übersetzung 10/50 denke ich)
    2. Das große ODO-Zahnrad auf einen Teilapparat spannen und mit Löchern im Umkreis versehen. So ca. 40 – 50 sollten möglich sein. Dann mittels Gabellichtschranke die Impulse mit dem Atmel zählen.
    3. Vielleicht ist es sogar möglich die Zahnflanken des ODO-Zahnrades mit einer Gabellichtschranke zu zählen

    Grüße, Hans.
    P.S.: Meine Regelsoftware ist etwas fett geraden. Ich werde sie reinstellen, wenn ich die Bugs rausgefiltert habe – bin noch am kämpfen.

Berechtigungen

  • Neue Themen erstellen: Nein
  • Themen beantworten: Nein
  • Anhänge hochladen: Nein
  • Beiträge bearbeiten: Nein
  •  

12V Akku bauen