Der KeplerBRAIN V4 Soccer IR Ballsensor besteht aus zwei Komponenten - der Sensorplatine und einer KeplerBRAIN V4 Stamp. Auf der Sensorplatine befinden sich die IR Sensoren zum Dedektieren des gepulsten Signals des RCJ-05 IR Balls. Auf der KeplerBRAIN V4 Stamp werden die Sensordaten mit einem Mikrocontroller ermittelt und weiter verarbeitet.
Der RCJ-05 Ball
Ein Infrarot-Ball, der den neuen Spezifikationen der RoboCupJunior Soccer-Wettbewerbe entspricht. Dieser neue IR-Ball stellt eine bedeutende Verbesserung gegenüber den bisherigen Versionen dar, die seit vielen Jahren in RoboCupJunior Soccer-Wettbewerben verwendet wurden. Er ist eine Antwort auf die neuen RoboCupJunior-Regeln und die Schwächen der aktuellen, unmodulierten IR-Bälle, die anfällig für Umgebungslicht sind und einen relativ schnellen Batterieverbrauch aufweisen.
Der 40-kHz-Trägerausgang des Balls wird mit einer trapezförmigen (stufenweisen) Wellenform mit einer Frequenz von 1,2 kHz moduliert. Dies ermöglicht es den Sensoren, das vom Ball ausgesendete Infrarotlicht leicht von Infrarotemissionen anderer Quellen zu unterscheiden und auch die ungefähre Entfernung zum Ball zu schätzen.
Der neue Ball kann nicht nur in diesem neuen, modulierten Pulsmodus betrieben werden, sondern auch im derzeitigen unmodulierten Modus sowie in zwei weiteren Pulsmodulationsmodi für andere Roboterwettbewerbe (insgesamt 4 verfügbare Modi).
Für die Stromanzeige werden zwei gut sichtbare rote LEDs verwendet. Sie zeigen den Batteriestand in 3 Stufen an, indem sie mit unterschiedlichen Geschwindigkeiten blinken.
Spezifikationen
- IR-Signal-Modus
- A: Pulsmodulation gemäß RoboCupJunior Soccer Ball Standard (stufenförmige Wellenmodulation, 40-kHz-Träger)
- B: Unmodulierter RoboCupJunior Soccer Ball Standard (konstante IR-Emission)
- C: 600-Hz-Pulsmodulation (40-kHz-Träger)
- D: 1200-Hz-Pulsmodulation (40-kHz-Träger)
- IR-Spitzenwellenlänge: 940 nm
- Anzahl der IR-LEDs: 20 Stück
- Batterien (nicht enthalten): 4 x AAA-Alkali-Trockenbatterie (AM4/LR03, 1,5 V) oder Ni-MH-Akkus (1,2 V)
- Versorgungsspannung (Nennwert): 4,8–6 V DC
- Stromverbrauch:
- 80 mA (Modus A)
- 230 mA (Modus B)
- 130 mA (Modus C, D)
- Abmessungen: Durchmesser 74 mm (3 Zoll), kugelförmig
- Gewicht: ca. 95 g (0,21 lbs), ohne Batterien
Das Signal des RCJ-05 Balls
Der Ball sendet ein Signal aus, das aus Pulsen mit einer Frequenz von 1,2kHz (Pulsbreite 833us) besteht. Dieses ist auf eine Trägerfrequenz mit einer Frequenz von 40kHz (Pulsbreite 25us) aufmoduliert.
Die Intensität der Pulse ändert sich dabei, sodass damit auch die Entfernung zum Ball bestimmt werden können sollte. Aufgrund der Abnahme der Intensitäten der Pulse der Trägerfrequenz ergibt sich eine unterschiedliche Länge der Pulse des 1,2kHz Signals. Daraus wäre es möglich vier unterschiedliche Abstände zwischen einem Sensor und dem Ball ableiten zu lassen.
Die Sensorplatine
Design und Layout by Janez Rotman 2019
Auf der Sensorplatine befinden sich auf der 16 IR Sensoren. Auf der Oberseite kann über Steckleisten ein KeplerBRAIN V4 Stamp Board aufgesteckt werden. Zusätzlich sind dort ein Potentiometer und eine LEDs platziert, welche spezielle Aufgaben in der Firmware übernehmen können.
Da der Öffnungwinkel der Sensoren grundsätzlich sehr groß ist, empfiehlt es sich den Empfangsbereich für IR Signale einzuschränken um die Richtung, aus der ein Signal kommt besser dedektieren zu können. Dazu bietet es sich z. B. an, 3D Druckteile zu entwerfen, die vor die IR Sensoren platziert werden.
Die KeplerBRAIN V4 Stamp
Die KeplerBRAIN V4 Stamp ist ein Mikrocontrollerboard im Briefmarkenformat für die die Entwicklung eigener Sensoren innerhalb des KeplerBRAIN V4 Robotik-Systems. Darauf befindet sich der gleiche STM32F411 Mikrocontroller, wie auf dem Mainboard und allen anderen Sensoren. Von diesem Mikrocontroller sind IO-Pins, analoge Eingangspins und I2C-Pins herausgeführt, sodass damit umfangreiche Möglichkeiten für die Entwicklung bereitstehen.
Dieses Board wird mit dem KeplerBRAIN V4 Mainboard über eine der drei SPI Schnittstellen verbunden, über welche die Datenübertragung erfolgt und auch Versorgungspannungen von 3,3V und 5V zu Verfügung gestellt werden. Zusätzlich befindet sich auf dem Board ein sechspoliger Anschluss für den selben Programmieradapter mit dem auch der Mikrocontroller auf dem Mainboard programmiert werden kann.
Firmware für den Soccer Bodensensor
Eine Firmware ist quasi das Betriebssystem eines Sensors. Dieser kann 1:1 so in der Arduino IDE kompilliert und auf das die KeplerBRAIN V4 Stamp übertragen werden. In der Folge ist es aber auch möglich die Firmware zu erweitern, um z. B. die Analyse und weitere Verarbeitung der Sensorwerte direkt am Sensor auszuführen.
Die Werte im Array spi_data[] werden über die SPI-Schnittstelle in einem durchgehenden Stream von 9 Werten zum Mikrocontoller eines KeplerBRAIN Mainboards geschickt. Der erste Wert eines solchen Datenpakets ist jeweils die Zahl 250, mit der der Beginn eines Datenpakets vom empfangenden Mikrocontroller identifiziert werden kann. Dabei ist darauf zu achten, dass keiner der folgenden 8 Zahlen den Wert 250 annehmen darf. Hier wird nur ein einziger Wert übertragen, der die Nummer eines der 16 Sensoren enthält, der das Signal des Balls "sieht".
Erweiterung der Firmware
Es ist möglich, bereits auf dem Sensorboard eine Analyse der gemessenen Werte vorzunehmen oder Berechnungen mit den Werten durchzuführen und dann nur die Ergebnisse zum Mikrocontroller auf dem Mainboard zu übertragen. Dazu sind im folgenden Code in den Funktionen setup() und loop() zwei Bereiche mit dem Kommentar // User Code vorgesehen, in denen eigener Code platziert werden kann.
Es bietet sich zum Beispiel an das gleichzeitige Erkennen eines Signals bei zwei oder drei Sensoren bereits am Sensor auszufiltern und daraus eine Signalrichtung zu ermitteln und dann diese zum Roboter zu schicken.
Auch kann das Fluktuieren von Werten bereits in der Firmware abgefangen werden, damit dann nur stabile Werte zur Software des Hauptprogramms gesendet werden.
Weiters könnte man das Dedektieren des Signals von den 16 Sensoren auf 8 Richtungen herunterbrechen oder aber auch mitauswerten, ob das Signal von links nach rechts, oder umgekehrt gewandert ist, um die Bewegung eines Balls im Vergleich zum Roboter zu analysieren und für die Steuerung des Roboters zu verwenden.
Auch ist es möglich über den Programmieradapter direkt Werte im Serial Monitor der Arduino IDE zum Testen des eigenen Codes anzeigen zu lassen. Siehe dazu Arduino > Arduino C C++ > Serial Monitor
Firmware Variante 1
Mit diesem Code werden die Pins des Mikrocontrollers als digitaler Eingang konfiguriert. An diesen wird ausgewertet, ob von den IR Transistoren infrarotes Licht "gesehen" wird und diese den Pin dann auf HI oder LO setzen. Es erfolgt keine explizite Dedektierung des 40kHz Signals des Balls.
Beim Übertragen des Werts über SPI zum Mainboard des Roboters wird nur die Nummer des Sensors mit der höchsten Zahl (1, ..., 16) herangezogen und diese übertragen. Dies wäre dahingehend zu erweitern, dass bereits in der Firmware eine Logik eingebaut wird, die darüber entscheidet, welcher Wert für die Richtung eines Balls übertragen wird, wenn mehrere Sensoren den Ball "sehen".
// ***************************************************************************
// *** KeplerBRAIN V4 Sensor STAMP SPI Client IR Ballsensor V 15.01.2024 ***
// ***************************************************************************
// Array zum Speichern der detection results
volatile uint8_t arr_sensor[16] = {0};
// SPI Data
volatile uint8_t spi_data[9] = {250,1,2,3,4,5,6,7,8};
volatile uint8_t tx_index = 0;
void setup()
{
// Initialize SPI1 as Slave with interrupt
SPI1_Init();
// Enable the SPI1 interrupt in NVIC
NVIC_EnableIRQ(SPI1_IRQn);
pinMode(PB8, INPUT);
pinMode(PB7, INPUT);
pinMode(PB6, INPUT);
pinMode(PA8, INPUT);
pinMode(PC0, INPUT);
pinMode(PC2, INPUT);
pinMode(PB15, INPUT);
pinMode(PB14, INPUT);
pinMode(PB12, INPUT);
pinMode(PB13, INPUT);
pinMode(PB1, INPUT);
pinMode(PC5, INPUT);
pinMode(PA1, INPUT);
pinMode(PA0, INPUT);
pinMode(PC13, INPUT);
pinMode(PB9, INPUT);
// User Code
//Serial.begin(115200);
}
void loop()
{
// explizite Auswertung
if (digitalRead(PA8)) arr_sensor[0] = 0; else arr_sensor[0] = 1;
if (digitalRead(PB7)) arr_sensor[1] = 0; else arr_sensor[1] = 1;
if (digitalRead(PB8)) arr_sensor[2] = 0; else arr_sensor[2] = 1;
if (digitalRead(PB6)) arr_sensor[3] = 0; else arr_sensor[3] = 1;
if (digitalRead(PB14)) arr_sensor[4] = 0; else arr_sensor[4] = 1;
if (digitalRead(PC0)) arr_sensor[5] = 0; else arr_sensor[5] = 1;
if (digitalRead(PC2)) arr_sensor[6] = 0; else arr_sensor[6] = 1;
if (digitalRead(PB15)) arr_sensor[7] = 0; else arr_sensor[7] = 1;
if (digitalRead(PB13)) arr_sensor[8] = 0; else arr_sensor[8] = 1;
if (digitalRead(PB1)) arr_sensor[9] = 0; else arr_sensor[9] = 1;
if (digitalRead(PC5)) arr_sensor[10] = 0; else arr_sensor[10] = 1;
if (digitalRead(PB12)) arr_sensor[11] = 0; else arr_sensor[11] = 1;
if (digitalRead(PA1)) arr_sensor[12] = 0; else arr_sensor[12] = 1;
if (digitalRead(PA0)) arr_sensor[13] = 0; else arr_sensor[13] = 1;
if (digitalRead(PC13)) arr_sensor[14] = 0; else arr_sensor[14] = 1;
if (digitalRead(PB9)) arr_sensor[15] = 0; else arr_sensor[15] = 1;
// Ausgabe Sensorwerte und Übertragung
for (int i = 0; i < 16; i++)
{
if (arr_sensor[i] == 1)
{
//Serial.print("1 ");
// Die Nummer des Sensors mit der höchsten Zahl der
// ein Signal "sieht" wird übertragen
// !!! Dies ist zu verbessern und hier ist eine Logik
// zu entwickeln, was übertragen wird, wenn mehr als ein
// Sensor das Signal dedektiert
spi_data[1] = i+1;
}
else
{
//Serial.print("0 ");
}
}
//Serial.println("");
}
// Initialize SPI1 in slave mode with interrupt
void SPI1_Init()
{
// Enable clocks for GPIOA and SPI1
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// Configure PA4 (NSS), PA5 (SCK), PA6 (MISO), PA7 (MOSI) as alternate function
GPIOA->MODER &= ~(GPIO_MODER_MODER4 | GPIO_MODER_MODER5 | GPIO_MODER_MODER6 | GPIO_MODER_MODER7);
GPIOA->MODER |= (GPIO_MODER_MODER4_1 | GPIO_MODER_MODER5_1 | GPIO_MODER_MODER6_1 | GPIO_MODER_MODER7_1);
GPIOA->AFR[0] |= (5 << (4 * 4)) | (5 << (5 * 4)) | (5 << (6 * 4)) | (5 << (7 * 4)); // Set AF5 for SPI1
// Configure SPI1 as a slave
SPI1->CR1 = 0; // Reset CR1
SPI1->CR1 &= ~SPI_CR1_MSTR; // Set as slave
SPI1->CR1 &= ~SPI_CR1_SSM; // Disable software slave management
SPI1->CR1 |= SPI_CR1_SPE; // Enable SPI
SPI1->CR2 |= SPI_CR2_RXNEIE; // Enable RXNE interrupt
SPI1->CR2 |= SPI_CR2_TXEIE; // Enable TXE interrupt
}
extern "C" void SPI1_IRQHandler(void)
{
// Check if RXNE (Receive Not Empty) flag is set and handle RX first
if (SPI1->SR & SPI_SR_RXNE)
{
uint8_t rx_value = SPI1->DR;
}
// Check if TXE (Transmit Empty) flag is set, but only if not busy
if (SPI1->SR & SPI_SR_TXE)
{
// Send data from tx_buffer if in "send mode"
if (tx_index < 9)
{
// Write data to SPI
SPI1->DR = spi_data[tx_index];
tx_index++;
}
else
{
// Reset buffer index
tx_index = 0;
}
}
}
Firmware Variante 2
In dieser Variante wird versucht genau das 40kHz Signal des Balls zu dedektieren. Da werden die Pins des Mikrocontrollers nicht nur als digitaler Eingang konfiguriert, sondern diesen wird auch eine eine Interrupt Routine zugewiesen. Dabei handelt es sich um Code, der umgehend ausgeführt wird, wenn sich der Zusand an einem Pin ändert. Hier das Ereignis rising edge und falling edge, also die ansteigende und fallende Kante im PWM-Signal des Balls.
Um nun herauszufinden, ob es sich um das 40kHz Signal handelt, wird die Zeit zwischen einer rising edge und einer falling edge gemessen. Da es leichte Abweichungen der Pulsbreite geben kann, wird in diesem Code auch eine Tolerenz der Pulslänge bzw. der Frequenz berücksichtigt.
Weiters ist in diesem Code implementiert, dass das Signal nur dann als "gesehen" ausgewertet wird, wenn dieses für eine bestimmte Zeitspanne von einem Sensor ausgewertet wird.
Beim Übertragen des Werts über SPI zum Mainboard des Roboters wird nur die Nummer des Sensors mit der höchsten Zahl (1, ..., 16) herangezogen und diese übertragen. Dies wäre dahingehend zu erweitern, dass bereits in der Firmware eine Logik eingebaut wird, die darüber entscheidet, welcher Wert für die Richtung eines Balls übertragen wird, wenn mehrere Sensoren den Ball "sehen".
// *************************************************************************************************
// *** KeplerBRAIN V4 Sensor STAMP SPI Client IR Ballsensor V 15.01.2024 PWM Interrupt Handler ***
// *************************************************************************************************
// SPI Data
volatile uint8_t spi_data[9] = {250,1,2,3,4,5,6,7,8};
volatile uint8_t tx_index = 0;
// GPIO pins
uint8_t sensorPins[16] = {PA8, PB7, PB8, PB6, PB14, PC0, PC2, PB15, PB13, PB1, PC5, PB12, PA1, PA0, PC13, PB9};
// Arrays für das pulse timing tracking
volatile uint32_t lastRisingEdge[16] = {0};
volatile uint32_t pulsePeriod[16] = {0};
// Array zum Speichern der detection results
volatile uint8_t arr_sensor[16] = {0};
// Array zum Speichern der letzen validen signal detection
volatile uint32_t lastSignalTime[16] = {0};
// Frequenz des Signals 40 kHz frequency and tolerance (±5%)
#define FREQ_40KHZ 40000
#define TOLERANCE 2000
// system clock frequency des STM32F411RE
#define TIMER_FREQUENCY 34000000
// 1 second timeout in microseconds
#define SIGNAL_TIMEOUT 100000
// Interrupt handler für jeden Pin
void handleInterrupt(int pinIndex)
{
// aktuelle Zeit in microseconds
uint32_t now = micros();
if (digitalRead(sensorPins[pinIndex]) == HIGH)
{
// rising edge detektiert
if (lastRisingEdge[pinIndex] != 0)
{
// Berechnung der pulse period
pulsePeriod[pinIndex] = now - lastRisingEdge[pinIndex];
// Berechnung der Frequenz und ÜBerprüfung auf 40 kHz
uint32_t frequency = TIMER_FREQUENCY / pulsePeriod[pinIndex];
//Serial.print(pinIndex); Serial.print(" "); Serial.println(frequency);
if ((frequency >= (FREQ_40KHZ - TOLERANCE)) && (frequency <= (FREQ_40KHZ + TOLERANCE)))
{
// Signal dedektiert
arr_sensor[pinIndex] = 1;
// update last signal detection time
lastSignalTime[pinIndex] = now;
}
}
// update last rising edge time
lastRisingEdge[pinIndex] = now;
}
}
// Deklatation der interrupt handler Funktionen
void handleInterrupt0() { handleInterrupt(0); }
void handleInterrupt1() { handleInterrupt(1); }
void handleInterrupt2() { handleInterrupt(2); }
void handleInterrupt3() { handleInterrupt(3); }
void handleInterrupt4() { handleInterrupt(4); }
void handleInterrupt5() { handleInterrupt(5); }
void handleInterrupt6() { handleInterrupt(6); }
void handleInterrupt7() { handleInterrupt(7); }
void handleInterrupt8() { handleInterrupt(8); }
void handleInterrupt9() { handleInterrupt(9); }
void handleInterrupt10() { handleInterrupt(10); }
void handleInterrupt11() { handleInterrupt(11); }
void handleInterrupt12() { handleInterrupt(12); }
void handleInterrupt13() { handleInterrupt(13); }
void handleInterrupt14() { handleInterrupt(14); }
void handleInterrupt15() { handleInterrupt(15); }
// Array der interrupt handler Funktionen
void (*interruptHandlers[16])() = {
handleInterrupt0, handleInterrupt1, handleInterrupt2, handleInterrupt3,
handleInterrupt4, handleInterrupt5, handleInterrupt6, handleInterrupt7,
handleInterrupt8, handleInterrupt9, handleInterrupt10, handleInterrupt11,
handleInterrupt12, handleInterrupt13, handleInterrupt14, handleInterrupt15
};
void setup()
{
// Initialize SPI1 as Slave with interrupt
SPI1_Init();
// Enable the SPI1 interrupt in NVIC
NVIC_EnableIRQ(SPI1_IRQn);
// Konfiguration der GPIO pins als digitale Eingänge mit Interrupt
for (int i = 0; i < 16; i++)
{
pinMode(sensorPins[i], INPUT); // Configure pins as inputs
// Interrupts an jeden Pin hängen mit CHANGE-Event bei rising and falling edge
attachInterrupt(digitalPinToInterrupt(sensorPins[i]), interruptHandlers[i], CHANGE);
}
// User Code
Serial.begin(115200);
}
void loop()
{
// aktuelle Zeit in microseconds
uint32_t now = micros();
// Mindestlänge des anliegenden Signals an einem Sensor
for (int i = 0; i < 16; i++)
{
// Überprüfen, ob das Signal im Zeitraum SIGNAL_TIMEOUT dedektiert wurde
if (arr_sensor[i] == 1 && (now - lastSignalTime[i] > SIGNAL_TIMEOUT))
{
// wenn kein Signal in der angegebenen timeout period dedektiert, Sensor auf 0
arr_sensor[i] = 0;
}
}
// Ausgabe Sensorwerte und Übertragung
for (int i = 0; i < 16; i++)
{
if (arr_sensor[i] == 1)
{
//Serial.print("1 ");
// Nummer des Sensors mit der höchsten Zahl der ein
// Signal des Balls "sieht" wird übertragen
// !!! Dies ist zu verbessern und hier ist eine Logik
// zu entwickeln, was übertragen wird, wenn mehr als ein
// Sensor das Signal dedektiert
spi_data[1] = i+1;
}
else
{
//Serial.print("0 ");
}
}
//Serial.println("");
delay(10);
}
// Initialize SPI1 in slave mode with interrupt
void SPI1_Init()
{
// Enable clocks for GPIOA and SPI1
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// Configure PA4 (NSS), PA5 (SCK), PA6 (MISO), PA7 (MOSI) as alternate function
GPIOA->MODER &= ~(GPIO_MODER_MODER4 | GPIO_MODER_MODER5 | GPIO_MODER_MODER6 | GPIO_MODER_MODER7);
GPIOA->MODER |= (GPIO_MODER_MODER4_1 | GPIO_MODER_MODER5_1 | GPIO_MODER_MODER6_1 | GPIO_MODER_MODER7_1);
GPIOA->AFR[0] |= (5 << (4 * 4)) | (5 << (5 * 4)) | (5 << (6 * 4)) | (5 << (7 * 4)); // Set AF5 for SPI1
// Configure SPI1 as a slave
SPI1->CR1 = 0; // Reset CR1
SPI1->CR1 &= ~SPI_CR1_MSTR; // Set as slave
SPI1->CR1 &= ~SPI_CR1_SSM; // Disable software slave management
SPI1->CR1 |= SPI_CR1_SPE; // Enable SPI
SPI1->CR2 |= SPI_CR2_RXNEIE; // Enable RXNE interrupt
SPI1->CR2 |= SPI_CR2_TXEIE; // Enable TXE interrupt
}
extern "C" void SPI1_IRQHandler(void)
{
// Check if RXNE (Receive Not Empty) flag is set and handle RX first
if (SPI1->SR & SPI_SR_RXNE)
{
uint8_t rx_value = SPI1->DR;
}
// Check if TXE (Transmit Empty) flag is set, but only if not busy
if (SPI1->SR & SPI_SR_TXE)
{
// Send data from tx_buffer if in "send mode"
if (tx_index < 9)
{
// Write data to SPI
SPI1->DR = spi_data[tx_index];
tx_index++;
}
else
{
// Reset buffer index
tx_index = 0;
}
}
}
Programmbeispiel - Einlesen von Werten des Soccer Bodensensors
Der Bodensensor wird an die SPI1 Schnittstelle eines KeplerBRAIN V4 Mainboards angeschlossen. Am Display sollen laufend die aktuellen, gemessenen Werte der 8 Reflexionssensoren angezeigt werden.
Dazu muss eine SPI Datenübertragung initiiert werden. Dies geschieht dadurch, dass die CS-Leitung (Chip Select) der SPI-Verbindung auf LOW gesetzt wird. Mit der Funktion spi.transfer(0xFF) wird ein Byte aus dem Datenstream ausgelesen. Kommt in diesem die Zahl 250 vor, so ist der erste Wert des Datenpakets aus 9 Werten identifiziert und die nächsten 8 Werte werden in den Variablen value_1, ..., value_8 abgelegt. Am Ende der SPI Kommunikation muss die CS-Leitung wieder auf HIGH gesetzt werden.
#include "KeplerBRAIN_V4.h"
uint8_t value_1;
void setup()
{
KEPLERBRAIN_INIT();
WRITE_LCD_TEXT(1,1," ");
WRITE_LCD_TEXT(1,2," ");
}
void loop()
{
// read 1 Byte from Soccer IR Sensor
digitalWrite(SPI1, LOW);
if(spi.transfer(0XFF) == 250)
{
value_1 = spi.transfer(0XFF);
}
digitalWrite(SPI1, HIGH);
WRITE_LCD_TEXT(1, 1, String(value_1)+" "
);
}
Erklärungen zu diesem Programmbeispiel
Zeile 3: uint8_t value_1;
Zunächst wird eine Variable vom Typ uint8_t definiert, in welcher die vom Sensorboard abgefragten Zahl abgelegt wird.
Zeile 17 - 20: // read 1 Byte from Soccer IR Sensor BEGIN - END
In diesem Code-Abschnitt sind grundsätzlich keine Änderungen vorzunehmen. Laufend werden über die SPI-Schnittstelle Zahlen von der OpenMV Cam abgefragt. Entspricht in diesem Daten-Stream eine Zahl dem Wert 250, so wird diese als erste Zahl der Neunergruppe identifiziert und alle weiteren werden in den Variablen value1, value2, ...abgelegt.
Zeile 24: WRITE_LCD_TEXT(1, 1, String(value_1)+" ");
Mit dieser Code-Zeile wird die empfangene Zahl am Display angezeigt. Die Leerzeichen dahinter bewirken, das etwaige Ziffern der vorigen Ausgabe gelöscht werden.