RC Roboter Controller (deutsch)

Wattuino RC – Getting started

Der Wattuino RC ("Roboter Controller") basiert auf dem SAMW25, einem SoC, das den SAMD21 Microcontroller (ARM Cortex-M0+ Kern) mit dem WINC1500 WiFi Chipsatz kombiniert. Auf der Platine befinden sich zwei Allegro A3909-LY Motortreiberbausteine, mit denen sich bis zu vier zweipolige Gleichstrommotoren mit maximal 1A pro Phase steuern lassen. Sieben als digitale oder analoge Inputs oder Outputs nutzbare Pins sind über die Stecker J1 bis J7 zugänglich. S1 stellt einen Mosfet bereit, der bis zu 2A schalten kann. SPI, UART und I2C sind über jeweils eigene Stecker zugänglich. Alle Inputs sind 5V tolerant, wobei natürlich bei analogen Messungen zu beachten ist, dass die Referenzspannung 3,3 Volt sind.

Das Board kennenlernen

Bei der Entwicklung des Wattuino RC hat Watterott Electronic viel Wert auf beste Kompatibilität zur Arduino IDE und den Standard-Bibliotheken gelegt. Dennoch gibt es einige Details zu beachten, in denen sich der Wattuino RC von der Verwandtschaft (Arduino Zero plus Wifi 101 Shield plus Allegro A3909-LY unterscheidet). Dieser Abschnitt stellt Software und Hardware vor und erläutert die Inbetriebnahme.

Vorbereitung der Arduino IDE

Um den Wattuino RC programmieren zu können, ist die Arduino IDE in Version 1.8 oder höher erforderlich. Fügen Sie unter "Datei > Voreinstellungen" die Boardverwalter-URL

https://github.com/watterott/Arduino-Boards/raw/master/package_watterott_index.json

Eitech-Variante:

https://github.com/watterott/Eitech-Robotics/raw/master/arduino/package_eitech_index.json

hinzu und öffnen Sie anschließend über "Werkzeuge > Boards > Boardverwalter" die Verwaltung der Hardwareunterstützung. Hier muss zunächst das Paket "Arduino SAMD Boards" (Herausgeber Arduino) installiert werden. Es bringt Compiler für ARM Cortex M0+ und Upload-Tool für den SAM-BAR Bootloader mit. Ist dies geschehen, installieren Sie "Watterott SAMD Boards" (alternativ Suchbegriff “Eitech”), es enthält im wesentlichen das Pin-Mapping des Wattuino RC/Eitech Robotics.

Unter Windows werden diese Treiber für den seriellen Zugriff benötigt.

Installation der Watterott SAMD Unterstützung

Um Compiler und Upload zu testen, sollten Sie "Datei > Beispiele > Blink" öffnen und unmodifiziert kompilieren und hochladen. Die Pin-Nummer 36 der Status-LED in der Nähe des Reset-Schalters muss nicht explizit angegeben werden, sie ist über das Macro LED_BUILTIN ansteuerbar.

Das Board-Layout

Die folgende Grafik zeigt die Anschlüsse des Wattuino RC, seine Arduino Pin-Belegungen, sowie Busse in Standard-Beschaltung. Sie können die Grafik unter https://github.com/mschlenker/PinoutsArduinoCompatible als PDF herunterladen und als "Spickzettel" ausdrucken.


Pinout des Wattuino RC

Serielles Debugging

Der USB-Port, welcher der Programmierung dient, kann als normaler serieller Port angesprochen werden und zur Ausgabe von Status- oder Debugging-Funktionen dienen. Wie bei anderen Boards, bei denen "Serial" in Software über den USB-Port realisiert ist, ist der Port im Programmcode erst verfügbar, nachdem er geöffnet wurde. Das folgende Beispiel verlässt die Setup-Routine erst, wenn eine USB-Verbindung besteht und diese im seriellen Monitor geöffnet wurde.

void setup() {
  // put your setup code here, to run once:
  Serial.begin(9600);
  pinMode(LED_BUILTIN, OUTPUT);
  while (!Serial) {
    ; // wait for serial port to connect. Needed for native USB port only
  }
}

void loop() {
  // put your main code here, to run repeatedly:
  Serial.println("Hallo Welt!");
  delay(1000);
  digitalWrite(LED_BUILTIN, HIGH);
  delay(500);
  digitalWrite(LED_BUILTIN, LOW);
}

Über "Serial1" kann der Hardware-UART (im Pinout-Diagram als RX1/TX1 gekennzeichnet) ohne diese Einschränkung angesprochen werden.

Digitale und analoge Pins

Auf der linken Seite der Platine finden Sie die sieben mit J1 bis J7 beschrifteten Stecker. Auf dem äußeren Pin liegt jeweils Masse an, auf dem mittleren 5V, der innere liegt auf dem Pin des Microcontrollers. Die Zuordnung zu Pins im Arduino-Schema ist wie folgt:

Platine Arduino digital analog
J1 D15 A0
J2 D25 A7
J3 D18 A3
J4 D19 A4
J5 D20 A5
J6 D21 A6
J7 D16 A1

Jeder der Pins kann als digitaler und analoger Input, sowie als digitaler Output benutzt werden. PWM ist nur an den Pins J3 bis J7 verfügbar. Um alle Pins (und damit die parallel geschalteten LEDs) der Reihe nach anzuschalten können Sie folgenden Sketch verwenden.

//                J1  J2  J3  J4  J5  J6  J7   
int allPins[] = { 15, 25, 18, 19, 20, 21, 16 };

void setup() {
  for (int i=0; i<7; i++) {
    pinMode(allPins[i], OUTPUT); 
  }
}

void loop() {
  for (int i=0; i<7; i++) {
    digitalWrite(allPins[i], HIGH);
    delay(300); 
  }
  delay(300); 
  for (int i=0; i<7; i++) {
    digitalWrite(allPins[i], LOW); 
  }
  delay(600); 
}

Zudem existiert am Anschluss S1 ein MOSFET, das über D37 maximal 2A schalten kann und PWM unterstützt, naturgemäß ist dieser Pin nur als Output nutzbar.

Für die Motorsteuerung werden acht Pins verwendet, die Zuordnung ist jeweils:

Platine 1. Pin 2. Pin
M1 D7 D6
M2 D1 D0
M3 D3 D2
M4 D5 D4

Sind beide Pins abgeschaltet, befindet sich der Motor im Freilauf, ist der derste Pin HIGH, der zweite LOW, läuft er vorwärts. Umgekehrt bei erstem Pin LOW und zweitem Pin LOW rückwärts. Beide Pins HIGH bedeutet aktives Bremsen. Alle acht Pins sind mit Pulsweitenmodulation zur Drehzahlregelung oder zum sanften Anfahren oder Abbremsen ausgestattet, wobei jeweils beide Pins eines Motors einen gemeinsamen Timer nutzen.

void setup() {
  // put your setup code here, to run once:
  pinMode(7, OUTPUT);
  pinMode(6, OUTPUT);
  pinMode(LED_BUILTIN, OUTPUT);
  digitalWrite(6, LOW);
}

void loop() {
  for (int i=63; i<256; i++) {
    analogWrite(7, i); 
    digitalWrite(LED_BUILTIN, HIGH);  
    delay(100);
    digitalWrite(LED_BUILTIN, LOW);
    delay(100);   
  }
  digitalWrite(7, HIGH);
  delay(2000); 
}

Die Auflösung des DAC (Digital Analog Converter) kann vom Standard 8 Bit (256 Stufen) auf 10 oder 12 Bit erhöht werden, hierfür dient die Funktion:

analogWriteResolution(12);

Standardfrequenz der Pulsweitenmodulation sind 730Hz, flackernde LEDs mit dieser Frequenz nimmt das menschliche Auge nicht war, steuert man jedoch einen Elektromotor mit dieser Frequenz an, kann es insbesondere bei einem niedrigen Duty Cycle zu einem unangenehmen Sirren kommen, zudem sind bei niedrigen Drehzahlen hörbare Schwebungen möglich. Sind auch technische Einschränkungen mit der niedrigen Frequenz verbunden (unrunder Lauf, wenn Motordrehzahl und PWM-Frequenz nahe beieinander liegen), können Sie mit den Bibliotheken https://github.com/adafruit/Adafruit_ZeroTimer und https://github.com/avandalen/avdweb_SAMDtimer die Timer ändern und so höhere PWM-Frequenzen erreichen.

ACHTUNG: Bei der Verwendung von PWM für die Motorsteuerung ist zu beachten, dass TCC4 auch von Arduinos Servo Bibliothek benutzt wird! Soll ein Servo verwendet werden, ist kein PWM an M2 möglich. Gleiches gilt für TCC5 und die Tone-Library von Arduino: Die Verwendung von PWM an M4, die Nutzung des USB-Ports als serielle Schnittstelle und die Verwendung der Tone-Bibliothek schließen sich gegenseitig aus!

Inbetriebnahme des WLAN-Moduls

Das im SoC integrierte WLAN-Modul entspricht dem als separates Shield erhältlichen WINC1500, das auf dem Arduino Shield "Wifi101" verlötet ist, es verwendet den SPI-Bus und kann mit der Bibliothek "Wifi101" (Herausgeber "Arduino", Nachinstallation erforderlich) angesprochen werden. Wichtig bei Verwendung des WLAN-Moduls mit der Arduino-IDE und der mitgelieferten Bibliothek "Wifi101" ist, dass Firmware-Stand des WLAN-Moduls zur Version der Bibliothek passt.

Um dies zu gewährleisten, sollten Sie bei Inbetriebnahme (und nach Updates der Arduino-IDE) ein Update der Firmware vornehmen. Hierfür wird zunächst der Sketch "Datei > Beispiele > Wifi101 > Firmware-Updater" auf dem Wattuino RC installiert. Anschließend starten Sie "Werkzeuge > WiFi101 Firmware Updater". Wählen Sie hier den seriellen Port, an dem der Wattuino RC angeschlossen ist und das korrekte Modell ("…510PB" auf dem Aufkleber mit MAC-Adresse und FCC ID bedeutet "Model B") und klicken Sie auf "Update Firmware". Im Abschnitt 3. können Sie darüber hinaus die zu bestimmten Domains gehörenden SSL-Root-Zertifikate installieren, falls Sie HTTPS-Verbindungen aufbauen wollen. Beachten Sie bei der Zertifikats-Installation, dass es durchaus vorkommen, dass Stammzertifikate widerrufen werden (siehe Fall Symantec) und sich die Seiten mit neuen Zertifikaten ausweisen. Während Webbrowser neue Stammzertifikate bei regulären Updates installieren und abgelaufene oder zurückgezogene Zertifikate entfernen, ist bei Microcontroller-Boards in diesen Fällen eine manuelle Aktualisierung erforderlich.


Die Firmware des WINC1500 muss zur Version der Wifi101-Bibliothek passen

Die in der Arduino IDE unter "Datei > Beispiele > Wifi101" verfügbaren Code-Schnippsel können Sie mit dem Wattuino RC testen. Sinnvoll für das Verständnis des APIs sind insbesondere "ConnectWithWPA" und "WiFiWebServer". Unter "Datei > Beispiele > Wattuino RC > WebServer_Basic" finden Sie einen auf das Wattuino RC Board abgestimmten einfachen Webserver, mit dem Sie die Ausgänge J1 bis J7 schalten und auslesen können.

Der Beispielsketch enthält rund 220 Zeilen HTML-Code, weshalb wir an dieser Stelle auf den vollständigen Abdruck verzichten:


Steuern Sie den Wattuino RC mit einem HTML Formular fern

Im Sketch müssen Sie entscheiden, ob der Wattuino RC als WPA-Client oder -Accesspoint dienen soll. Der Accesspoint-Modus des Wattuino RC ist zwar praktisch, weil er fernab des heimischen WLANs funktioniert, allerdings müssen Sie ggf. austesten, ob Ihr Smartphone oder Tablet auch Accesspoints ohne Internetverbindung akzeptiert. Ist der Sketch hochgeladen, können Sie gegebenenfalls die IP-Adresse des Wattuino RC aus dem Accesspoint oder DSL-Router auslesen (ein Blick auf die MAC-Adresse auf dem Aufkleber des Wattuino RC hilft bei der Identifikation). Zum Zugriff auf den Wattuino RC genügt dann ein Webbrowser.


Da isser! MAC-Adresse vergleichen hilft, den Wattuino RC aufzuspüren

UDP fürs Datenlogging

Meist ist das Ziel der Mühe am Roboter ein autonommer Roboter, der Hindernisse umfährt oder einer Linie folgt (ihn per WLAN fernzusteuern wäre geschummelt). Allerdings kann es sehr sinnvoll sein, Sensordaten zu einem PC zu schicken um Denkfehler oder nicht wie gewünscht messende Sensoren (Erfassungswinkel eines Distanzsensors falsch eingeschätzt o.ä.) schnell zu erkennen und zu beheben. Auch ist es oft praktisch, Parameter der Software (Dauer gegenläufiger Motorbewegung zum Drehen auf der Stelle, Abstände zu Hindernissen, an denen reagiert werden soll…) während des Betriebs setzen zu können, ohne einen neuen Sketch auf das Board hochladen zu können. Unser erster Sketch verbindet sich mit einem WLAN-Netzwerk, liest einen Potentiometer an J1 aus (analog/DAC, 10 Bit Auflösung) und erstellt daraus eine Statusmeldung als String. Dann schickt es den gemessenen Wert im Sekundentakt zu einem Rechner im Netz, das Ziel ist hier der Rechner mit IP 10.76.23.5, Port ist 6789. Wichtig ist hier, WiFiUDP.begin() mit einer Portnummer aufzurufen, selbst dann wenn kein Empfang von UDP-Paketen, sondern lediglich das Senden gewünscht ist.

#include <SPI.h>
#include <WiFi101.h>
#include <WiFiUdp.h>

int status = WL_IDLE_STATUS;
char ssid[] = "pinguinbaendiger"; //  your network SSID (name)
char pass[] = "ganzgeheim";    // your network password 
char sendBuffer[64];

WiFiUDP Udp;

void setup() {
  pinMode(LED_BUILTIN, OUTPUT); 
  pinMode(A0, INPUT); 
  while ( status != WL_CONNECTED) {
    status = WiFi.begin(ssid, pass);
    // wait 10 seconds for connection:
    delay(9000);
    digitalWrite(LED_BUILTIN, HIGH);
    delay(1000);
    digitalWrite(LED_BUILTIN, LOW);
  }
  Udp.begin(1234); 
}

void loop() {
  sprintf(sendBuffer,"Messwert an J1: %4d", analogRead(A0)); 
  digitalWrite(LED_BUILTIN, HIGH);
  Udp.beginPacket( "10.76.23.5" , 6789) == 0; 
  Udp.write(sendBuffer); 
  Udp.endPacket();
  delay(1000);
  digitalWrite(LED_BUILTIN, LOW);
  delay(500);
}

Zum Empfangen verwenden wir ein kleines Python-Programm, das die erhaltenen Werte einfach auf die Standardausgabe schreibt, das ist kein Problem, da die Nachricht bereits als String formatiert wurde.

import socket

UDP_IP = "10.76.23.5" # an diese IP binden
UDP_PORT = 6789

sock = socket.socket(socket.AF_INET, # Internet
        socket.SOCK_DGRAM) # Unix Datagram Protocol
sock.bind((UDP_IP, UDP_PORT))

while True:
        data, addr = sock.recvfrom(1024) # Puffer 1024 bytes
        print "raw message: " , data

Genug Trockenübungen – Praxis!

Jetzt wird der Wattuino RC vom PC getrennt und auf dem Roboterchassis montiert. Getestet haben wir mit einem Watterott Roboter Starterkit V2, prinzipiell eignet sich jedes Roboterchassis mit Raupenantrieb oder zwei angetriebenen Rädern und genügend Platz für einen Akku für Gehversuche mit Robotern. Als Strombersorgung können Sie einen Akku mit 7 bis 14 Volt verwenden, der dann an den Batteriestecker "POWER" angeschlossen wird. Falls 5V für anzusteuernde Motoren genügen, können Sie auch eine Powerbank und ein kurzes USB-Kabel verwenden. Bei Stromversorgung über den USB-Port ist sicherzustellen, dass 5V nicht wesentlich über- oder unterschritten werden. Zudem sollte die gesamte Stromaufnahme 1A nicht überschreiten. Bei Stromversorgung mit einem separaten Netzteil sind 1A pro Motor und maximal 2A am per MOSFET geschalteten S1 möglich.

Hier ist unser Versuchsaufbau mit dem auf einem Servo montierten Ultraschall-Entfernungsmesser. Die Stromversorgung erfolgt über eine Powerbank. Die Halterung der Powerbank mit Bohrungen für den Wattuino RC kommt aus dem 3D-Drucker.


Der Versuchsaufbau für die folgenden Beispiele

Test mit Webserver

Sind die Motoren angeschlossen, können Sie mit unserem Beispielsketch "Datei > Beispiele > Wattuino RC > WebServer_Car" loslegen. Im Sketch müssen Sie die Anschlüsse der Motoren und deren Polarität eintragen, sowie entscheiden, ob der Wattuino RC als WPA_Client oder -Accesspoint dienen soll. Um den Roboter fernzusteuern genügt dann die Eingabe der IP-Adresse im Webbrowser. Der orangene Punkt dient dann als Joystick, um den Roboter nach links oder rechts zu drehen und schneller oder langsamer vorwärts und rückwärts zu fahren:


Klappt auch mit Smartphone oder Tablet: Fernsteuerung per virtuellem Joystick

Motoren kalibrieren

Gleichstrom-Elektromotoren mit Bürsten sind in der Regel nicht drehsymetrisch aufgebaut: In der Regel sind die Bürsten relativ zu den Statoren etwas verdreht, um früher ein Magnetfeld anliegen zu haben. Das garantiert höhere Drehzahlen und besseres Anlaufen, hat aber zur Folge, dass den Motor im Rückwärtslauf zu betreiben exakt den gegenteiligen Effekt hat. Bei verschraubten Motoren mit wechselbaren Bürsten (oft im RC-Flug- oder Automodellbaubereich zu finden) können Sie das Lagerschild mit den Bürsten bei laufendem Motor vorsichtig verdrehen, bis die höchste Drehzahl hörbar ist. Bei verklebten oder verklemmten Motoren ist dies nicht möglich. Hier ist die beste Abhilfe, einen der Motoren über Pulsweitenmodulation langsamer anzusteuern. Der folgende Beispielsketch kann dazu genutzt werden, den schnelleren Motor etwas abzubremsen, hier hatten wir beim Watterott Roboter Starterkit V2 bei ca. 245 (von 255, 8 Bit PWM) einen guten Geradeauslauf:

#define LEFTPHA  7
#define LEFTGND  6
#define RIGHTPHA 3
#define RIGHTGND 2

#define LEFTFWD   245
#define RIGHTFWD  255
#define LEFTBACK  255
#define RIGHTBACK 245

void setup() {
  // put your setup code here, to run once:
  pinMode(LEFTPHA, OUTPUT);
  pinMode(RIGHTPHA, OUTPUT);
  pinMode(LEFTGND, OUTPUT);
  pinMode(RIGHTGND, OUTPUT);
  pinMode(LED_BUILTIN, OUTPUT);
  analogWrite(LEFTPHA, 0);
  analogWrite(RIGHTPHA, 0);
  analogWrite(LEFTGND, 0);
  analogWrite(RIGHTGND, 0);
}

void loop() {
  analogWrite(RIGHTPHA, RIGHTFWD);
  analogWrite(LEFTPHA, LEFTFWD);
  analogWrite(RIGHTGND, 0);
  analogWrite(LEFTGND, 0);
  delay(3000);
  analogWrite(RIGHTPHA, 0);
  analogWrite(LEFTPHA, 0);
  analogWrite(RIGHTGND, RIGHTBACK);
  analogWrite(LEFTGND, LEFTBACK);
  delay(3000); 
}

Einen Ultraschallsensor auslesen

Sehr praktisch für die Roboterei sind Ultraschallsensoren wie der HC-SR04 (Art.-Nr. 20110874). Diese haben einen einigermaßen guten Erfassungsbereich (ca. 2cm bis 400cm geradeaus, im Nahbereich rund 45° Erfassungswinkel) und sind leicht von Arduino anzusprechen: Über den Trigger-Pin wird ein 2 bis 10ms langer Impuls zum Sensor geschickt, dessen IC antwortet mit einem langen Puls, der der Laufzeit des Signals entspricht. Bei rund 340m/s Schallgeschwindigkeit und unter Beachtung der zwei zurückgelegten Wege entspricht demnach 1/100 s oder 10000µs Signallaufzeit einer Objektdistanz von 1,7m. Für den Testaufbau haben wir den Sensor mit TRIG auf TX des UART und ECHO auf RX des UART angeschlossen (dies ermöglichte es, ein einziges Kabel zu nutzen, Art.-Nr. 20170071). Zur Messung kommt die Arduino-Funktion PulseIn() zum Einsatz.


Das Plateau des Echo-Signals hat exakt die Länge der Signallaufzeit

Für das folgende Beispiel haben wir den Sketch fürs Logging per UDP auf den Ultraschallsensor übertragen: Zunächst wird der Trigger-Pin 2 bis 10µs auf high gezogen und dann sofort pulseIn() aufgerugen, hier mit einem Timeout von 25000µs – ohne Timeout würde die Funktion eine Sekunde auf einen eingehenden Impuls warten – allerdings beträgt die Reichweite des Sensors keine 170 Meter.

#include <SPI.h>
#include <WiFi101.h>
#include <WiFiUdp.h>

int status = WL_IDLE_STATUS;
char ssid[] = "pinguinbaendiger"; //  your network SSID (name)
char pass[] = "geheim";    // your network password (use for WPA, or use as key for WEP)
// char SendBuffer[] =      "Hallo Welt Hallo Welt Hallo Welt Hallo Welt";       // a string to send back
char sendBuffer[63];
long duration; 

WiFiUDP Udp;

void setup() {
  pinMode(LED_BUILTIN, OUTPUT); 
  // Trigger for ultrasonic
  pinMode(14, OUTPUT);
  // PulseIn for ultrasonic
  pinMode(13, INPUT);
  // attempt to connect to WiFi network:
  while ( status != WL_CONNECTED) {
    // Connect to WPA/WPA2 network. Change this line if using open or WEP network:
    status = WiFi.begin(ssid, pass);
    // wait 10 seconds for connection:
    delay(9000);
    digitalWrite(LED_BUILTIN, HIGH);
    delay(1000);
    digitalWrite(LED_BUILTIN, LOW);
  }
  Udp.begin(1234); 
}

void loop() {
  digitalWrite(14, HIGH);
  delayMicroseconds(10);
  digitalWrite(14, LOW);
  // max. 25ms warten
  duration = pulseIn(13, HIGH, 25000); 
  sprintf(sendBuffer,"Echo nach %5d µs", duration); 
  digitalWrite(LED_BUILTIN, HIGH);
  Udp.beginPacket( "10.76.23.5" , 6789) == 0; 
  Udp.write(sendBuffer);
  Udp.endPacket();
  delay(1000);
  digitalWrite(LED_BUILTIN, LOW);
  delay(500);
}

Mit einem Servo arbeiten

Wenn Sie den Roboter nur mit den Informationen des Ultraschallsensors versuchen zu steuern, werden Sie schnell feststellen, dass der Roboter immer wieder im spitzen Winkel auf ein Hindernis fährt und daran hängen bleibt. Abhilfe schafft hier ein Servo, auf das der Sensor montiert wird. Typischerweise kann ein schnelles Modellbauservo aus der Mittellage in etwa 0,2 bis 0,3 Sekunden 90° in der einen oder anderen Richtung erreichen. Servos werden in der Regel über ein PWM-Signal mit 50Hz angesprochen, wobei der Duty-Cycle den Ausschlag bestimmt. Der Abgleich erfolgt mit einem internen Potentiometer. Die Arduino IDE stellt für Servos eine eigene Bibliothek zur Verfügung, die auf dem ATSAMD21 des Wattuino RC und verwandter Boards (Arduino Zero) den Timer 4 verwendet. Dies hat zur Folge, dass an M2 keine Pulsweitenmodulation verwendet werden kann!

Achtung! Typische Modellbauservos nehmen bei geringer Last (wie bei dem auf dem Servohorn montierten Sensor) 10 bis 50mA auf. Dieser benötigte Strom kann aber massiv ansteigen, sobald das Servo gegen einen Widerstand arbeiten muss – 1A ist nicht ungewöhnlich. Um das Wattuino RC Board nicht zu beschädigen, sollten Sie bei hohen Lasten das Servo nicht über das Board versorgen. Bei externer Versorgung ist die maximale Arbeitsspannung des Servos zu beachten: Viele Servos sind bis 5,0V spezifiziert, andere bis 7,4V oder 12V.

Der folgende Sketch nutzt die Bibliothek Servo, um das Servo an J7 in der Setup-Routine zunächst in Mittelstellung zu bringen und zehn Sekunden zu warten. Dann fährt das Servor die Punkte 0° und 180° an, um wieder in Mittelstellung zu verharren. Beachten Sie, dass viele Servos eher 210° bis 240° Winkel aufweisen, einege fast 360° schaffen. 0° und 180° dienen hier lediglich dazu, die äußeren Anschläge zu identifizieren.

Während der 5 Sekunden Wartezeit in der Setup-Routine können Sie den Wattuino RC von der Stromversorgung trennen, das Servohorn abschrauben und es zusammen mit dem Sensor in Mittelstellung montieren. Die Wartezeit beim Wechsel der Richtung sollte gerade groß genug sein, dass das Servo an der Mittel- bzw. Endposition einen Moment verharrt:

#include <Servo.h>

Servo myservo;  // create servo object to control a servo

void setup() {
  myservo.attach(16);  // J7
  myservo.write(90); 
  delay(5000); 
}

void loop() {
  myservo.write(0);                  
  delay(600);          
  myservo.write(180);  
  delay(1200);     
  myservo.write(90);  
  // delay(500);
  delay(2000); 
}

Alles zusammen: Roboter mit Ultraschallsensor auf Servo

Der folgende Beispielsketch verwendet einem auf dem Servo montierten Ultraschall-Entfernungssensor um sich seinen Weg zu suchen. Bei direkter Fahrt auf ein Hindernis dreht er um ca. 90°, wird ein Hindernis in spitzem Winkel angefahren um etwa 30°. Bei freiem Weg fährt der Roboter 0,3 Sekunden lang gerade aus, bevor er erneut prüft. Die Werte für die Zeit umzudrehen und die Geradeausfahrt sind maßgeblich von der Geschwindigkeit der Motoren abhängig. Bei Verwendung schneller Fahrmotoren und langsamer Servos kann es sinnvoll sein, bei sehr nahen Distanzen zu einem Hindernis anzuhalten und die Umgebung zunächst per Servo und Ultraschallsensor zu scannen, anstatt einfach irgendwo hin zu fahren. Hilfreich bei Ermittlung der benötigten Zeit zum Umdrehen kann zudem ein Magnetometer (Pollolu LSM303D, Art.-Nr. 2127) sein, der später auch dazu dienen kann, in eine bevorzugte Richtung zu fahren.

Ab jetzt ist Ihre Kreativität gefragt: Unser Beispielsketch hat noch keinen Killswitch für den Fall, dass der Roboter Amok fährt (per Webinterface?), noch loggt er nicht per UDP und enthält keine zusätzlichen Sensoren – doch der Code sollte gut genug zu lesen sein, um ihn mit eigenen Ideen zu erweitern.

Wir wünschen viel Spaß und freuen uns auf Ihre Projektberichte mit dem Wattuino RC Board!

// Motors on M1 (left) and M3 (right)
#define LEFTPHA  7
#define LEFTGND  6
#define RIGHTPHA 3
#define RIGHTGND 2

// ECHO and TRIG for HC-SR04 
#define TRIG 14
#define ECHO 13

// Servo on J7
#define SERV 16
// How long does the servo need from 90° to 30°?
#define SERVDELAY 300

// Approach an obstacle straight ahead: 3500µs ~ 60cm
#define STRAIGHTOBST 3500
// How many ms does turning for about 90° take?
#define TURNTIME 250
// Approach an obstacle from the side: 3000µs ~ 50cm (divided by 10!)
#define SIDEOBST 300
// How many ms does turning for about 30 to 45° take?
#define SMALLTURN 150
// How many ms go straight before checking again?
#define STRAIGHTTIME 300

#include <Servo.h>

Servo myservo;  // create servo object to control a servo

long duration = 10000; 
long lastDistLeft = 500;
long lastDistRight = 500; 
int lastSide = 0; 

void setup() {
  pinMode(LEFTPHA, OUTPUT);
  pinMode(LEFTGND, OUTPUT);
  pinMode(RIGHTPHA, OUTPUT);
  pinMode(RIGHTGND, OUTPUT);
  pinMode(LED_BUILTIN, OUTPUT);
  // Trigger for ultrasonic
  pinMode(TRIG, OUTPUT);
  // PulseIn for ultrasonic
  pinMode(ECHO, INPUT);
  myservo.attach(SERV);  
  digitalWrite(LEFTPHA, LOW);
  digitalWrite(LEFTGND, LOW);
  digitalWrite(RIGHTPHA, LOW);
  digitalWrite(RIGHTGND, LOW);
  digitalWrite(TRIG, LOW);
  myservo.write(45);
  delay(600); 
  myservo.write(135);
  delay(1200); 
  myservo.write(90);
  delay(600); 
}

void loop() {
  digitalWrite(RIGHTPHA, HIGH);
  digitalWrite(LEFTPHA, HIGH);
  digitalWrite(RIGHTGND, LOW);
  digitalWrite(LEFTGND, LOW);
  delay( STRAIGHTTIME / 3 ); 
  digitalWrite(TRIG, HIGH);
  delayMicroseconds(5);
  digitalWrite(TRIG, LOW);
  duration = pulseIn(ECHO, HIGH, 10000); 
  if (duration < STRAIGHTOBST && duration > 0) {
    digitalWrite(LEFTPHA, LOW);
    digitalWrite(LEFTGND, LOW);
    digitalWrite(RIGHTPHA, LOW);
    digitalWrite(RIGHTGND, LOW);
    turnAround(); 
  } else {
    checkSideWays(); 
  }
}

void checkSideWays() {
  long currentDuration;
  if (lastSide < 1) {
    myservo.write(30);
  } else {
    myservo.write(150);
  }
  delay(SERVDELAY); 
  digitalWrite(TRIG, HIGH);
  delayMicroseconds(5);
  digitalWrite(TRIG, LOW);
  currentDuration = pulseIn(ECHO, HIGH, 10000) / 10;
  myservo.write(90);
  if (currentDuration < SIDEOBST && currentDuration < lastDistLeft && lastSide < 1) {
    turnSmall(0);
  } else if (currentDuration < SIDEOBST && currentDuration < lastDistRight && lastSide > 0) {
    turnSmall(1);
  } else {
    digitalWrite(LEFTGND, LOW);
    digitalWrite(RIGHTGND, LOW);
    digitalWrite(LEFTPHA, HIGH);
    digitalWrite(RIGHTPHA, HIGH);
    delay(STRAIGHTTIME / 2); 
  }
  if (lastSide < 1) {
      lastDistLeft = currentDuration;
  } else {
      lastDistRight = currentDuration;
  }
  lastSide = (lastSide + 1) % 2; 
}

void turnSmall(int direction) {
  digitalWrite(LEFTGND, LOW);
  digitalWrite(RIGHTGND, LOW);
  digitalWrite(LEFTPHA, LOW);
  digitalWrite(RIGHTPHA, LOW);
  myservo.write(90); 
  int a = LEFTPHA;
  int b = RIGHTGND;
  int c = LEFTGND;
  int d = RIGHTPHA;
  if (direction > 0) {
    a = LEFTGND;
    b = RIGHTPHA;
    c = LEFTPHA;
    d = RIGHTGND;
  }
  digitalWrite(a, HIGH);
  digitalWrite(b, HIGH);
  digitalWrite(c, LOW);
  digitalWrite(d, LOW);
  delay(SMALLTURN);
  digitalWrite(a, LOW);
  digitalWrite(b, LOW);
}

void turnAround() {
  int a = LEFTPHA;
  int b = RIGHTGND;
  int c = LEFTGND;
  int d = RIGHTPHA;
  if (duration % 2 > 0) {
    a = LEFTGND;
    b = RIGHTPHA;
    c = LEFTPHA;
    d = RIGHTGND;
  }
  while (duration < STRAIGHTOBST && duration > 0) {
    digitalWrite(a, HIGH);
    digitalWrite(b, HIGH);
    digitalWrite(c, LOW);
    digitalWrite(d, LOW);
    delay(TURNTIME);
    digitalWrite(TRIG, HIGH);
    delayMicroseconds(5);
    digitalWrite(TRIG, LOW);
    duration = pulseIn(ECHO, HIGH, 10000);
  }
  digitalWrite(a, LOW);
  digitalWrite(b, LOW);
}