- Akku Tests und Balkonkraftwerk Speicher         
Ergebnis 1 bis 10 von 15

Thema: Servo ansteuerung durch pwm

Hybrid-Darstellung

Vorheriger Beitrag Vorheriger Beitrag   Nächster Beitrag Nächster Beitrag
  1. #1
    Erfahrener Benutzer Begeisterter Techniker
    Registriert seit
    11.01.2008
    Ort
    Krefeld
    Beiträge
    272
    Also wenn cih den servo durch andere port steuern kann, geh ich von aus das er ein ausreichende versorgung hat oder?
    Die belegung ist einfach
    rot = 5V
    Schwarz= masse
    orange = Signal auf OCR1a...

    Also ich hab ehrlich nur das projekt aufgemacht und die sachen rein kopiert ... alle anderen komponente rausgesteckt nur den Servo angeschlossen und gestartet....
    Nach den Code müsste der servo nach einander auf alle drei stellungen gehen und von vorne anfangen aber er bewegt sich nur beim einschalten vom controller kurz....
    Habe danach auch versucht den servo an den motortreiber dran zu tun, an den wo der getriebe motor immer lief aber da tut sich auch nichts, und kaputt ist er glaube ich nicht weil ich
    kann ihn mit PORTC ansteuern....
    hat jemand ein anderen tipp für mich?
    Ich kam, sah und alles funktionierte **** doch dann klingelte mein Wecker!!!

  2. #2
    Erfahrener Benutzer Begeisterter Techniker Avatar von Torrentula
    Registriert seit
    10.10.2009
    Ort
    Procyon A
    Beiträge
    355
    Benutzt du das AVRStudio5? Wenn ja solltest du die Compiler-Optimizations auf "optimize for size" stellen, da sonst _delay_ms() nicht funktioniert und zusätzlich muss auch noch F_CPU irgendwo definiert sein (im Makefile oder im Quellcode selbst mit #define F_CPU 16000000UL).

    Wenn du WinAVR benutzt sollte das Makefile eigentlich alles übernehmen (sofern der richtige Controller und Quarzfrequenz eingestellt sind).

    kann ihn mit PORTC ansteuern....
    Wie meinst du das du kannst ihn über PORTC ansteuern?

    MfG

    Torrentula
    MfG Torrentula

  3. #3
    Erfahrener Benutzer Begeisterter Techniker
    Registriert seit
    11.01.2008
    Ort
    Krefeld
    Beiträge
    272
    Ok, mach ich sobald ich zuhause bin ....
    also ich kann den servo ja ne 1 geben und dan geht er an und mit pausen kann ich ihn dann ansteurn bis zum anschlag.
    darum bin ich der meinung wenn das geht, sollte er nicht kaputt gehen
    Ich kam, sah und alles funktionierte **** doch dann klingelte mein Wecker!!!

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

    Aber ein pwm signal im timer mit einer bestimmte breite für ein servo zu erstellen, bekomme ich nicht hin
    Das wollte ich mal aufgreifen. 16-Bit Hardware-PWM für Servos zu verschwenden kann man sich meist nicht leisten, weil man das mit der Getriebemotoransteuerung belegt hat. Zufällig sind die OC1A- und OC1B-Pins an meinem cat16 nicht belegt, deshalb möchte ich mal zeigen, wie man das angehen könnte. (btw.: Es gibt 1001 Möglichkeiten ein Servo anzusteuern und man kann ungemein weit abschweifen, wenn man es erklären will.)

    Mit etwas Grundwissen über Servosignale, dem Datenblatt und einem Taschenrechner bewaffnet gehen wir ans Werk: Da die Servoimpulse alle 20ms gesendet werden sollten (alle Angaben über die Impulswiederholung beziehen sich auf analoge Servos!), berechnen wir zuerst, wieviele Systemtakte in 20ms vergehen: 16MHz/20ms sind 16000000/0,02 oder 320000 Systemtakte. Also müssen wir bei einem 16MHz-Systemtakt immer nach 320000 Takten einen Impuls senden. Soviele Takte können wir aber mit einem 16-Bit-Timer nicht zählen, deshalb verwenden wir den Vorteiler (=prescaler) um die Systemtakte vorzuteilen und einen eigenen Takt für den Timer zu erzeugen. Das geübte Auge erkennt sofort, das 320000/8 genau 40000 Takte ergibt. Das bedeutet, mit einem Perscaler von /8 passt der 20ms-Bereich in ein 16-Bit-Register und dass nach 8 Systemtakten jeweils ein Timertakt abgearbeitet wird.

    Günstig wäre, wenn der Timer von alleine, also ohne ISR-Aufruf, genau in einem 20ms-Zyklus laufen und nebenher noch die Impulse am OC1x-Pin erzeugen würde. Deshalb wählen wir Mode 14: "FastPWM mit ICR1 als Top". Was bedeutet das? In diesem Mode zählt der Timer immer von 0 bis zu dem Wert der im ICR1-Register steht. Wenn der Zähler den ICR1-Wert erreicht hat, startet er wieder bei 0. Wenn wir 40000 ins ICR1-Register schreiben, haben wir genau den gewünschten 20ms-Zyklus.

    Für die Impulserzeugung müssen wir die Ausgabe der Impulse an den OC1x-Pins aktivieren. Wir wählen den "non-inverting Mode": Clear OC1A/OC1B on compare match, set OC1A/OC1B at BOTTOM.

    Nun müssen wir noch den Wert für den Compare-Match im OCR1x-Register festlegen. Match ist, wenn das Zählregister des Timers den Wert im OCR1x-Register erreicht hat und der Ausgang von high nach low geschaltet wird. Dieser Wert ist die Impulslänge und sollte für eine Millisekunde 20ms/20 oder 40000/20=2000 Takte sein. (Bei meinen ES5-Servos ist die Mitte des Drehbereichs etwa OCR1x=3000 oder 1,5ms)

    Das war's schon. Jetzt noch die Datenrichtungsregister der OC1X-Pins auf Ausgang schalten und fertig:

    Code:
    // Servoansteuerung mit 16Bit-Timer1 Hardware-PWM (2 Servos mit arexx cat16) mic 21.10.2011
    
    #include <avr/io.h>
    #include <avr/interrupt.h> // wegen cli() und sei()
    
    // Definitionen für das cat16
    # define OC1A 				PD5
    # define OC1B 				PD4
    
    # define servoa_DDR		DDRB
    # define servoa_PORT 	PORTB
    # define servoa_PIN 		PB0
    # define servob_DDR		DDRB
    # define servob_PORT 	PORTB
    # define servob_PIN 		PB1
    
    #define green	0x10
    #define red		0x20
    #define yellow 0x30
    
    // Funktionen fürs cat16
    void sleep(uint16_t pause);                   // ca. 1/1000 Sekunde blockierende Pause
    void leds(uint8_t mask);
    
    int main(void)
    {
    	cli();
    
    	// InitSPI für Leds des cat16
    	// Disable SPI, Master, set clock rate fck/128
       SPCR = ( (0<<SPE)|(1<<MSTR) | (1<<SPR1) |(1<<SPR0));
    
    	DDRB = 0b10110011;                        // SCK: PD7, MoSi: PB5, SS: PB4 (!)?
    	DDRC = 0b11111100;                        // und Servoausgänge setzen
    	DDRD = 0b01000000;                        // PD6 ist STRB fürs 4094
    
    	// Timer1 für 16MHz-ATMega16
      	TCCR1A = 0;
      	TCCR1B = (0<<CS12)|(1<<CS11)|(0<<CS10);	// prescaler /8
    
    	TCCR1A |= (1<<WGM11)|(0<<WGM10);       	// Mode 14: FastPWM mit ICR1 als Top
    	TCCR1B |= (1<<WGM13)|(1<<WGM12);
    
    	TCCR1A |= (1<<COM1A1)|(0<<COM1A0);       	// OCR1A set on Botton, reset on Match
    	TCCR1A |= (1<<COM1B1)|(0<<COM1B0);       	// OCR1B set on Botton, reset on Match
    
    	TCNT1 = 0;                                // Timer1 zurücksetzen;
       ICR1 = 40000;                             // 16MHz/8/20mS für 20ms-Zyklus
    	OCR1A = 3000;                             // Match und OC1A auf Low nach 1ms
    	OCR1B = 3000;                             // Match und OC1B auf Low nach 1ms
    
    	DDRD |= (1<<OC1A) | (1<<OC1B);         	// PWM-Pins sind Ausgang...
    	PORTD &= ~((1<<OC1A) | (1<<OC1B));     	// ...und low
    	
    	// Portdefinitionen für das cat16
       servoa_DDR |= (1<<servoa_PIN);
    	servoa_PORT |= (1<<servoa_PIN);
    	servob_DDR |= (1<<servob_PIN);
    	servob_PORT |= (1<<servob_PIN);
    
    	sei();
    	leds(green);
       sleep(1000);
    
    	while(1)                                  // Demo
    	{
          leds(red);
          OCR1A=OCR1B=2000;
          sleep(1000);
    
          leds(yellow);
          OCR1A=OCR1B=4000;
          sleep(1000);
    	}
    	return(0);
    }
    
    void sleep(uint16_t pause)
    {
       uint32_t p = pause*5;
       uint8_t temp = 1;
       if(p) while(p--) while(temp++)
       {
          // OCRx-Pins kopieren auf normale Pins für cat16
          if(PIND & (1<<OC1A)) servoa_PORT |= (1<<servoa_PIN); else servoa_PORT &= ~(1<<servoa_PIN);
          if(PIND & (1<<OC1B)) servob_PORT |= (1<<servob_PIN); else servob_PORT &= ~(1<<servob_PIN);
       }
    }
    void leds(uint8_t mask)
    {
    	SPCR = ( (1<<SPE)|(1<<MSTR) | (1<<SPR1) |(1<<SPR0));
    	SPDR = mask;
    	while(!(SPSR & (1<<SPIF))); // Wait for transmission complete!
    	SPCR = ( (0<<SPE)|(1<<MSTR) | (1<<SPR1) |(1<<SPR0));
    	PORTD |= (1<<6); 	// STRB high
    	PORTD &= ~(1<<6);	// STRB low
    }
    Da meine Servos nicht an den OCR1x-Pins angeschlossen sind, kopiere ich in der sleep()-Funktion die Pegel der OC1x-pins auf frei wählbare Pins. Deshalb verwende ich diese verschachtelten Zählschleifen in sleep(). Wenn die Servos wirklich an den OC1x-Pins angeschlossen sind, kann man die Pausen auch mit delay.h umsetzen. Die Impulserzeugung läuft dann trotzdem im Hintergund ohne dem Kontroller Resourcen zu nehmen.

    Und so sieht das dann aus:



    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!

  5. #5
    Erfahrener Benutzer Begeisterter Techniker
    Registriert seit
    11.01.2008
    Ort
    Krefeld
    Beiträge
    272
    Hey es klappt, aber ....

    jetzt habe ich ein problem was ich noch nie hatte, und zwar läuft das programm nur wenn ich den ISP Programmer mit angeschlossen habe??????
    Wenn ich den roboter nur an der stromversorgung dran habe läuft er nicht mehr, aber nur bei diesem programm und das hört sich ein wenig komisch an ist aber so???
    Wo dran kann da sliegen?


    MFG
    Sp666dy
    Ich kam, sah und alles funktionierte **** doch dann klingelte mein Wecker!!!

  6. #6
    Moderator Robotik Visionär Avatar von radbruch
    Registriert seit
    27.12.2006
    Ort
    Stuttgart
    Alter
    62
    Beiträge
    5.799
    Blog-Einträge
    8
    Durch entfernen des Motortreiber IC´s aus der Fassung, steht PD4 und PD5 zur freien Verfügung.
    (aus http://rn-wissen.de/index.php/RN-Con...per-Funktionen , unter Beschreibung von Port D)

    Würde ich mal versuchen...
    Bild hier  
    Atmel’s products are not intended, authorized, or warranted for use
    as components in applications intended to support or sustain life!

  7. #7
    Erfahrener Benutzer Fleißiges Mitglied
    Registriert seit
    19.03.2010
    Beiträge
    161
    Ich habe mir gerade einen 10-fach Servo Controller gebaut. http://stefanfrings.de/servocontroller/index.html

    Dazu nutze ich einen Timer vom AVR im Fast PWM Modus mit zwei Compare Registern. Um die zwei direkten Ausgänge auf 10 zu erweitern, verwende ich nicht mehr die OCR Ausgänge, sondern eine Interrupt-Routine, die zwischen 2x5 Ausgängen multiplext. Jeder Komparator steuert immer abwechselnd einen von fünf Servos an.

    Vielleicht magst Du von meinem Source abgucken. Den I2C-Teil in der Main-Loop kannst Du ja weglassen.

Ähnliche Themen

  1. RP6 Servo Ansteuerung
    Von Christian3 im Forum Robby RP6
    Antworten: 14
    Letzter Beitrag: 27.05.2012, 22:04
  2. Ansteuerung Servo mit Servo Fkt. oder mit PWM?
    Von cosanostra im Forum Basic-Programmierung (Bascom-Compiler)
    Antworten: 8
    Letzter Beitrag: 14.11.2007, 10:26
  3. Antworten: 3
    Letzter Beitrag: 02.11.2007, 02:41
  4. Servo Ansteuerung
    Von Gerko im Forum Elektronik
    Antworten: 3
    Letzter Beitrag: 26.11.2006, 18:40
  5. Antworten: 4
    Letzter Beitrag: 07.08.2004, 21:13

Berechtigungen

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

Labornetzteil AliExpress