1. Einleitung

Der MakeBlock Ranger Bausatz ist ziemlich cool und bietet einiges. Leider ist eigentlich nur die Block-basierte Programmierung wirklich gut dokumentiert, aber diese hat Grenzen. Dokumentation für die Programmierung mittels C in der Arduino IDE gibt es kaum, zumindest keine offizielle, daher habe ich dieses Tutorial und Anleitung zusammengestellt. Außerdem soll diese Dokumentation als Leitfaden für einen Programmier-/Robotikkurs an der Schule dienen.

Diese Makeblock Ranger Anleitung baut auf vorhandenen Grundlagen zur Arduino-Programmierung auf. Man sollte also schon die Arduino IDE kennen und natürlich auch Grundlagen der C-Programmiersprache beherrschen. In diesem Tutorial bzw. Robotik-Kurs wird gezeigt, wie man den mBot Ranger Bausatz mittels der Arduino-IDE und der C bzw. C++ Programmiersprache programmiert (wenn man also die Stufe der Block-Programmierung überwunden hat).

Es geht also um folgenden Robotor

makeblock mbot ranger

bzw. die darin verbaute Auriga-Platine mit dem ATmega-Prozessor (wie auf einem Arduino Board)

1.1. Überblick über den Roboterbausatz

Als Roboterbausatz wird der Makeblock mBot Ranger verwendet. Es gibt noch andere Makeblock Bausätze. Die Pin/Port-Belegung ist dann etwas anders und es gibt andere Sensoren, aber im Großen und Ganzen funktioniert das alles sehr ähnlich wie bei dem hier beschriebenen mBot Ranger.

Mit dem Bausatz lassen sich 3 verschiedene Modelle bauen (und mit etwas Kreativität noch weitere):

makeblock mbot ranger
Abbildung 1. Land Raider - ein Kettenfahrzeug mit Linienfolgesensor und Abstandsradar
makeblock mbot raptor
Abbildung 2. Dashing Raptor - ähnlich wie Ranger - ohne Ketten zwar weniger cool, dafür schneller unterwegs (auf glatten Fußböden)
makeblock mbot bird
Abbildung 3. Nervous Bird - interessante Demo für die Verwendung des Neigungs-/Beschleunigungssensors (quasi ein Segway-Personal-Transporter ohne Person); mit diesem Modell kann man seine ganze Kreativität bei der Regelungsprogrammierung ausspielen, um das Gefährt auf hügeligem Gelände sicher und mit konstanter Geschwindigkeit fahren zu lassen.

Der MakeBlock Ranger Bausatz verwendet ein Auriga Board mit einem ATmega2560 Prozessor, wie auf dem Arduino Mega 2560 Board (damit ist die Programmierung schon sehr ähnlich der Arduino-Programmierung). Das Auriga-Board ist die Weiterentwicklung des Orion-Boards (welches bei früheren mBot Bausätzen verwendet wurde) und kann einiges mehr.

Hier ist eine Funktions-/Ausstattungsbeschreibung (basierend auf der Produktbeschreibung aus shop.technik-lpe.de:

Der Auriga ist eine gut ausgestattete Hauptsteuerplatine, die speziell für den MINT-Unterricht entwickelt wurde. Basierend auf dem ATmega 2560 sind auf dem Auriga bereits eine Reihe von Sensoren und Aktoren vebaut, und es können externe Sensoren oder Motoren angesteckt werden. Hier ist ein kleiner Überblick:

  • Onboard-Gyroskop, Tonsensor, passiver Summer und Temperatursensor, 2 Lichtsensoren

  • Unterstützt DC-Motoren, Schrittmotoren, Servoregler, Smart Servos, Encoder-Motoren, etc.

  • Kann zwei Encoder-Motoren ansteuern und unterstützt Überstromschutz für 4A (sofort).

  • Unterstützt Bluetooth und drahtlose Bluetooth-Upgrade-Firmware Bluetooth-Dongle

  • Blaue LED

  • WS1282 RGB LED ring

auriga schaubild
Abbildung 4. Schaubild der Aurigaplatine mit verbauten Sensoren
farbcodierung auriga
Abbildung 5. Farbkodierung der Anschlüsse (Details dazu im Kapitel zu den RJ25 Ports)
  • PORT1 - PORT4 unterstützen einen kontinuierlichen 3,5A-Ausgang (max. 5A)

  • PORT1 - PORT4 haben einen Kurzschluss- und Überstromschutz für 3,5A

  • PORT5 - PORT10 unterstützen kontinuierlich 5V DC und 4A Ausgang (max. 3A)

  • PORT5 - PORT10 haben einen Kurzschluss- und Überstromschutz für 3A

  • USB-Anschluss mit antistatischem Schutz (Akkus werden darüber nicht geladen)

1.2. Informationsquellen

Die offizielle Dokumentation des Roboterbausatzes schweigt sich über die Internas und Programmierung der Platine ziemlich aus. Daher basiert diese Anleitung auf Reverse-Engineering, Literaturrecherche im Internet und Sichtung vieler Forenbeiträge.

Viele nachfolgend und in den anderen Teilen beschriebene Details habe ich aus dem englischsprachigen Text von Gosse Adema (https://www.instructables.com/Advanced-Makeblock-Sensors-DIY) gefunden.

Hier sind noch einige Dokumente, die ich zusammengetragen habe:

Auch gibt es zahlreiche Github-Projekte (siehe Schlagwort MakeBlock ).

2. Treiberinstallation und -konfiguration

Bevor man den Roboter bzw. die Auriga-Platine programmieren kann, muss man erstmal das jeweilige Betriebssystem vorbereiten. Für Windows, Linux und MacOS gibt es hier jeweils unterschiedliche Vorgehensweisen.

2.1. Linux

Nachfolgende Schritte sind für ein hinreichend aktuelles Linux beschrieben, konkret Ubuntu 22.04 oder neuer. Eigentlich müsste das Board aber auch mit älteren Systemen wie Ubuntu 18.04 oder so noch problemlos funktionieren.

2.1.1. Verbindung des Auriga-Boards mit den Linux-PC

Der erste Schritt zur Programmierung des Auriga Boards ist es, eine serielle Verbindung mit dem Board aufzubauen. Dazu verbindet man das Board via USB-Kabel mit dem PC.

Wie üblich unter Linux muss der Nutzer zum Zugriff auf COM Ports der Gruppe dialout zugehören.

sudo dmesg sollte dann ausgeben, mit welchem COM-Port das Bord verbunden ist.

Ausgabe von dmesg beim Anstecken des Auriga Boards
> sudo dmesg
[ 1588.506008] usb 3-2: new full-speed USB device number 4 using xhci_hcd
[ 1588.677924] usb 3-2: New USB device found, idVendor=1a86, idProduct=7523, bcdDevice= 2.64
[ 1588.677942] usb 3-2: New USB device strings: Mfr=0, Product=2, SerialNumber=0
[ 1588.677949] usb 3-2: Product: USB Serial
[ 1588.686988] ch341 3-2:1.0: ch341-uart converter detected
[ 1588.701256] usb 3-2: ch341-uart converter now attached to ttyUSB0

2.1.2. Behebung von brttly Problemen

Bei Ubuntu 22.04 und einigen neueren Ubuntu Versionen wird beim Anschließen des Boards an den USB-Port die Verbindung mit /dev/ttyUSB0 kurz hergestellt und gleich wieder unterbrochen

Ab Ubuntu 24.04 scheint das aber kein Problem mehr zu sein.

Ausgabe von sudo dmesg ist ähnlich wie:

[  284.973894] usb 3-4.2: ch34x converter now attached to ttyUSB0
[  285.019333] usb 3-4.2: usbfs: interface 0 claimed by ch34x while 'brltty' sets config #1
[  285.019883] ch34x ttyUSB0: ch34x converter now disconnected from ttyUSB0
[  285.019895] ch34x 3-4.2:1.0: device disconnected

Das Problem liegt daran, dass der brltty-Dienst (braille display driver/Treiber für ein Brailledisplay) dazwischenfunkt.

Den brltty Dienst (Assistenzdienst) schaltet man wie folgt ab:

# Systemdienste deaktivieren
sudo systemctl mask brltty.path
sudo systemctl mask brltty.service

# udev Regeln ausschalten
for f in /usr/lib/udev/rules.d/*brltty*.rules; do
    sudo ln -s /dev/null "/etc/udev/rules.d/$(basename "$f")"
done
# Dienste neu laden
sudo udevadm control --reload-rules

Nun kann man das Board verbinden und sollte die Ausgabe wie oben in Abschnitt 2.1.1 sehen.

2.2. Windows

  • TODO: ch341 Treiber…​

2.3. MacOS

  • TODO: Intel CPUs ch341 Treiber

  • TODO: M CPUs

3. Aufspielen/Aktualisieren der Firmware und ein erstes Testprogramm

3.1. Firmware-Update / Neu-Installieren

Der Makeblock Ranger bzw. das Board und der Prozessor werden mit einer vorinstallierten Firmware geliefert. Diese Firmware ist nichts anderes als ein (recht komplexes) Arduino-Programm. Dieses Programm enthält die Basisfunktionalität (wie im Handbuch beschrieben), einschließlich der Bluetooth-Kommunikation mit der SmartPhone-App.

Dieses Programm (also die Firmware) ist im Quelltext verfügbar. Den kann man sich herunterladen (siehe unten) und nach Belieben anpassen und verändern. Das ist auch einer der Gründe, warum ich die MakeBlock Roboterbausätze ziemlich cool finde. Außerdem kann man in der Firmware jede Menge abgucken.

Wenn man nach dem Hochladen eigener Programme mal wieder die Originalfunktionalität haben will, spielt man einfach dieses Firmware-Programm hoch und hat wieder den Auslieferungszustand. Man kann also nichts kaputt machen :-)

Die originale Firmware stellt auch die Funktionalität für die "Live"-Tests in der mBlock-Umgebung (z.B. zum Sensor-Auslesen) bereit. Sobald man ein anderes Programm hochgeladen hat, funktioniert diese "Live"-Funktionalität nicht mehr. Wenn man also wieder mit der Block-basierten Programmierung in mBlock arbeiten will und dort die "Live"-Test Funktionalität braucht, lädt man einfach die Firmware wieder hoch und mBlock funktioniert wieder wie bisher.

Wie wir später sehen werden, kann man aber über den Serial Monitor der Arduino-IDE alle Sensorwerte bequem ausgeben und braucht die mBlock Oberfläche gar nicht mehr.

3.1.1. Firmware mit mBlock aktualisieren/zurücksetzen

Die Firmware kann auch mit der mBlock Entwicklungsumgebung installiert werden.

In der aktuellen mBlock Webversion scheint der Download der Firmware allerdings nicht mehr robust zu funktionieren. Auch funktionieren die Treiber für Linux nicht mehr und auch sonst scheint die Software nicht (mehr) richtig zu funktionieren. Außerdem ist die original-Firmware seit 2020 nicht mehr weiterentwickelt worden. Daher sollte die Firmware besser wie nachfolgend beschrieben mit der Arduino-IDE aktualisiert werden.

3.2. Makeblock-Libraries über Arduino-IDE Bibliotheksverwaltung installieren

Für das Compilieren der Firmware sind aber noch die Makeblock-Bibliotheken notwendig. Dafür gibt es zwei Methoden:

  1. Installation mittels Arduino-IDE Bibliotheksverwaltung (empfohlen!)

  2. Manuelle Installation der Bibliothek, oder

3.2.1. Installation via Bibliotheksmanager (empfohlen)

Die Installation der makeblock-Bibliothek erfolgt analog zu anderen Arduino-Bibliotheken.

Abgesehen von der Original-Bibliothek gibt es inzwischen verschiedene Forks mit aktualisierten Quelltexten, die einige Fehler beheben. In der aktuellen Version der Arduino-IDE ist eine solche aktualisierte Version auch direkt über den Bibliotheksmanager verfügbar (Bibliotheksverwaltung öffnen und im Filter makeblock eingeben):

arduino ide makeblock library install
Abbildung 6. Bibliotheksmanager in der Arduino-IDE und ausgewählte MakeBlock Dive Updated Bibliothek

3.2.2. Manuelle Installation

Alternativ gibt es auch hier die Möglichkeit, die Bibliothek via Download des Quelltextes manuell zu installieren. Das ist vielleicht mal notwendig, wenn die Bibliothek nicht mehr vom Bibliotheksverwalter angeboten wird.

Man kann so auch aktualisierte Versionen einer Bibliothek installieren, ohne auf die offiziellen Bibliotheksquellen zu warten. Außerdem kann man so eigene Anpassungen in der Bibliothek (so man das braucht) integrieren.

Dazu lädt man den Quelltext herunter, z.B. den MakeBlock Drive Updated Quelltext. Die heruntergeladene Bibliothek kann in der Arduino-IDE via Sketch→Bibliothek einbinden→.ZIP-Bibliothek hinzufügen…​ eingebunden werden.

Die offiziellen MakeBlock-Bibliotheken werden seit 2020 nicht mehr aktiv weiterentwickelt.

Falls man doch mal die Originalversionen braucht: Das offizielle Makeblock-Libraries GitHub Repository enthält die originalen Quelltexte. Man kann die Bibliothek auch über den Link über folgenden Link herunterladen: Makeblock-Libraries - ZIP.

3.3. Software erstellen und Hochladen

Wie üblich in der Arduino IDE wählt man zuerst

3.4. Firmware Update installieren / zurücksetzen

Die Makeblock Bibliothek bringt als Beispiel-Programm die Firmware mit. Man wählt diese über Datei→Beispiele→MakeBlock Drive Updated→Firmware_For_Auriga aus.

Man muss dann in der Arduino-IDE noch den Port und die CPU einstellen: hier wählt man Arduino Mega or Mega 2560 aus (dazu gleich mehr im folgenden Kapitel). Dann kann man das Firmware-Programm übersetzen und hochladen. So kann man nach dem Ausprobieren eigener Programme stets zum Originalzustand zurückkehren.

3.5. Ein erstes Testprogramm

Um das Aufspielen des Programms zu testen, kann man die eingebaute LED auf Pin 13 (wie bei jedem Arduino Board) blinken lassen. Das Programm dazu entspricht dem typischen Arduino Blink-Beispielprogramm:

Triviales Beispielprogramm für ein Arduino-Board. Die eingebaute LED wird ein- und ausgeschaltet. Um sie von der rhythmisch blinkenden anderen blauen LED zu unterscheiden, lassen wir sie lang-kurz blinken.
// Eingebaute LED auf dem Arduino-Board blinken lassen
// Dies ist quasi das Standard-Test-Programm für die meisten Arduino-Boards

int BlueLed = LED_BUILTIN; // Pin 13

void setup() {
  pinMode( BlueLed, OUTPUT);
}

void loop() {
  // lang an
  digitalWrite( BlueLed, HIGH);
  delay (2000);
  // kurz aus
  digitalWrite( BlueLed, LOW);
  delay (500);
}

Die LED ist etwas schwer zu erkennen und liegt einseitig etwas verdeckt. Sehr sinnvoll ist damit ihre Ansteuerung nicht, aber zum Testen kann man das ja mal machen.

auriga Builtin LED
Abbildung 7. Auriga Built-in LED

4. Auriga-Pin/Ports Referenz

Auf dem Auriga-Board ist ein ATmega2560 Prozessor verbaut wie auf dem Arduino Mega 2560 Board (Datenblatt ). Dieser hat insgesamt 54 digitale Ein- und Ausgangspins, wovon 15 mittels PWM angesteuert werden können. Außerdem hat er noch 16 analoge Inputs und 4 UARTs. Das sollte doch für einen kleinen Roboter reichen. Für die Programmierung dieses Mikroprozessors muss man natürlich wissen, welche Pins davon wofür genutzt werden.

In diesem Kapitel wird ein Überblick über diese Pins und deren Verwendung gegeben. Die Informationen in diesem Kapitel sind als Referenz zu verstehen, da die einzelnen Ports und Pins in den nachfolgenden Kapiteln für alle Komponenten nochmal einzeln eingeführt und erklärt werden. Wer möchte, kann also gerne zum ersten echten Programmierkapitel (Abschnitt 5zum Thema OnBoard LEDs und RGB Ring ) vorspringen und einfach bei Bedarf hierher zurück kommen.

Einige der Ein- und Ausgänge sind direkt mit Komponenten auf dem Auriga-Board verbunden. Andere sind mit externen Ports und Anschlüssen verbunden. Die Details dazu findet man auf dem Auriga Schaltplan. Der ist allerdings nicht leicht zulesen und enthält auch viele Informationen, welche man bei Verwendung der MakeBlock-Programmierbibliothek gar nicht benötigt.

Daher ist es sinnvoller, sich das sogenannte Pinout-Diagramm anzuschauen.

auriga pinout
Abbildung 8. Auriga Board PinOut Diagramm

Das Pinout-Diagramm gibt es auch als Auriga Pinout PDF.

4.1. Ports und zugeordnete Arduino-Pins

Innerhalb der Makeblock-Bibliothek werden Sensoren und Aktoren über Ports angesprochen, statt direkt Pins zu bezeichnen. Dies liegt daran, dass die Makeblock-Bibliothek auch für andere mBot Modelle ähnlich verwendet wird. Die Zuordnung von Ports zu Pins ist in Quelltext-Header-Dateien hinterlegt, welche für die unterschiedlichen mBot-Bausätze anders heißen. Die für Auriga-Board verwendete Diese sind in der Makeblock-Bibliothek in der Datei MeAuriga.h definiert:

Auszug aus der Header-Datei MeAuriga.h
MePort_Sig mePort[17] =
{
	{ NC, NC }, {   5,   4 }, {   3,   2 }, {   7,   6 }, {   9,   8 },
	{ 16, 17 }, { A10, A15 }, {  A9, A14 }, {  A8, A13 }, {  A7, A12 },
	//             LIGHT2        LIGHT1        TEMP          SOUND
	{ A6,A11 }, {  NC,  A2 }, {  NC,  A3 }, {  NC,  A0 }, {  NC,  A1 },
	{ NC, NC }, { NC, NC },
};

// etwas umformatiert und kommentiert
MePort_Sig mePort[17] = {
	Port 0  {  NC,  NC }   Not connected
	Port 1  {   5,   4 }   red
	Port 2  {   3,   2 }   red
	Port 3  {   7,   6 }   red
	Port 4  {   9,   8 }   red
	Port 5  {  16,  17 }   grey
	Port 6  { A10, A15 }   universal
	Port 7  {  A9, A14 }   universal
	Port 8  {  A8, A13 }   universal
	Port 9  {  A7, A12 }   universal
	Port 10 {  A6, A11 }   universal
	Port 11 {  NC,  A2 }   light sensor 1
	Port 12 {  NC,  A3 }   light sensor 2
	Port 13 {  NC,  A0 }   temperature sensor
	Port 14 {  NC,  A1 }   sound sensor
	Port 15 {  NC,  NC }
	Port 16 {  NC,  NC }
}

Jeder Makeblock-Port ist an 2 Pins angeschlossen. Diese Pins werden als Slot1 und Slot2 bezeichnet. NC steht für Not Connected. Ports 1 bis 10 sind RJ25 Ports (dazu mehr im Kapitel zu den RJ25 Anschlüssen [chap:rj25]).

Als Beispiel: der Port 6 ist an den analogen Pin 10 und analogen Pin 15 des Mikrocontrollers angeschlossen.

4.2. Weitere verwendete Pins des Mega 2560 Prozessors

Einige Komponenten sind direkt über IO Pins anzusteuern:

Pin 44 = 12 RGB LED Ring
Pin 45 = Buzzer
Pin 13 = Blaue LED (built-in LED)

Die Motoren können zwar recht einfach durch die Bibliothek angesteuert werden, hier sind aber nochmal die Pins (falls man die Motoren klassisch über Arduino Pin PWM-write-Befehle ansteuern möchte, siehe Kapitel über die Motorensteuerung Abschnitt 8):

// Motor 1 (links)

ENA A  = pin 19 // Interrupt-Pin 1 für Encoder
ENA B  = pin 42 // Pin 2 für Encoder

PWMA   = pin 11 // Geschwindigkeit/PWM
DIR A2 = pin 49 // Richtung
DIR A1 = pin 48 // Richtung

// Motor 2 (rechts)

ENB A  = pin 18 // Interrupt-Pin 1 für Encoder
ENB B  = pin 43 // Pin 2 für Encoder

PWMB   = pin 10 // Geschwindigkeit/PWM
DIR B1 = pin 47 // Richtung
DIR B2 = pin 46 // Richtung

5. OnBoard LEDs und RGB Ring

Nun beginnen wir mit der Programmierung. Auf dem Auriga-Board sind zahlreiche LEDs verbaut. In diesem Kapitel geht es darum, diese LEDs zum Leuchte zu bringen.

5.1. Allgemeines

Auf dem Board gibt es eine ganze Reihe von LEDs, die man programmieren kann. Da ist zunächst eine blaue Standard Arduino LED, die wie bei anderen Arduino Boards auf dem Pin 13 anzusprechen ist. Dann sind da noch 2 LEDs beim Kommunikationsmodul vorhanden, die primär Kommunikation über die serielle Schnittstelle (Bluetooth/USB) anzeigen. Dazu gibt es noch den 12er RGB LED Ring, bei dem man alle 12 LED unterschiedlich bunt einfärben kann und damit ein vielseitiges Anzeigegerät für Roboterzustände hat.

Dann gibt es noch eine grüne "On"-Status-LED (nicht programmierbar, hart verdrahtet), 2 rote LEDs direkt unter dem RGB-Ring (auch nicht programmierbar) und die blaue, ryhtmisch blinkende LED oberhalb des Reset-Tasters (auch nicht programmierbar).

5.2. Standard built-in LED

Die eingebaute blaue LED auf dem Board ist eher schlecht zu sehen (im Vergleich zu der regelmäßig blinkenden blauen "an"-Status LED):

auriga Builtin LED
Abbildung 9. Eingebaute Standard-LED auf dem Board

Diese LED wird wie bei allen Arduino-Boards programmiert - man kann das Standard-Blink-Beispielprogramm nehmen:

5.2.1. Beispielprogramm

// Eingebaute LED auf dem Arduino-Board blinken lassen
// Dies ist quasi das Standard-Test-Programm für die meisten Arduino-Boards

int BlueLed = LED_BUILTIN; // Pin 13

void setup() {
  pinMode( BlueLed, OUTPUT);
}

void loop() {
  // lang an
  digitalWrite( BlueLed, HIGH);
  delay (1000);
  // kurz aus
  digitalWrite( BlueLed, LOW);
  delay (250);
}

Die LED 13 ist an einen PWM-fähigen Pin angeschlossen, daher kann man die LED auch via PWM langsam ein- und ausblenden:

// Eingebaute LED auf dem Arduino-Board ein- und ausblenden

int BlueLed = LED_BUILTIN; // Pin 13

void setup() {
  pinMode( BlueLed, OUTPUT);
}

void loop() {
  for (int i=0; i<25; ++i) {
    analogWrite(BlueLed, i*10);
    delay (40);
  }
  for (int i=0; i<25; ++i) {
    analogWrite(BlueLed, (25-i)*10);
    delay (40);
  }
}

5.3. OnBoard LEDs (Kommunikationsmodul)

comm red blue LEDs
Abbildung 10. Rote und blaue Kommunikations-Modul-LEDs

Es gibt zwei weitere LEDs auf dem Auriga Board und zwar die zwei kleinen roten und blauen LEDs in der Nähe des USB Anschlusses. Diese werden in der Makeblock Bibliothek nicht verwendet, auch nicht in der Firmware. Man kann diese aber mit den Arduino-Standardpins ansprechen, wenn man denn erstmal weiß, an welchen Pins diese LEDs angeklemmt sind.

Daher schaut man zuerst mal in den Schaltplan MeAuriga_Schaltplan.pdf. Die zwei LEDs sind im Abschnitt 程序更新&无线遥控 (dt. Programmaktualisierung und drahtlose Fernbedienung) aufgeführt:

Schaltplanauszug OnBoard LEDs
Abbildung 11. Auszug Schaltplan OnBoard LEDs

Diese LEDs sind mit den Pins D0/RX0 und D1/TX0 des MEGA2560 Mikrocontrollers verbunden. Diese LEDs werden hauptsächlich dafür benutzt, die Kommunikation über diese Ports anzuzeigen. Die Anoden der LEDs sind mit +5 Volt verbunden. Also leuchten sie, wenn der jeweilige Pin (Kathodenseite) auf GND gezogen wird (LOW).

Die LEDs sind auch mit dem BLE (Bluetooth Low Energy) und UART Modulen (Universal Asynchronous Receiver/Transmitter) verbunden. Wenn man die LEDs direkt ansteuert, stört das diese Module. Wahrscheinlich ist das auch der Grund, warum die beiden LEDs in der Dokumentation und in der Bibliothek nicht aufgeführt sind.

5.3.1. Beispielprogramm

// Programm für wechselseitiges Ein- und Ausschalten der KommunikationsLEDs

// Auf dem Auriga Board sind die LEDs an Pin 0 und 1 geklemmt und mit +5V verbunden
int BlueLed = 0;
int RedLed  = 1;

void setup() {
  pinMode( BlueLed, OUTPUT);
  pinMode( RedLed, OUTPUT);
}

void loop() {
  digitalWrite( BlueLed, LOW);  // Blau anschalten
  digitalWrite( RedLed, HIGH);  // Rot ausschalten
  delay (400);
  digitalWrite( BlueLed, HIGH); // Blau ausschalten
  digitalWrite( RedLed, LOW);   // Rot anschalten
  delay (100);
}

5.4. 12er RGB LED Ring

Als Zusatzmodul für das Auriga-Board gibt es einen RGB Ring (Typ: ws12812).

RGBRing
Abbildung 12. Rings aus 12 RGBS

Der LED Ring wird über einen Controller angesteuert, der am PWM PIN 44 am ATmega 2560 angeschlossen ist. Die Programmierung des Controllers ist in der Klasse MeRGBLed implementiert, welche über die Include-Datei MeRGBLed.h eingebunden wird. Der RGB-Controller selbst wird über das WS2811/2812 Protokoll angesprochen, was aber die MeRGBLed-Klasse übernimmt.

Wer genauer wissen will, wie das Protokoll auf dem an PIN 44 angeschlossenen LED Controllerchip funktioniert, kann das hier nachlesen:

Wenn man dann mal in den Code der Klasse MeRGBLed innerhalb der MakeBlock Bibliothek schaut, dann findet man die im Text erwähnten Timings und den Assembler code zum Übertragen der Daten.

#define w_zeropulse (350)  // +- 150 ns
#define w_onepulse  (900)  // +- 150 ns
#define w_totalperiod (1250)

Grundsätzlich hält die Klasse eine Datenstruktur für die RGB-Informationen jeder einzelnen RGB. Die Konfiguration der RGB kann nun durch Zugriffsfunktionen wie setColorAt() geändert werden. Dabei wird zunächst nur der interne Zustand des Klassenobjekts geändert. Die Ansteuerung des Controllers selbst und damit das Umschalten der LEDs erfolgt erst beim Aufruf von show().

Die LED 0 (bzw. 1. LED) ist übrigends die LED auf "1 Uhr", wenn man sich das Bild oben anschaut. Die oberste LED ("12 Uhr") ist die LED 11 und LED 2 (bzw. 3. LED) zeigt in Richtung "Vorwärts" des Land Raider Modells.

5.4.1. Beispielprogramm

// Testprogramm für den LED Ring auf dem Auriga Board.

// Zuerst den Header für das Auriga-Board einbinden
#include <MeAuriga.h>

// Der Auriga on-board LED Ring hat 12 LEDs. Zur Vereinfachung der Lesbarkeit
// legen wir hier ein Define fest.
#define LEDNUM  12

// Beim Auriga-Board steuern wird den on-board LED Ring an.
// Die Klasse MeRGBLed bietet die Schnittstellenfunktionen dafür.
// Im Constructor übergeben wir den Port 0
MeRGBLed led( PORT0, LEDNUM );

void setup() {
  // LED Ring Controller ist am PWM PIN D44 angeschlossen
  led.setpin( 44 );
  // Nach dem Setzen des Pin muss minimal kurz gewartet werden.
  // Wenn man den delay()-Aufruf vergisst, dann wird nach dem
  // led.show() Befehl die erste LED in grün angezeigt.
  delay(1);
  // nun können wir die initalen LED-Werte (alle AUS/SCHWARZ) setzen
  // (Die Klasse MeRGBLed setzt anfänglich alle LEDs auf schwarz/aus, man kann
  //  aber auch led.setColor(0,0,0) vor dem led.show() nochmal aufrufen)
  led.show();
}

void loop() {
  // wir setzen nun unterschiedliche Farben in den LEDs und schalten diese dann jeweils an
  for (uint8_t i = 0; i < LEDNUM; ++i ) {
    // alle ausschalten
    led.setColor(0,0,0);
    // die LED mit Index i anschalten
    led.setColorAt( i, i*20, 0, (LEDNUM-i-1)*20 ); // i = 0...11
    // LED Einstellungen an den LED controller übertragen
    // (erst mit diesem Befehl ändern sich tatsächlich die Farben)
    led.show();
    delay(100);
  }
}

Grundlegende Herangehensweise ist immer:

  • Farbe ändern einzelner LEDs mit setColorAt() oder aller zusammen mit setColor()

  • dann die Farben an den Controller und damit an den LED-Ring übertragen mit show()

5.4.2. Die wichtigsten Funktionen der MeRGBLed Klasse

// Alle RGB mit der gleichen Farbe setzen
bool MeRGBLed::setColor(uint8_t red, uint8_t green, uint8_t blue);
// Alle RGB (index=0) setzen, oder einzelne (1-basierte Indizierung; index = 1...LEDNUM)
bool MeRGBLed::setColor(uint8_t index, uint8_t red, uint8_t green, uint8_t blue);
// Einzelne LED setzen (index = 0...LEDNUM-1); 0-basierte Indizierung der LED
bool MeRGBLed::setColorAt(uint8_t index, uint8_t red, uint8_t green, uint8_t blue);
// Gesetzte Farben an den Controller und damit an die LED übertragen (500 µs Wartezeit bei jedem Aufruf)
bool MeRGBLed::show();

5.4.3. Programmierideen

Den RGB-Ring kann man prima für verschiedene Sachen nutzen, bspw.:

  • zur Anzeige von Sensordaten, bspw. den Abstand beim Entfernungssensor

  • Kompassrichtung anzeigen oder Fahrrichtung

  • die verstrichenen Sekunden oder den Zeitverlauf anzeigen

  • oder einfach nur eine coole Knight-Rider Animation bauen

6. OnBoard Sensoren (Licht, Schall, Temperature, Gyroskop)

Hier geht es um das Auslesen der verschiedenen OnBoard-Sensoren auf dem Auriga-Board. Auf dem Auriga Board sind 4 Sensortypen platziert:

  • Schall/Lautstärke

  • Licht/Helligkeit (2 Mal, links und rechts)

  • Temperatur

  • Gyroskop/Neigungssensor

Nachfolgend wird gezeigt, wie diese Sensoren einzeln auszulesen sind, und welche Genauigkeiten/Wertebereiche zu erwarten sind.

6.1. Lautstärke/Schall

Der Sound-Sensor auf dem Auriga-Board wird über die Klasse MeSoundSensor (Include-Datei nur MeAuriga.h) ausgelesen.

Im Gegensatz zu anderen MakeBlock Bausätzen (mBot etc.) ist der Sound-Sensor auf dem Auriga-Board an Port 14 angeschlossen (siehe Variable mePort in der Datei MeAuriga.h und Erklärung dazu in Abschnitt 4.

Die Klasse hat nur eine sinnvolle Memberfunction: strength(), was die Lautstärke im Bereich 140 bis ~600 ausgibt.

6.1.1. Beispielprogramm

Liest kontinuierlich die Lautstärke aus und übergibt diese via serieller Verbindung an den PC und kann dort bspw. mit dem Serial Plotter der Arduino-IDE angezeigt werden.

// Testprogramm für den Sound-Sensor am Auriga-Board.
//
// ACHTUNG: beim Auriga ist der Sound-Sensor am Port 14 angeschlossen.
#include <MeAuriga.h>

MeSoundSensor soundSensor(PORT_14);

void setup() {
  Serial.begin(115200);
}

void loop() {
  Serial.print("value:");
  Serial.println(soundSensor.strength() );
  delay(50);
}
auriga soundsensor
Abbildung 13. Im SerialPlotter sieht man die erfassten Werte, als ich mehrfach laut direkt über dem Auriga-Board geklatscht habe. In sehr leiser Umgebung rauscht das Signal bei ca. 130…​140.

6.2. Licht/Helligkeit

Es gibt zwei Helligkeitssensoren auf dem Auriga Board:

  • neben Port 2, wird über PORT_11 angesteuert

  • neben Port 9, wird über PORT_12 angesteuert

Im Gegensatz zu anderen MakeBlock Bausätzen (mBot etc.) sind die Lichtsensoren auf dem Auriga-Board an den Ports 11 und 12 angeschlossen (siehe Variable mePort in der Datei MeAuriga.h und Erklärung dazu in Abschnitt 4.

Die Klasse MeLightSensor liest die Helligkeitswerte aus (im Bereich 0..1000) (Memberfunktion read()).

6.2.1. Beispielprogramm

// Test für die Lichtsensoren
#include <MeAuriga.h>

MeLightSensor lightSensorRight(PORT_11); // Der Sensor neben Port 2
MeLightSensor lightSensorLeft(PORT_12);  // Der Sensor neben Port 9

void setup() {
  Serial.begin(115200);
}


void loop() {
  // Lichtsensoren auslesen
  int right = lightSensorRight.read();
  int left = lightSensorLeft.read();

  // Werte via serieller Verbindung an PC senden
  Serial.print("min:0,max:1000,");
  Serial.print("left:");
  Serial.print(left);
  Serial.print(",right:");
  Serial.println(right);
  // alle 50 ms
  delay(100);
}
auriga lightsensors
Abbildung 14. Bei direkten Anleuchten mit einer Fahrradlampe wurde der Wert 1000 ausgegeben. In sehr dunklen Räumen (nur der Monitor in 30 cm Entfernung ist an), zeigt der Sensor Werte zwischen 1-3. Im Beispiel oben habe ich wechselseitig den einen und dann den anderen Sensor mit der Hand abgedeckt.

Interessant: bei moderatem Licht von Energiesparlampen zeigt der Sensor (wellenförmige schwankende) Werte zwischen 55 und 140 an.

Auch interessant: Wenn man den Ranger seitlich ans Fenster stellt, so werden leicht unterschiedliche Helligkeitswerte angezeigt. Eine Drehung um 180° führt jedoch wieder Erwarten nicht zum Vertauschen der Helligkeitswerte beider Sensoren, wie man das vielleicht erwarten würde. Ein Regeln der Ausrichtung des Ranges basierend auf seitlich einfallendem Licht scheint eher schwierig zu sein (selber ausprobieren!).

6.3. Temperatur

Auf dem Board ist ein DS18B20 Temperatursensor verbunden. Dieser wird über das Wire-Protokoll am Port 13 abgefragt. Die entsprechende Implementierung steckt in der Klasse MeOnBoardTemp mit der Member-Funktion readValue() (bzw. readAnalog() für den Rohwert).

6.3.1. Beispielprogramm

// Test für den Temperatursensor
#include <MeAuriga.h>

// Der OnBoard-Temperatursensor wird über Port 13 angesprochen
MeOnBoardTemp tempSensor(PORT_13);

void setup() {
  Serial.begin(115200);
}

void loop() {
  Serial.print("Analogwert:");
  Serial.print(tempSensor.readAnalog());
  Serial.print(",Temperaturwert:");
  Serial.println(tempSensor.readValue());
  delay(1000);
}
auriga temperatursensor
Abbildung 15. Vom Sensor gelieferter Temperaturverlauf, wenn man den Arduino nach längerer Zeit (6h) erstmalig anschaltet. Ausgehend von der Raumtemperatur (ca. 22°) erwärmt sich das Board und der Sensor in wenigen Minuten auf über 25°C, wenn man noch ein paar LEDs anmacht, oder dem Mikroprozessor ordentlich was zu tun gibt, geht die Temperatur rauf auf knapp 30°C.

Der Temperatursensor wird maßgeblich durch die Energieabgabe von LEDs und des Prozessors allgemein beeinflusst. Die Umgebungstemperatur lässt sich damit nur sehr ungenau messen, da die Wärmezirkulation zum Sensor durch das Plastikgehäuse behindert ist.

6.4. Gyroskop

Das Auriga-Board hat einen Neigungssensor verbaut. Dieser liefert für die 3 Achsen x,y,z jeweils Neigungswerte/Ausrichtungswerte und dazu die Beschleunigungen auf den 3 Achsen.

Die Achsenzuordnung ist dabei wie folgt:

  • X-Achse : Kippen um die Querachse (der Anstieg beim Fahren auf einen Hügel): -90° (nach unten)…​90° (nach oben)

  • Y-Achse : Kippen um die Längsachse; -90° (nach rechts geneigt) …​90° (nach links geneigt)

  • Z-Achse : N, O, S, W Ausrichtung; 0° = der USB-Port am Auriga zeigt dann nach Norden; -180°/180° = der USB-Port zeigt nach Süden; -90° = der USB-Port zeigt nach Westen

Entsprechend ist die X-Beschleunigung die Beschleunigung vorwärts und Y-Beschleunigung die Drehbeschleunigung. Interessant ist die Z-Beschleunigung (Querbeschleunigung) beim schnellen Kurvenfahren.

Zum Auslesen des Neigungssensors/Gyroskops verwendet man die Klasse MeGyro wie im nachfolgendem Beispiel gezeigt.

6.4.1. Beispielprogramm

// Testprogramm für den Neigungssensor
#include <MeAuriga.h>

MeGyro gyro(0, GYRO_DEFAULT_ADDRESS);

void setup() {
  Serial.begin(115200);

  // Klasse initialisieren
  gyro.begin();
}

void loop() {
  // Aktualisiere Zustand des gyro-Objects (liest Sensoren aus und berechnet Winkel/Beschleunigungen)
  // Alternativ kann man auch fast_update() verwenden
  gyro.update();

  // greife auf die Sensordaten zu
  Serial.print("Angle-X:");
  Serial.print(gyro.getAngleX());
  Serial.print(",Angle-Y:");
  Serial.print(gyro.getAngleY());
  Serial.print(",Angle-Z:");
  Serial.print(gyro.getAngleZ());

  Serial.print(",Gyro-X:");
  Serial.print(gyro.getGyroX());
  Serial.print(",Gyro-Y:");
  Serial.print(gyro.getGyroY());
  Serial.print(",Gyro-Z:");
  Serial.println(gyro.getGyroZ());

  delay(100);
}

6.5. Programmierideen

  • Der Roboter soll im Dunkeln das LED-Licht anschalten (aber beeinflusst das nicht die Helligkeitsmessung?)

  • Der Roboter soll sich zur Lärmquelle hinbewegen (dazu braucht man noch den Antrieb aus Abschnitt 8)

  • Der Roboter fährt ein Rampe hoch und hält dann auf der waagerechten Fläche wieder an

Für den Nervous Bird (das umgedrehte Pendel) ist der Neigungssensor essentiell, damit man hier das Gleichgewicht hält. Die Programmierung eines solchen Robotermodells, der beim anschubsen selbständig vor-/zurück fährt und das Gleichgewicht behält, ist aber ein anspruchsvolleres Projekt.

7. Töne mit dem passiven Buzzer auf dem Board

Hier steuern wir den passiven Buzzer auf dem Board an.

7.1. Allgemeines

Auf dem Auriga-Board ist ein passiver Buzzer verbaut, welcher an einen PWM-Pin angeschlossen ist. Der Buzzer ist an Pin 45 angeschlossen.

auriga buzzer

Beim Blick in die Include-Datei MeAuriga.h fällt einem am Schluss der Datei folgende Quelltext auf:

#define   pinMode(45,OUTPUT),digitalWrite(45, HIGH)
#define buzzerOff() pinMode(45,OUTPUT),digitalWrite(45, LOW)

Hier wird also beim Einschalten der Pegel auf HIGH gezogen und beim Ausschalten der Pegel wieder auf LOW. Das ist allerdings Code, der für einen aktiven Buzzer gedacht ist, und wahrscheinlich vergessen wurde, zu entfernen.

Für den MakeBlock ranger sind die Funktionen buzzerOn() und buzzerOff() nicht zu verwenden.

Um den passiven Buzzer anzusteuern, verwendet man tone() und zum Ausschalten noTone(). Hier ist ein Beispiel für die direkte Ansteuerung des Pins.

7.1.1. Beispielprogramm

#define BUZZER_PIN 45

void setup()  {
  pinMode(BUZZER_PIN, OUTPUT);
}

void loop()  {
  tone(BUZZER_PIN, 131);   // c
  delay(1200);

  tone(BUZZER_PIN, 165);   // e
  delay(400);

  tone(BUZZER_PIN, 196);   // g
  delay(1800);

  noTone(BUZZER_PIN);     // aus
  delay(4000);
}

Hier ist noch ein Programm, bei dem aus dem einfachen Buzzer etwas interessantere Geräusche raus kommen.

#define BUZZER_PIN 45

void setup()  {
  pinMode(BUZZER_PIN, OUTPUT);
}

void loop()  {
  for (int i=0; i<35; ++i) {
    int freq = 80 + i*10;
    int terz = freq*6.0/5;
    for (int j=0; j<10; ++j) {
      tone(BUZZER_PIN, freq);
      delay(30);
      tone(BUZZER_PIN, terz);
      delay(30);
    }
  }
  for (int i=35; i>1; --i) {
    int freq = 80 + i*10;
    int terz = freq*6.0/5;
    for (int j=0; j<10; ++j) {
      tone(BUZZER_PIN, freq);
      delay(30);
      tone(BUZZER_PIN, terz);
      delay(30);
    }
  }

}

Eine Liste von Frequenzen für die ersten 6 Oktaven findet man im Arduino-Beispiel: 02. Digital->toneMelody und der dort enthaltenen Datei pitches.h.

7.2. Verwendung der Makeblock Klasse MeBuzzer

Nur für den Anschluss externer Buzzer sinnvoll!

In der Makeblock-Bibliothek gibt es noch die Klasse MeBuzzer. Diese kapselt den Zugriff zwar etwas, macht die Ansteuerung des Buzzers aber nicht wirklich einfacher.

Man kann mittels der Member-Funktion MeBuzzer::tone(frequenz, dauer in ms) einen Ton ausgeben. Diese Funktion implementiert einen Software-PWM (d.h. in dieser Funktion wird der angegebene Buzzer-Pin sehr häufig an und aus geschaltet, wobei das Verhältnis der an/aus-Zeiten die Tonhöhe definiert).

Somit kann man auch externe Buzzer anschließen und dabei Ports mit digitalen Pins (keine analogen/PWM Pins) nutzen.

Für die Verwendung des OnBoard-Buzzers sollte man die MeBuzzer-Klasse nicht benutzen, sondern stattdessen wie im Beispiel oben via tone() die Frequenz einstellen. Das hat auch den Vorteil, dass man ohne Wartezeiten parallel zum Melodie abspielen noch Sensoren auslesen und andere Dinge steuern kann.

7.2.1. Beispielprogramm

// Beispielprogramm für die Verwendung der MeBuzzer-Klasse
// Diese Variante ist aber NICHT EMPFOHLEN (siehe Text)
#include <MeAuriga.h>

#define BUZZER_PIN 45

MeBuzzer buzzer;

void setup()  {
  buzzer.setpin(BUZZER_PIN);
  buzzer.noTone();
}

void loop()  {
  buzzer.tone(262, 250);   //NOTE_C4
  buzzer.tone(294, 250);   //NOTE_D4
  buzzer.tone(330, 250);   //NOTE_E4
  delay(2000);

  buzzer.tone(587, 250);   //NOTE_D5
  buzzer.tone(659, 250);   //NOTE_E5
  buzzer.tone(523, 250);   //NOTE_C5
  delay(2000);
}

8. Motorsteuerung

Jetzt wird endlich mal was bewegt. In diesem Teil geht es um die Programmierung der Motoren.

Zunächst aber mal ein konstruktiver Tipp:

Die Ketten sind am Anfang ewas steif und durch die Lagerung und Verpackung etwas oval verformt. Wenn man den Land Raider wie in der Konstruktionszeichnung zusammen baut, dann sitzen die Ketten sehr straff und der Motor braucht jedes Mal viel Kraft, um aus der gekrümmten Kettenform rauszudrehen (was er bei etwas entleerten Batterien häufig nicht schafft). Bei der vorgegebenen Firmware führt das dann beim Steuern des Land Raider häufig dazu, dass er mit einem Beepen stehen bleibt (warum die Firmware das macht und wie diese erkennt, dass der Land Raider stecken bleibt, erklär ich unten).

Es gibt zwei Dinge, die man tun kann, um dieses Problem mit dem Land Raider zu beheben:

  • die Ketten "rund" dehnen, z.B. auf eine ausreichend dicke Blumevase schieben, bis sie leicht gespannt sind, und dann eine Weile in die Sonne stellen und ggfs. gelegentlich nachspannen

  • die Motoren um eine Bohrung nach Innen befestigen, wie auf dem nachfolgenden Bild zu sehen ist

raider motor verschoben
Abbildung 16. Um ein Loch verschobene Motormontage zur Reduktion der Spannung in den Ketten

8.1. Allgemeines

Am Auriga-Board gibt es zwei Motorports. Jeder der DC-Motoren kann über einen PWM Pin (analoge Spannung für die Geschwindigkeit) und zwei digitalen Pins für die Drehichtung angesteuert werden. Die Ansteuerung kann einmal direkt über die Arduino-Pins erfolgen oder unter Verwendung der Makeblock Bibliothek (in der die Details gekapselt sind).

Grundsätzlich bewegen sich die Motoren nur, wenn die Spannungsversorgung über die Batterien erfolgt (die Motoren brauchen eine Spannung > 7V, was der USB-Port ja nicht liefern kann). Das ist auch ganz praktisch, da man so den Robotor angesteckt an den Computer programmieren kann, ohne Angst zu haben, dass er vom Tisch rollt.

Die Motoren werden an die beiden Motorports angesteckt:

auriga motorports
Abbildung 17. Motor-Ports an der Auriga-Platine

Die DC-Motoren des Ranger Baukastens sind intern mit einem Getriebe versehen. Die eigentlichen Elektromotoren drehen bei Maximalleistung (d.h. vollen Batterien und ohne Kette) mit ungefähr 14000 Umdrehungen pro Minute (oder engl. revolutions per minute - rpm). Durch das Getriebe mit der Übersetzung 39,6 laut Datenblatt drehen sich die angesteckten Räder eher so mit 350 rpm. Bei einem Radius von ca. 22 mm (einschließlich Kette) und damit einem Abrollumfang von Pi*2*22mm sind das dann ca. 138 mm pro Umdrehung und stolze 350*138 mm = 48 m pro Minute (oder 0,8 m/s oder ca. 2,9 km/h). Das wäre dann also die theoretische Maximalgeschwindigkeit.

Zunächst beschreibe ich mal die Programmierung der Motoren ohne die MakeBlock-Bibliotheksklassen. Dadurch versteht man besser, wie das alles zusammen funktioniert. Danach beschreibe ich in Abschnitt 8.7 die Funktionalität der MakeBlock-Bibliotheksklasse zur Encoder-Motor-Programmierung.

8.2. Direkte Ansteuerung mit Arduino-Hausmitteln

Aus dem Schaltplan kann man die Bezeichnung der digitalen Pins (D46…​D49) und die PWM Pins (D10, D11) entnehmen:

auriga schaltplanauszug motor
Abbildung 18. Schaltplanauszug für die Motoransteuerung

Die digitalen Pins werden nun wie folgt angesprochen:

  • PWMA und PWMB erhalten Drehgeschwindigkeiten (PWM, im Bereich 0..255)

  • DIRA1 und DIRA2 regeln die Richtung des Motors A (links) und müssen jeweils entgegengesetzt geschaltet sein

  • DIRB1 und DIRB2 regeln die Richtung des Motors B (rechts) und müssen jeweils entgegengesetzt geschaltet sein

DC-Motoren drehen sich in Abhängigkeit der anliegenden Gleichspannung schneller oder langsamer - je höher die Spannung, umso schneller. Der Arduino liefert die für die DC-Motoren benötigte Spannung aber nicht direkt, denn die Motoren brauchen eine Spannung zwischen 7..8.2 V. Die Motoren werden vom Batteriepack mit Spannung versorgt.

Der Arduino generiert aber eine quasi-Analoge Spannung durch Verwendung von PWMs. Hierbei wird in einem bestimmten Takt (der z.B. 1ms dauert) die Spannung kurz angeschaltet und danach wieder kurz ausgeschaltet. Je nachdem wie lange die Spannung im Verhältnis zur Gesamtzeit angeschaltet ist, umso höher ist die generierte Quasi-Gleichspannung. Das Verhältnis von "An-Zeit" zur gesamten Taktzeit nennt man Duty-Cycle. Bei 100% wird also die Nominalspannung des Arduino (5V) ausgegeben.

Diese am Pin anliegende Spannung wird im DC-Motor genutzt, um den Strom vom Batteriepack zum eigentlichen DC-Motor zu leiten (Internetsuche zum Thema "DC-Motoren und MOSFET"). Je höher die Taktfrequenz des PWM-Signals, umso gleichmäßiger baut sich das Magnetfeld auf/ab und der Motor läuft ruhiger. Dies ist insbesondere bei geringeren Duty-Cycles wichtig (siehe auch Abschnitt 8.6).

8.2.1. Beispielprogramm - Beschleunigen und Abbremsen

// Testprogramm für die Ansteuerung der Motoren via Arduino Pins

#define PWMA  11 // Motor A/Links
#define DIRA1 49
#define DIRA2 48
#define PWMB  10 // Motor B/Rights
#define DIRB1 47
#define DIRB2 46

void setup() {
  // PWM und Richtungspins setzen
  pinMode(PWMA,  OUTPUT);
  pinMode(DIRA1, OUTPUT);
  pinMode(DIRA2, OUTPUT);
  pinMode(PWMB,  OUTPUT);
  pinMode(DIRB1, OUTPUT);
  pinMode(DIRB1, OUTPUT);

  // kurze Wartephase zur Initialisierung
  delay(20);
}

void setLeftMotorSpeed(int speed) {
  if (speed >= 0) {
    analogWrite (PWMA,  speed);
    digitalWrite(DIRA1, LOW);
    digitalWrite(DIRA2, HIGH);
  }
  else {
    analogWrite (PWMA,  -speed);
    digitalWrite(DIRA1, HIGH);
    digitalWrite(DIRA2, LOW);
  }
}

void setRightMotorSpeed(int speed) {
  if (speed >= 0) {
      analogWrite (PWMB,  speed);
      digitalWrite(DIRB1, HIGH);
      digitalWrite(DIRB2, LOW);
  }
  else {
    analogWrite (PWMB,  -speed);
    digitalWrite(DIRB1, LOW);
    digitalWrite(DIRB2, HIGH);
  }
}


// Maximalgeschwindigkeit
int maxSpeed = 255;
int speed = 0;
bool upward = true;

void loop() {

  // Steuerungsprogramm:
  // - Vorwärtsfahren und Geschwindigkeit in jeder Schleife
  //   erhöhen bis Maximalgeschwindikeit erreicht ist
  // - dann langsamer werden und schließlich Rückwärtsfahren
  //   bis maximale Rückwärtsgeschwindigkeit erreicht ist
  // - dann wieder umschalten auf vorwärts fahren
  if (upward)
    speed += 5;
  else
    speed -= 5;
  if (speed > maxSpeed) {
    upward = false;
    speed = maxSpeed;
  }
  if (speed < -maxSpeed) {
    upward = true;
    speed = -maxSpeed;
  }

  // Motorgeschwindigkeiten anpassen
  setLeftMotorSpeed(speed);
  setRightMotorSpeed(speed);

  delay(50);
}

Hier fährt der Roboter einfach nur vor und zurück und beschleunigt/bremst dabei.

8.2.2. Beispielprogramm - Konstante Fahrt vorwärts

Man kann das Programm auch vereinfachen und den Roboter einfach mit konstanter Geschwindigkeit geradeaus fahren lassen. Dabei werden beide Motoren mit dem gleichen PWM-Signal (gleicher Leistung) angesteuert.

// Testprogramm für die Ansteuerung der Motoren via Arduino Pins

#define PWMA  11 // Motor A/Links
#define DIRA1 49
#define DIRA2 48
#define PWMB  10 // Motor B/Rights
#define DIRB1 47
#define DIRB2 46

void setup() {
  // PWM und Richtungspins setzen
  pinMode(PWMA,  OUTPUT);
  pinMode(DIRA1, OUTPUT);
  pinMode(DIRA2, OUTPUT);
  pinMode(PWMB,  OUTPUT);
  pinMode(DIRB1, OUTPUT);
  pinMode(DIRB1, OUTPUT);

  // kurze Wartephase zur Initialisierung
  delay (20);

  // links vorwärts, 100 PWM
  analogWrite (PWMA,  100);
  digitalWrite(DIRA1, LOW);
  digitalWrite(DIRA2, HIGH);

  // rechts rückwärts, 100 PWM
  analogWrite (PWMB,  100);
  digitalWrite(DIRB1, HIGH);
  digitalWrite(DIRB2, LOW);
}

// in der Hauptschleife machen wir nix
void loop() {
}

Nun sollte der Raider schön geradeaus fahren…​ macht er aber gelegentlich nicht. Warum? Weil je nach Steifigkeit der Kette oder Untergrund oder anderen Reibungsfaktoren sich die Motoren trotz gleichem PWM-Signal nicht gleich schnell drehen. Um das zu beheben und wirklich präzise zu navigieren, müsste man die Motorleistung so anpassen, dass die geforderte Drehzahl erreicht wird. Dafür müsste man aber herausfinden, wie schnell sich die Motoren tatsächlich drehen. Und genau das kann man bei den Encoder-Motoren machen.

8.3. Motordrehgeschwindigkeit mittels Encoder ermitteln

Der Encoder im Motor ist ein Drehimpulsgeber/Tacho und liefert elektrische Impulse, die man zählen kann. Damit kann man die Geschwindigkeit und zurückgelegte Entfernung bestimmen. Zum Einstieg in das Thema Encoder kann ich das Encoder Tutorial Arduino (deutsch, für Anfänger) empfehlen.

Der Encoder eines Motors ist am Arduino an jeweils zwei digitalen Pins angeklemmt. Um einen Drehimpuls zu erfassen, muss man den einen Pin überwachen und feststellen, wann dieser von 0 auf 1 wechselt. Damit man das präzise machen kann, ohne dass anderen Aufgaben im Mikroprozessor die Messung beeinträchtigen, verwendet man Interruptfunktionen. Dazu registriert man für jeden Motor eine Interruptfunktion, die immer dann aufgerufen wird, wenn am entsprechenden Pin ein RISING Signal anliegt (also der Eingangspin von LOW auf HIGH wechselt). In der Interruptfuktion wird dann ein Zähler hochgezählt, der dann für die Berechnung der Momentangeschwindigkeit und Bewegung verwendet wird.

8.3.1. Beispielprogramm - Variable Motordrehzahl und Geschwindigkeit via Encoder auslesen

Nun folgt ein etwas längeres Beispielprogramm, welches aber unten detailliert erklärt wird.

// Testprogramm für die Ansteuerung der Encoder-Motoren via Arduino Pins

// Motor A/Links
#define PWMA  11
#define DIRA1 49
#define DIRA2 48

#define ENCODER1_PIN1 19  // Interrupt-Pin für Encoder 1
#define ENCODER1_PIN2 42

// Motor B/Rechts

#define PWMB  10
#define DIRB1 47
#define DIRB2 46

#define ENCODER2_PIN1 18  // Interrupt-Pin für Encoder 2
#define ENCODER2_PIN2 43

#define PULSESPERREVOLUTION 353.403   // Anzahl der Pulse pro Umdrehung

int targetSpeedPWM;                   // Ziel-PWM für beide Motoren
unsigned long startMillis;            // Millis am Programmstart
unsigned long pulseCountStartMillis;  // Millis beim Start der Pulszählung
unsigned long lastOutputMillis;       // Millis bei der letzten Ausgabe

long encoder1Pulses;                  // gezählte Pulse des Encoders 1 (können negativ werden)
long encoder2Pulses;                  // gezählte Pulse des Encoders 2 (können negativ werden)

// Für präzise Messung der Geschwindigkeit (und damit Position) der Motoren
// werden die Pulse via Interruptfunktionen hoch/runtergezählt.
// Jedes Mal, wenn der Interrupt-Pin eines Encoders von LOW auf HIGH wechselt (RISING),
// wird die jeweilige isr_encoderX() Funktion aufgerufen und zählt einen Puls hoch.

// Interruptfunktion für Encoder 1
void isr_encoder1(void) {
  if (digitalRead(ENCODER1_PIN2) == 0)
    ++encoder1Pulses;
  else
    --encoder1Pulses;
}

// Interruptfunktion für Encoder 2
void isr_encoder2(void) {
  if (digitalRead(ENCODER2_PIN2) == 0)
    --encoder2Pulses;   // ACHTUNG: Drehrichtung des 2. Motors ist andersherum
  else
    ++encoder2Pulses;
}

// Umrechung von Pulsen zu Umdrehungen pro Minute (RPM)
float rpmFromPulses(long pulses) {
  unsigned long deltaT = millis() - pulseCountStartMillis; // Zeit seit Beginn der Zählung
  float pulsePerSecond = pulses*1000.0/deltaT;
  float rpm = pulsePerSecond*60/PULSESPERREVOLUTION; // 353.403 Pulse pro Umdrehung
  return rpm;
}

// setzt Geschwindigkeit für linken Motor (-255...255)
void setLeftMotorSpeed(int targetPWM) {
  if (targetPWM >= 0) {
    analogWrite (PWMA,  targetPWM);
    digitalWrite(DIRA1, LOW);
    digitalWrite(DIRA2, HIGH);
  }
  else {
    analogWrite (PWMA,  -targetPWM);
    digitalWrite(DIRA1, HIGH);
    digitalWrite(DIRA2, LOW);
  }
}

// setzt Geschwindigkeit für rechten Motor (-255...255)
void setRightMotorSpeed(int targetPWM) {
  if (targetPWM >= 0) {
      analogWrite (PWMB,  targetPWM);
      digitalWrite(DIRB1, HIGH);
      digitalWrite(DIRB2, LOW);
  }
  else {
    analogWrite (PWMB,  -targetPWM);
    digitalWrite(DIRB1, LOW);
    digitalWrite(DIRB2, HIGH);
  }
}


void setup() {
  // PWM und Richtungspins setzen
  pinMode(PWMA,  OUTPUT);
  pinMode(DIRA1, OUTPUT);
  pinMode(DIRA2, OUTPUT);
  pinMode(PWMB,  OUTPUT);
  pinMode(DIRB1, OUTPUT);
  pinMode(DIRB1, OUTPUT);

  // WICHTIG: INPUTs mit PullUp Widerständen!
  pinMode(ENCODER1_PIN1, INPUT_PULLUP);
  pinMode(ENCODER1_PIN2, INPUT_PULLUP);
  pinMode(ENCODER2_PIN1, INPUT_PULLUP);
  pinMode(ENCODER2_PIN2, INPUT_PULLUP);

  // kurze Wartephase zur Initialisierung
  delay (20);

  // Festlegen der Interruptfunktionen für das Messen/Zählen der Bewegung
  attachInterrupt(digitalPinToInterrupt(ENCODER1_PIN1), isr_encoder1, RISING);
  attachInterrupt(digitalPinToInterrupt(ENCODER2_PIN1), isr_encoder2, RISING);

  // Variable für gelegentliche Ausgaben auf die serielle Schnittstelle
  lastOutputMillis = startMillis = pulseCountStartMillis = millis();

  encoder1Pulses = 0;
  encoder2Pulses = 0;

  // Serielle Kommunikation konfigurieren
  Serial.begin(115200);
}


// in der Hauptschleife verändern wir je nach Eingabe der Geschwindigkeit
// das Tempo und geben regelmäßig Zielwert und tatsächliche Geschwindigkeit aus
void loop() {
  // von der seriellen Schnittstelle lesen
  if (Serial.available()) {
    // Zeichen 0...6 werden gelesen
    char a = Serial.read();
    switch(a) {
      case '0': targetSpeedPWM =    0; break;  // stop
      case '1': targetSpeedPWM =   20; break;  // slow forward
      case '2': targetSpeedPWM =  200; break;  // fast forward
      case '3': targetSpeedPWM =  255; break;  // fastest forward
      case '4': targetSpeedPWM = -100; break;  // slow backward
      case '5': targetSpeedPWM = -200; break;  // fast backward
      case '6': targetSpeedPWM = -255; break;  // fastest backward
    }
    setLeftMotorSpeed(targetSpeedPWM);
    setRightMotorSpeed(targetSpeedPWM);
  }

  // alle 100 Millisekunden die Geschwindigkeit ausgeben
  if (millis() > lastOutputMillis + 500) {
    lastOutputMillis = millis();
    // Ausgabe: Zeit [s]  \t Ziel-PWM \t Speed 1 [rpm] \t Speed 2 [rpm]
    Serial.print((millis() - startMillis)*0.001);
    Serial.print("\t");
    Serial.print(targetSpeedPWM);
    Serial.print("\t");
    Serial.print(rpmFromPulses(encoder1Pulses));
    Serial.print("\t");
    Serial.println(rpmFromPulses(encoder2Pulses));
    // die Counter zurücksetzen
    encoder1Pulses = 0;
    encoder2Pulses = 0;
    pulseCountStartMillis = millis();
  }
}

Dieses Programm hat viele Bestandeile, die man aber am Besten nach und nach erklärt.

8.3.2. Interruptfunktionen für Encoder-Pins und Geschwindigkeitsberechnung

Für die Erfassung der Geschwindigkeit müssen wir die Encoder-Pins (2 für jeden Motor) auslesen. Hierbei ist wichtig, diese als INPUT-Pins mit integriertem Pullup-Widerstand zu konfigurieren. Der entsprechende Block in der setup()-Funktion ist:

// WICHTIG: INPUTs mit PullUp Widerständen!
pinMode(ENCODER1_PIN1, INPUT_PULLUP);
pinMode(ENCODER1_PIN2, INPUT_PULLUP);
pinMode(ENCODER2_PIN1, INPUT_PULLUP);
pinMode(ENCODER2_PIN2, INPUT_PULLUP);

Wie schon oben erwähnt, werden Interruptfunktionen mit den Interrupt-Pins der Encoder verknüpft, wobei auf den Wechsel des Pegels von LOW auf HIGH reagiert wird (RISING). Das passiert in der setup() Funktion:

  // Festlegen der Interruptfunktionen für das Messen/Zählen der Bewegung
  attachInterrupt(digitalPinToInterrupt(ENCODER1_PIN1), isr_encoder1, RISING);
  attachInterrupt(digitalPinToInterrupt(ENCODER2_PIN1), isr_encoder2, RISING);

Der Funktionspräfix isr steht für Interrupt Service Routine.

Auf dem Mega 2560 gibt es mehrere Interrupt-fähige Pins, unter anderem Pin 18 und 19, welche mit dem Encoder verbunden sind (siehe auch Pinout-Diagramm, M1 und M2, wo D19/INT1 und D18/INT3 steht). Diesen Pins wird im Mega 2560 jeweils eine Interrupt-Nummer zugewiesen. Mit der Funktion digitalPinToInterrupt() erhält man die zu einem Interrupt-fähigen Pin zugehörige Interrupt-Nummer:

int interruptNr1 = digitalPinToInterrupt(19);  // -> interrupt 4
int interruptNr2 = digitalPinToInterrupt(18);  // -> interrupt 5

Wie bei Encodern üblich, wird die Flanke des einen Pins überwacht und dann durch den (etwas versetzten) Pegel des zweiten Pins die Drehrichtung bestimmt. Dies geschicht in der Interrupt-Funktion:

// Interruptfunktion für Encoder 1
void isr_encoder1(void) {
  if (digitalRead(ENCODER1_PIN2) == 0)
    ++encoder1Pulses;
  else
    --encoder1Pulses;
}

In den Interrupt-Funktionen wird jetzt bei jedem Aufruf ein Puls hoch oder runter gezählt. Da sich der Motor 2 anders herum dreht, wird entsprechend invertiert gezählt (sodass positive Pulszahlen einer Vorwärtsfahrt entsprechen).

Die Funktion rpmFromPulses() rechnet nun die bislang gezählten Pulse in eine Drehzahl um. Die seit Beginn der Zählung verstrichene Zeit wird berechnet und dann wird auf Pulse pro Minute hochgerechnet. Die Encoder geben bei einer Umdrehung 353.403 Pulse ab.

Die Encodermotoren drehen sich eigentlich bei Maximalgeschwindigkeit mit ca. 14000 Umdrehungen pro Minute (rpm). Das eingebaute Getriebe hat laut Spezifikation ein Verhältnis von 39.6, sodass sich das angesteckte Rad selbst eher mit 350 rpm dreht. In der Makeblock-Bibliothek ist jedoch ein Getriebeverhältnis von 39.267 angegeben, also hab ich diesen Wert verwendet.

Bei jeder Umdrehung des Motors werden 9 Pulse abgegeben. Damit ergeben sich bei einer Umdrehung des Rades die 9*39.267=353.403 Pulse.

Nach Berechnung der Geschwindigkeit wird ein neues Zählintervall gestartet, indem der Startzeitpunkt aktualisiert wird und die Pulszählvariablen auf 0 gesetzt werden:

// die Counter zurücksetzen
encoder1Pulses = 0;
encoder2Pulses = 0;
pulseCountStartMillis = millis();

8.4. Steuerung der Geschwindigkeit mittels Serial Plotter/Serial Monitor

Damit man die Rotationsgeschwindigkeit in Abhängigkeit des gesetzten PWM-Duty-Cycles testen kann, wird im Programm von der seriellen Schnittstelle gelesen. Diese serielle Schnittstelle dient eigentlich dazu, Daten vom Roboter an die Arduino-IDE zu geben, z.B. den SerialPlotter zur Anzeige (wie das schon in Abschnitt 6 mit den Sensoren gemacht wurde).

Mann kann aber genauso gut auch Text zurück an den Roboter senden. Dazu tippt man einach im SerialMonitor oder SerialPlotter den Text ein und bestätigt mit Enter. In diesem Programmbeispiel werden die Zeichen 0 bis 6 akzeptiert und je nach Zeichen wird eine andere PWM-Leistung eingestellt. In einem späteren Beispiel wird diese Kommunikation nochmal etwas erweitert.

In diesem Testbeispiel kann man den Robotor begrenzt steuern:

  • Nach Start des Programms den SerialMonitor der Arduino-IDE aufrufen

  • in die Zeile "Nachricht" des SerialMonitor eine Zahl 0…​6 eintippen und mit Enter abschicken

  • das Programm wertet diese Zahl aus und legt die Drehgeschwindigkeit der Motoren fest

Alternativ kann man das auch im SerialPlotter machen.

8.5. Testlauf und Geschwindigkeitsmessung mit und ohne Kette

Wenn man jetzt das Programm mal und die Geschwindigkeiten plottet erhält man ein interessantes Bild:

auriga encoder speed original PWM timer one belt
Abbildung 19. Ausgabe der Motorgeschwindigkeiten mit einem Motor mit Kette und dem anderen Motor freidrehend

Da die Kette schwingt und auch nicht gleichmäßig steif ist, führt dies zu ungleichmäßigen Drehbewegungen des Motors. Um diesen Einfluss zu sehen, habe ich an einen Motor die Kette angebaut und am anderen Motor nicht. Klar erkennbar im Diagramm ist auch die Bremswirkung der Kette insgesamt - der Motor mit Kette dreht langsamer.

Außerdem scheint die Drehzahl nicht proportional zum PWM-Duty-Cycle zu steigen (vor allem bei PWM 100). Dies liegt daran, dass der generierte PWM-Takt zu langsam ist. Um dies zu beheben, kann der PWM-Timer des Arduino umprogrammiert werden, sodass er mit 8kHz läuft.

8.6. Höhere PWM-Taktfrequenz für einen ruhigeren Motorlauf bei geringen Duty-Cycles

Der MEGA 2560 Prozessor hat intern Timer, die auch für die Generierung von PWM-Duty-Cycles verwendet werden. Für die Pins 11 und 12 ist der Timer 1 zuständig (16 bit). Und für Pins 9 und 10 der Timer 2. Für diese Pins ist die Standardfrequenz 490 Hz.

Diese Timer-Frequenzen kann man umprogrammieren (siehe auch Erklärung in Interrupts – Teil 3: Timer Interrupts und beispielsweise die konkret verwendete Bitmaske für Timer 1 auf Arduino Web Timers).

Der relevante Code-Block ist:

// Interne Timer für PWM auf 8KHz programmieren (Mode 5 - Fast PWM, 8-Bit, Prescaler 8)
// Timer 1
TCCR1A = _BV(WGM10);
TCCR1B = _BV(CS11) | _BV(WGM12);

// Timer 2
TCCR2A = _BV(WGM21) | _BV(WGM20);
TCCR2B = _BV(CS21);

_BV(X) steht für einen Bitshift 1 << X.

Erneut getestet sieht die Geschwindigkeitsausgabe deutlich besser aus, d.h. auch die durch die Encoder erfasste Drehzahl ist auch bei kleineren Drehzahlen hinreichend proportional zur Sollgeschwindigkeit (in PWM), was man gut am freilaufenden Motor sehen kann.

auriga encoder speed 8kHz PWM timer one belt
Abbildung 20. Ausgabe der Motorgeschwindigkeiten (in Umdrehungen pro Minute) mit umprogrammierten PWM-Timern und jeweils einen Motor mit Kette und den anderen Motor freidrehend

Beim freilaufenden Motor wird die festgelegte Soll-Geschwindigkeit offenbar gut erreicht. Beim Motor mit Kette bleibt die Sollgeschwindigkeit etwas hinter der festgelegten Geschwindigkeit, was ja an der Bremswirkung liegt.

Im Beispiel oben wurde die Geschwindigkeit in PWM angegeben und die Drehzahl vom Encoder in Umdrehungen pro Minute (RPM) abgelesen. Die Verhältnisse sind

132/100 = 1.32
266/200 = 1.33
339/255 = 1.33

Damit könnte man also die geforderte Drehzahl im Bereich -340…​340 mit der Formel einstellen:

pwm = rpm/1.33

und so hoffen, dass sich der Ranger genau mit der angegebenen Geschwindigkeit fortbewegt.

ABER: Die Drehzahl eines unbelasteten Rades alleine sagt ja noch nichts über die Fahrgeschwindigkeit des Roboters aus. Denn diese hängt natürlich auch noch vom Batterieladezustand ab und vom Anstieg und von der Reibung der Kette und und und…​ Deshalb ist es sinnvoller, die Leistung anhand der geforderten Geschwindigkeit einzuregeln. Doch dazu später mehr.

Wenn man den Land Raider mit aufgeladenen Batterien und Maximalgeschwindigkeit fahren lässt, so schafft er bei vollen Batterien auf gerader Fläche immerhin 0,56 m/s bzw. 2 km/h. Das ist zwar langsamer als die oben ausgerechnete Maximalgeschwindigkeit, reicht locker, um durch eine Legostadt zu düsen und spektakuläre Videos aus der Legomännelperspektive zu filmen.

Als ich das Testprogramm gerade nochmal mit frisch aufgeladenen Akkus getestet habe, sind bei PWM 255 durchaus Drehzahlen bis 388 angezeigt wurden. Die Akkuspannung hat also einen erheblichen Einfluss darauf, was an Drehzahlen und Geschwindigkeiten so möglich ist.

8.7. Ansteuerung über Encoder-Klasse der Bibliothek

Die MakeBlock-Bibliothek bietet zahlreiche Klassen für die Programmierung von Encoder-Motoren. Für die mitgelieferten DC-Motoren wird die Klasse MeEncoderOnBoard verwendet. Diese übernimmt, wie der Name schon sagt, die Programmierung der auf dem Board befindlichen Motorsteuerung. Diese Klasse erlaubt sowohl die direkte Ansteuerung der Motoren durch Setzen der Leistung via PWM, als auch die geregelte Steuerung.

8.7.1. Beispielprogramm - Ansteuerung mittels Bibliotheksfunktion

Zunächst soll das obige Testbeispiel hier nochmal unter Verwendung der Makeblock-Bibliothek umgesetzt werden.

Testprogramm für die Motorsteuerung und Messung der Geschwindigkeit mittels der Encoder-Klasse in der Makeblock-Bibliothek
// Testprogramm für die Ansteuerung der DC Motoren via Makeblock-Bibliothek
#include <MeAuriga.h>

MeEncoderOnBoard Encoder_1(SLOT1);
MeEncoderOnBoard Encoder_2(SLOT2);

// Für präzise Messung der Geschwindigkeit (und damit Position) der Motoren
// werden die Pulse via Interruptfunktionen hoch/runtergezählt.
// Jedes Mal, wenn der Interrupt-Pin eines Encoders von LOW auf HIGH wechselt (RISING),
// wird die jeweilige isr_process_encoderX() Funktion aufgerufen und zählt einen
// Pulse hoch.

// Interruptfunktion für Encoder 1
void isr_process_encoder1(void) {
  if (digitalRead(Encoder_1.getPortB()) == 0)     Encoder_1.pulsePosMinus();
  else                                            Encoder_1.pulsePosPlus();
}

// Interruptfunktion für Encoder 2
void isr_process_encoder2(void) {
  if (digitalRead(Encoder_2.getPortB()) == 0)     Encoder_2.pulsePosMinus();
  else                                            Encoder_2.pulsePosPlus();
}


int lastOutputMillis;
int targetSpeedPWM;

void setup() {
  // Festlegen der Interruptfunktionen für das Messen/Zählen der Bewegung
  attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
  attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
  Serial.begin(115200);

  // Interne Timer der PWM auf 8KHz programmieren
  TCCR1A = _BV(WGM10);
  TCCR1B = _BV(CS11) | _BV(WGM12);

  TCCR2A = _BV(WGM21) | _BV(WGM20);
  TCCR2B = _BV(CS21);

  // Variable für gelegentliche Ausgaben auf die serielle Schnittstelle
  lastOutputMillis = millis();
  targetSpeedPWM = 0;
}

void loop() {
  // von der seriellen Schnittstelle lesen
  if (Serial.available()) {
    // Zeichen 0...6 werden gelesen
    char a = Serial.read();
    switch(a) {
      case '0': targetSpeedPWM =    0; break;  // stop
      case '1': targetSpeedPWM =  100; break;  // slow forward
      case '2': targetSpeedPWM =  200; break;  // fast forward
      case '3': targetSpeedPWM =  255; break;  // fastest forward
      case '4': targetSpeedPWM = -100; break;  // slow backward
      case '5': targetSpeedPWM = -200; break;  // fast backward
      case '6': targetSpeedPWM = -255; break;  // fastest backward
    }
    Encoder_1.setTarPWM(-targetSpeedPWM);
    Encoder_2.setTarPWM(targetSpeedPWM);
  }

  // In der loop() Funktion wird die Geschwindigkeit im Motor berechnet
  Encoder_1.loop();
  Encoder_2.loop();

  // alle 100 Millisekunden die Geschwindigkeit ausgeben
  if (millis() > lastOutputMillis + 500) {
    lastOutputMillis = millis();
    Serial.print("Target speed [PWM]:");
    Serial.print(targetSpeedPWM);
    // Erreichte Geschwindigkeit
    Serial.print(",Speed 1:");
    Serial.print(-Encoder_1.getCurrentSpeed());
    Serial.print(",Speed 2:");
    Serial.println(Encoder_2.getCurrentSpeed());
  }
}

Dieser Code ist dem obigen sehr ähnlich, nur dass einige Dinge in der Bibliothek gemacht werden. Der eigentliche Steuerungscode wird in der Klasse MeEncoderOnBoard gekapselt, wobei für jeden Motor/Encoder ein Klassenobjekt erstellt wird.

Bei der Verknüpfung der Interrupt-Funktionen liefert die Funktion Encoder_1.getIntNum() die Interruptnummer für den interruptfähigen Pin:

// Verknüpfung einer Interrupt-Funktion
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);

Das Hoch-/Runterzählen der Pulse in den Interruptfunktionen ist wie beim bisherigen Beispiel. Die Encoder zählen jetzt also bei jedem Aufruf einen Puls höher oder runter. In der in jedem Durchlauf aufgerufenen Funktion MeEncoderOnBoard::loop() wird die Funktion MeEncoderOnBoard::updateSpeed() aufgerufen, welche letztlich die Anzahl der Pulse seit dem letzten Aufruf von updateSpeed() in die Drehgeschwindigkeit umrechnet.

Die originale Firmware für den Makeblock Bausatz prüft bei Motorfahrt die Geschwindigkeit. Wird trotz Ansteuerung des Motors eine Geschwindigkeit von 0 zurückgeliefert, werden die Motoren ausgeschaltet und ein Beep ertönt. Dies schont wirkungsvoll die Batterien.

Die Geschwindigkeit in den Motoren wird mit der Funktion setTarPWM() gesetzt. Hier muss man selbst aufpassen, welcher Motor vorwärts und welcher rückwärts eingebaut ist und entsprechend das Vorzeichen ändern. Indem man die Funktion setTarPWM() aufruft, wird die Klasse in den direkten Steuerungsmodus PWM gesetzt und stellt die Geschwindigkeit wie bei unserem vorherigen Beispiel via PWM-Duty-Cycle ein. Damit ergibt sich auch eine ähnliche Ausgabe wie bei unserem bisherigen Programm.

8.8. Motorleistung adaptiv regeln mittels in der Encoder-Klasse

Die Ansteuerung via setzen der Ziel-PWM ist die einfachste und direkteste Möglichkeit, den Roboter zu steuern. Aber wie oben erwähnt kann man so kaum eine geforderte Fahrgeschwindigkeit bestimmen. Die Klasse MeEncoderOnBoard bietet aber noch eine zweite Variante, wie man die Geschwindigkeit bzw. Motorleistung definieren kann: einen klassischen P-Regler-Ansatz.

Hierbei wird die aktuelle Geschwindigkeit andauernd mit der Sollgeschwindigkeit verglichen. Die Abweichung (der Regelfehler) wird dazu benutzt, um die Leistung/PWM der Motoren solange anzupassen, bis die Ist-Geschwindigkeit der Soll-Geschwindigkeit entspricht und der Regelfehler (nahezu) 0 wird.

Beispielprogramm für die adaptive Regelung der Geschwindigkeit
// Testprogramm für die Ansteuerung der DC Motoren via Makeblock Bibliothek
#include <MeAuriga.h>

MeEncoderOnBoard Encoder_1(SLOT1);
MeEncoderOnBoard Encoder_2(SLOT2);

// Interruptfunktion für Encoder 1
void isr_process_encoder1(void) {
  if (digitalRead(Encoder_1.getPortB()) == 0)     Encoder_1.pulsePosMinus();
  else                                            Encoder_1.pulsePosPlus();
}

// Interruptfunktion für Encoder 2
void isr_process_encoder2(void) {
  if (digitalRead(Encoder_2.getPortB()) == 0)     Encoder_2.pulsePosMinus();
  else                                            Encoder_2.pulsePosPlus();
}

int lastOutputMillis;
int targetSpeedRPM;
char buf[4];
int buffIndex;

void setup() {
  // Festlegen der Interruptfunktionen für das Messen/Zählen der Bewegung
  attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
  attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
  Serial.begin(115200);

  // Interne Timer der PWM auf 8KHz programmieren
  TCCR1A = _BV(WGM10);
  TCCR1B = _BV(CS11) | _BV(WGM12);

  TCCR2A = _BV(WGM21) | _BV(WGM20);
  TCCR2B = _BV(CS21);

  // Die PID Reglerparameter einstellen, eigentlich nur den P-Teil des Reglers, denn der Integral und Differentialteil
  // werden bei der Geschwindigkeitsregelung nicht benutzt.
  Encoder_1.setSpeedPid(0.18, 0, 0);
  Encoder_2.setSpeedPid(0.18, 0, 0);

  // Variable für gelegentliche Ausgaben auf die serielle Schnittstelle
  lastOutputMillis = millis();
  targetSpeedRPM = 0;
  buffIndex = 0;
}

void loop() {
  // von der seriellen Schnittstelle lesen

  // eine maximal 3-stellige Zahl von der seriellen Schnittstelle lesen
  char lastChar;
  while (Serial.available() && buffIndex<4) {
    lastChar = Serial.read();
    // Falls noch weniger < 3 Zeichen und kein Zeilenende, Zeichen in Puffer schieben
    if (lastChar != '\n' && buffIndex != 3)
      buf[buffIndex++] = lastChar;
    else {
      // Zeichenkette in Puffer mit \0 beenden
      buf[buffIndex] = '\0';
      // Text in Zahl umwandeln
      targetSpeedRPM = atoi(buf);
      Serial.print("targetspeed = ");
      Serial.println(targetSpeedRPM);
      // Motorzielgeschwindigkeiten anpassen
      Encoder_1.runSpeed(-targetSpeedRPM);
      Encoder_2.runSpeed(targetSpeedRPM);
      buffIndex = 0;
    }
  }

  // In der loop() Funktion wird die Geschwindigkeit im Motor geregelt
  Encoder_1.loop();
  Encoder_2.loop();

  // alle 100 Millisekunden die Geschwindigkeit und Duty Cycle ausgeben
  if (millis() > lastOutputMillis + 100) {
    lastOutputMillis = millis();
    Serial.print("TargetSpeed:");
    Serial.print(targetSpeedRPM);
    Serial.print(",Speed1:");
    Serial.print(-Encoder_1.getCurrentSpeed());
    Serial.print(",PWM1:");
    Serial.print(-Encoder_1.getCurPwm());
    Serial.print(",Speed2:");
    Serial.print(Encoder_2.getCurrentSpeed());
    Serial.print(",PWM2:");
    Serial.println(Encoder_2.getCurPwm());
  }
}

In diesem Programm wird die geforderte Geschwindigkeit über die serielle Schnittstelle gelesen. Im SerialPlotter oder SerialMonitor kann man dazu eine 3-stellige Zahl eingeben. In jedem Schleifendurchlauf wird ein neues Zeichen von der seriellen Schnittstelle in einen Pufferspeicher gelesen, bis entweder ein Zeilenendzeichen (\n) folgt, oder das 4. Zeichen gelesen wurde. Dann wird der Text im Pufferspeicher mit einem \0 beendet und in eine Zahl gewandelt. Diese wird dann als Soll-Drehzahl übergeben (in der etwas unzutreffenden Funktion runSpeed(). Der Controller berechnet in der stets aufgerufenen MeEncoderOnBoard::loop()-Funktion den Regelfehler und passt den Duty Cycle (PWM) entsprechend an.

Im Quelltext besteht der wesentliche Unterschied zur ungeregelten Ansteuerung des Motors in der Festlegung der Zielgeschwindigkeit mit der Funktion runSpeed():

// Motorzielgeschwindigkeiten anpassen
Encoder_1.runSpeed(-targetSpeedRPM);
Encoder_2.runSpeed(targetSpeedRPM);

Hier wird die Geschwindigkeit in RPM vorgegeben. Für die Berechnung der Korrektur des PWM-Duty-Cycle wird noch der P-Regler-Faktor benötigt. Den setzt man in der setup() Funktion mit setSpeedPid():

// Die PID Reglerparameter einstellen, eigentlich nur den P-Teil des Reglers, denn der Integral und Differentialteil
// werden bei der Geschwindigkeitsregelung nicht benutzt.
Encoder_1.setSpeedPid(0.18, 0, 0);
Encoder_2.setSpeedPid(0.18, 0, 0);

In diesem Programmbeispiel kann die Geschwindigkeit direkt als 3-stellige Zahl angegeben werden. Entsprechend ist das Lesen aus der seriellen Schnittstelle etwas komplexer (Zeichenweise erst in einen Puffer, der dann eine abschließende 0 erhält und dann mit der c-Funktion atoi() in eine Zahl gewandelt wird).

Wir testen das wiederum mit verschiedenen Zielgeschwindigkeiten:

auriga encoder speed 8kHz RPM controlled
Abbildung 21. Geregelte Motorleistung, getestet mit 4 Geschwindigkeiten (50, 100, 200, und Max. 340 rpm) sieht das so aus (ein Motor wieder mit Kette, der andere frei drehend):

Man sieht sehr schön, dass der Regler es eigentlich ganz gut schafft, bei beiden Motoren die geforderten Drehzahlen zu erreichen. Nur in der höchsten Stufe schafft es der Motor mit Kette nicht ganz die geforderte Drehzahl zu erreichen, denn er läuft schon konstant am obersten Limit (Duty Cycle 100%). Aufgrund der unterschiedlichen Reibwiderstände muss der Motor mit der Kette (hellblau) stets einen deutlich höheren Duty Cycle fahren, um die Drehzahl zu erreichen.

8.9. Andere Steuerungsfunktionen in der Makeblock-Bibliothek

Statt nur die Motorgeschwindigkeiten zu kontrollieren, kann man mit der Klasse MeEncoderOnBoard den Land Raider eine bestimmte Strecke fahren lassen. Das Beispiel in der Makeblock-Bibliothek Me_Auriga_encoder_pid_pos.ino zeigt die Verwendung der Klasse moveTo(). Ein weiteres Beispiel Me_Auriga_encoder_callback.ino zeigt eine Variante dieses Aufrufs, bei der bei Erreichen des Endpunktes eine callback-Funktion aufgerufen wird.

Die Idee der moveTo() Funktion ist folgende:

  • die Pulse werden in eine zurückgelegte Entfernung umgerechnet und es wird die verbleibende Entfernung bis zum Ziel ausgerechnet

  • die Geschwindigkeit wird in Abhängigkeit dieser noch verbleibenden Entfernung gewählt - je weiter weg, umso schneller (allerdings begrenzt durch einen Maximalwert)

  • sinkt die verbleibende Strecke, so wird auch die Geschwindigkeit (durch den P-Anteil) reduziert

  • der D-Anteil des Reglers wird benutzt, um einem Überschreiten des Zielwertes entgegenzuwirken

Der I-Parameter wird nicht verwendet.

In meinen Tests funktionierte die moveTo() Funktion nicht so wirklich gut. Auch fiepten die Motoren nach Erreichen der Zielentfernung weiterhin vor sich hin, wurden also wohl nicht komplett ausgeschaltet. Aber als Ideengrundlage für eine eigene Streckensteuerung kann man das verwenden.

8.10. Zusammenfassung

Die Ansteuerung der Motoren selbst ist direkt über das Setzen des PWM-Duty-Cycles und der Richtungsbits sehr einfach möglich. Um aber eine wirklich kontrollierte Fahrt zu programmieren, muss man die Drehgeschwindigkeit mittels Encodern bestimmen. Dazu werden Interruptfunktionen bentuzt, welche Pulse zählen. Diese können dann in Geschwindigkeiten oder zurückgelegte Entfernungen umgerechnet werden.

Die Klasse MeEncoderOnBoard der Makeblock-Bibliothek bietet mit der Funktion runSpeed() eine P-Regler-kontrollierte Steuerung für die Motorgeschwindigkeit entsprechend einer geforderten Drehzahl. Das ist schon recht bequem. Die Funktion moveTo() der Klasse ist aber nicht so toll und sollte besser durch eine eigene Funktion ersetzt werden.

9. Über den Autor

Vielleicht abschließend noch ein paar kurze Infos über mich. Meine Name ist Andreas Nicolai (ursprünglich aus Berlin, aber jetzt schon seit vielen Jahren in Dresden) und ich bin in einer Zeit groß geworden, als Computer noch recht primitiv waren (mein erster Rechner war ein Commodore PC-10 III mit gerade mal 4.7…​9.6 Mhz Taktfrequenz). Entsprechend einfach war die Software (und entsprechend simpel waren die Spiele). Aber so konnte ich die Entwicklung der Hardware und Software über inzwischen 4 Jahrezehnte mitverfolgen.

Obwohl meine Leidenschaft eigentlich der numerischen Simulation gilt (ich liebe es, einen Rechner richtig mit knackigen Aufgaben schuften zu lassen :-) ), hab ich seit kurzem meine Begeisterung für Microcontroller und Mikroelektronik entdeckt (und verstehe jetzt endlich, wie das ganze Zeug unter der Haube funktioniert). Und da ich nun schon seit mehr als 35 Jahren C/C++ programmiere, finde ich es auch spannend, mich in die (glücklicherweise) als Open-Source vorliegende Bibliothekssoftware einzugraben und herauszufinden, wie die verschiedenen Hardwarekomponenten so angesteuert werden. Naja, und beruflich hab ich auch gerade viel mit Regelungstechnik und Automatisierung zu tun, und da passt das ja irgendwie zusammen.