Added Coderacer MKII Arduino files
This commit is contained in:
parent
0281b9518d
commit
9fce3463a3
29 changed files with 2906 additions and 60 deletions
BIN
3DPrint/CodeRacerMKII/5xAABatterieHolder.stl
Normal file
BIN
3DPrint/CodeRacerMKII/5xAABatterieHolder.stl
Normal file
Binary file not shown.
BIN
3DPrint/CodeRacerMKII/5xAABatterieHolder.zip
Normal file
BIN
3DPrint/CodeRacerMKII/5xAABatterieHolder.zip
Normal file
Binary file not shown.
BIN
3DPrint/CodeRacerMKII/HCSR04mountholder.stl
Normal file
BIN
3DPrint/CodeRacerMKII/HCSR04mountholder.stl
Normal file
Binary file not shown.
BIN
3DPrint/CodeRacerMKII/HCSR04mountholder.zip
Normal file
BIN
3DPrint/CodeRacerMKII/HCSR04mountholder.zip
Normal file
Binary file not shown.
|
@ -0,0 +1,736 @@
|
||||||
|
// Übungen mit Lösungen
|
||||||
|
// Stand 20.11.2019
|
||||||
|
// Ergänze den Code für die Übungen an den Stellen wo die Übung formuliert ist, bzw. wo der Hinweis steht das der Code hier einesetzt werden soll.
|
||||||
|
// !!! Denke daran dir stets eine Sicherungskopie der letzten lauffähigen Programmversion abzulegen, also auch hiervon, bevor du weitermachst!!!
|
||||||
|
// Ich schlage vor jeweils das Datum in umgekehrter Reihenfolge anzuhängen. Für den 2. November 2019 also 191102.
|
||||||
|
// Dann werden die Programmversionen im File Exporer sortiert angezeigt. Wenn nötig kannst du zusätzlich die Uhrzeit anhängen.
|
||||||
|
//
|
||||||
|
// Einige Übungen sind einfach mit Copy und Paste zu erledigen. Aber auch das will gelent sein. Oft geht dabei was schief und es fehlt z.B.
|
||||||
|
// die schließende Klammer für einen Anweisungsblock. Wenn dir so etwas passiert oder sich aus anderen Gründen dein Code nicht mehr übersetzen lässt
|
||||||
|
// und du den Fehler nicht sofort findest Kommentier den betreffenden Teil, oder auch z.b. den ganzen Inhalt der switch Anweisung, mit /* und */ aus,
|
||||||
|
// so dass es sich wieder übersetzen lässt. Kommentier dann Bloch für Block oder auch zeile für zeile wieder ein indem du /* oder */ an eine andere Position setzt.
|
||||||
|
//
|
||||||
|
// Bedenke das zum Programmieren alle Microschalter in der Stellung 0 oder off stehen müssen. Wenn das nicht der Fall ist kann es sein das sich der ESP32 nicht programmieren lässt.
|
||||||
|
// Um dir die Arbeit zu erleichten kannst du den case 0 auskommentieren und den case in dem du die Übung bearbeitest vorübergehend zu case 0 machen. Das erspart das einstellen der Zahl.
|
||||||
|
|
||||||
|
// Schalterstellung Aktion
|
||||||
|
// 0000 Lauflicht
|
||||||
|
// 0001 measure battery voltage and show as bar
|
||||||
|
// 0010 move Servo
|
||||||
|
// 0011 measure distance and show as binary number
|
||||||
|
// 0100 measure distance and show as bar
|
||||||
|
// 0101 Motoren vorwärts
|
||||||
|
// 0110 Motoren rückwärts
|
||||||
|
// 0111 Motor Links vorwärts/rückwärts
|
||||||
|
// 1000 Motor Rechts vorwärts/rückwärts
|
||||||
|
// 1001 Fahren, 2 Sekunden nach loslassen der Taste_Links fährt der CodeRacer 5 Sekunden vorwärts
|
||||||
|
// 1010 Variable Geschwindigkeit für beide Motoren und anzeigen des Zählers mit den LEDs
|
||||||
|
// 1011 x
|
||||||
|
// 1100 x
|
||||||
|
// 1101 x
|
||||||
|
// 1110 x
|
||||||
|
// 1111 x
|
||||||
|
|
||||||
|
// Übung 0, case 0, CProgrammiere die Funktion Lauflicht. Den Rumpf des Unterprogramms findest du im Abschnitt Subroutines.
|
||||||
|
// Übung 1, case 4, case 3 als Balken Anzeige für die Werteintervalle bis 4, 8, 12, 16, 20, 24
|
||||||
|
// Übung 2, case 5, Ergänzen für den rechten Motor
|
||||||
|
// Übung 3, case 6, case 5 ändern für Motoren rückwärts
|
||||||
|
// Übung 4, case 7, linker Motor vorwärts wenn Taste_Links gedrückt und rückwärts wenn Taste_Rechts gedrückt
|
||||||
|
// Übung 5, case 8, rechter Motor vorwärts wenn Taste_Links gedrückt und rückwärts wenn Taste_Rechts gedrückt
|
||||||
|
// Übung 6, case 9, 2 Sekunden nach loslassen der Taste_Links soll der CodeRacer 5 Sekunden vorwärts fahren und dann wieder halten
|
||||||
|
|
||||||
|
//Schreibe Funktionen MotorLinks(byte Richtung, byte Speed) und MotorRechts(byte Richtung, byte Speed)
|
||||||
|
//Ersetze die Befehle um die Motoren anzusteuern im gesamten Programm durch diese Funktionen.
|
||||||
|
|
||||||
|
//CodeRacer um ein Rad drehen
|
||||||
|
//Ein Rad steht still. Das andere Rad läuft vorwärts. Wie lange muss man den Motor eingeschaltet lassen , bzw. wie viele Impulse abwarten, bis das Fahrzeug wieder an der ursprünglichen Position steht?
|
||||||
|
|
||||||
|
//CodeRacer auf der Stelle drehen
|
||||||
|
//Beide Räder drehen sich in entgegengesetzte Richtung. Das Fahrzeug dreht sich auf der Stelle. Wie lange muss man den Motor eingeschaltet lassen , bzw. wie viele Impulse abwarten, bis das Fahrzeug wieder an der ursprünglichen Position steht?
|
||||||
|
|
||||||
|
//Quadrat abfahren
|
||||||
|
//Der CodeRacer soll 50cm geradeaus fahren, dann um 90\[Degree] drehen, wieder 50cm geradeaus fahren und so weiter bis es wieder auf der Ausgangsposition steht.
|
||||||
|
|
||||||
|
// Arduino Code für CodeRacer MK II des MakerLab Murnau
|
||||||
|
// Testen der Hardware des CodeRacers
|
||||||
|
//------------------------------------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
#include <ESP32Servo.h>
|
||||||
|
#include "esp32-hal-ledc.h"
|
||||||
|
|
||||||
|
//-- Pin Zuordnung -------------------------------------------------------------------------------------------------------
|
||||||
|
#define LED_1 32 // Pins an dem die LEDs angeschlossen sind
|
||||||
|
#define LED_2 33
|
||||||
|
#define LED_3 25
|
||||||
|
#define LED_4 27
|
||||||
|
#define LED_5 14
|
||||||
|
#define LED_6 12
|
||||||
|
|
||||||
|
#define Taster_Links 13 // Pins an denen die Schalter angeschlossen sind
|
||||||
|
#define Taster_Rechts 16
|
||||||
|
#define Schalter_1 4
|
||||||
|
#define Schalter_2 0
|
||||||
|
#define Schalter_3 2
|
||||||
|
#define Schalter_4 15
|
||||||
|
|
||||||
|
#define SERVO_Pin 18 // Pin an dem der Servo angeschlossen ist
|
||||||
|
#define Trigger 21 // Pin an denen der Ultraschallabstandssensor angeschlossen ist
|
||||||
|
#define Echo 17
|
||||||
|
|
||||||
|
#define Motor_Links_Ein 23 // Pins an denen die Motore angeschlossen sind
|
||||||
|
#define Motor_Links_VorwaertsRueckwaerts 22
|
||||||
|
#define Motor_Rechts_Ein 5
|
||||||
|
#define Motor_Rechts_VorwaertsRueckwaerts 19
|
||||||
|
#define Geschwindigkeit_Links 34 // Pins an denen die Geschwindigkeitssensoren angeschlossen sind
|
||||||
|
#define Geschwindigkeit_Rechts 35
|
||||||
|
|
||||||
|
#define Abstand_Hinten_Links x // Pins an denen die Abstandssensoren hinten angeschlossen sind
|
||||||
|
#define Abstand_Hinten_Rechts x
|
||||||
|
#define Batteriespannung 26 // Pin an dem der Spannungsteiler für die Batterie Spannung angeschlossen ist
|
||||||
|
|
||||||
|
#define PWM_Links 5 // Zuordnung der PWM Kanäle
|
||||||
|
#define PWM_Rechts 6
|
||||||
|
|
||||||
|
//-- Defines --------------------------------------------------------------------------------------------------------------------
|
||||||
|
#define LEDon 100 // 100ms eingeschaltet
|
||||||
|
#define LEDoff 50 // 50ms ausgeschaltet
|
||||||
|
|
||||||
|
#define Vorwaerts HIGH
|
||||||
|
#define Rueckwaerts LOW
|
||||||
|
|
||||||
|
//-- Globale Variables ----------------------------------------------------------------------------------------------------------
|
||||||
|
int i, Number, Schalter;
|
||||||
|
volatile unsigned int StL, StR;
|
||||||
|
volatile unsigned int StepsL, StepsR;
|
||||||
|
volatile unsigned long timeL, timeR, timeLPrev, timeRPrev;
|
||||||
|
volatile unsigned long countL, countR;
|
||||||
|
volatile unsigned int diffL, diffR;
|
||||||
|
volatile boolean isrRFlag, isrLFlag;
|
||||||
|
|
||||||
|
Servo servo;
|
||||||
|
|
||||||
|
//-- Subroutines ----------------------------------------------------------------------------------------------------------------
|
||||||
|
long measureDistance()
|
||||||
|
{ long dist, duration;
|
||||||
|
pinMode(Echo, INPUT);
|
||||||
|
digitalWrite(Trigger, LOW);
|
||||||
|
delayMicroseconds(2);
|
||||||
|
digitalWrite(Trigger, HIGH);
|
||||||
|
delayMicroseconds(10);
|
||||||
|
digitalWrite(Trigger, LOW);
|
||||||
|
duration=pulseIn(Echo,HIGH);
|
||||||
|
dist=duration/2*0.0344;
|
||||||
|
return(dist);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Lauflicht()
|
||||||
|
{ // Ergänze hier den Code für Übung 0
|
||||||
|
digitalWrite(LED_1,HIGH);
|
||||||
|
delay(LEDon);
|
||||||
|
digitalWrite(LED_1,LOW);
|
||||||
|
delay(LEDoff);
|
||||||
|
digitalWrite(LED_2,HIGH);
|
||||||
|
delay(LEDon);
|
||||||
|
digitalWrite(LED_2,LOW);
|
||||||
|
delay(LEDoff);
|
||||||
|
digitalWrite(LED_3,HIGH);
|
||||||
|
delay(LEDon);
|
||||||
|
digitalWrite(LED_3,LOW);
|
||||||
|
delay(LEDoff);
|
||||||
|
digitalWrite(LED_4,HIGH);
|
||||||
|
delay(LEDon);
|
||||||
|
digitalWrite(LED_4,LOW);
|
||||||
|
delay(LEDoff);
|
||||||
|
digitalWrite(LED_5,HIGH);
|
||||||
|
delay(LEDon);
|
||||||
|
digitalWrite(LED_5,LOW);
|
||||||
|
delay(LEDoff);
|
||||||
|
digitalWrite(LED_6,HIGH);
|
||||||
|
delay(LEDon);
|
||||||
|
digitalWrite(LED_6,LOW);
|
||||||
|
delay(LEDoff);
|
||||||
|
}
|
||||||
|
|
||||||
|
void LEDsoff()
|
||||||
|
{ digitalWrite(LED_1,LOW);
|
||||||
|
digitalWrite(LED_2,LOW);
|
||||||
|
digitalWrite(LED_3,LOW);
|
||||||
|
digitalWrite(LED_4,LOW);
|
||||||
|
digitalWrite(LED_5,LOW);
|
||||||
|
digitalWrite(LED_6,LOW);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ShowDistance(int distance)
|
||||||
|
{ digitalWrite(LED_1, bitRead(distance,6));
|
||||||
|
digitalWrite(LED_2, bitRead(distance,5));
|
||||||
|
digitalWrite(LED_3, bitRead(distance,4));
|
||||||
|
digitalWrite(LED_4, bitRead(distance,3));
|
||||||
|
digitalWrite(LED_5, bitRead(distance,2));
|
||||||
|
digitalWrite(LED_6, bitRead(distance,1));
|
||||||
|
};
|
||||||
|
|
||||||
|
void MotorLinks(byte Richtung, byte Speed)
|
||||||
|
{ digitalWrite(Motor_Links_VorwaertsRueckwaerts, Richtung);
|
||||||
|
ledcWrite(PWM_Links, Speed);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorRechts(byte Richtung, byte Speed)
|
||||||
|
{ digitalWrite(Motor_Rechts_VorwaertsRueckwaerts, Richtung);
|
||||||
|
ledcWrite(PWM_Rechts, Speed);
|
||||||
|
}
|
||||||
|
|
||||||
|
void DreheLinks(int steps)
|
||||||
|
{ int StartR;
|
||||||
|
StartR = countR;
|
||||||
|
digitalWrite(Motor_Links_VorwaertsRueckwaerts, HIGH);
|
||||||
|
digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,HIGH);
|
||||||
|
ledcWrite(PWM_Links, 0);
|
||||||
|
ledcWrite(PWM_Rechts, 80);
|
||||||
|
while ( (countR-StartR)<steps ) {};
|
||||||
|
ledcWrite(PWM_Links, 0);
|
||||||
|
ledcWrite(PWM_Rechts, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void DreheRechts(int steps)
|
||||||
|
{ int StartL;
|
||||||
|
StartL = countL;
|
||||||
|
digitalWrite(Motor_Links_VorwaertsRueckwaerts, HIGH);
|
||||||
|
digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,HIGH);
|
||||||
|
ledcWrite(PWM_Links, 85);
|
||||||
|
ledcWrite(PWM_Rechts, 0);
|
||||||
|
while ( (countL-StartL)<steps ) {};
|
||||||
|
ledcWrite(PWM_Links, 0);
|
||||||
|
ledcWrite(PWM_Rechts, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void IRAM_ATTR detectStepL()
|
||||||
|
{ timeL = micros();
|
||||||
|
diffL = timeL - timeLPrev;
|
||||||
|
timeLPrev = timeL;
|
||||||
|
countL++;
|
||||||
|
isrLFlag = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void IRAM_ATTR detectStepR()
|
||||||
|
{ timeR = micros();
|
||||||
|
diffR = timeR - timeRPrev;
|
||||||
|
timeRPrev = timeR;
|
||||||
|
countR++;
|
||||||
|
isrRFlag = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
//-- Setup ----------------------------------------------------------------------------------------------------------------
|
||||||
|
void setup()
|
||||||
|
{ Serial.begin(115200); // Serielle Schnittstelle aktivieren, Erstellungsdatum senden
|
||||||
|
Serial.println("Build "+String(__DATE__)+" "+String(__TIME__)+"\n");
|
||||||
|
|
||||||
|
pinMode(LED_1, OUTPUT); // LED Pins als Ausgang setzen und LEDs ausschalten
|
||||||
|
digitalWrite(LED_1,LOW);
|
||||||
|
pinMode(LED_2, OUTPUT);
|
||||||
|
digitalWrite(LED_2,LOW);
|
||||||
|
pinMode(LED_3, OUTPUT);
|
||||||
|
digitalWrite(LED_3,LOW);
|
||||||
|
pinMode(LED_4, OUTPUT);
|
||||||
|
digitalWrite(LED_4,LOW);
|
||||||
|
pinMode(LED_5, OUTPUT);
|
||||||
|
digitalWrite(LED_5,LOW);
|
||||||
|
pinMode(LED_6, OUTPUT);
|
||||||
|
digitalWrite(LED_6,LOW);
|
||||||
|
|
||||||
|
pinMode(Taster_Links, INPUT_PULLUP); // Taster Pins als Eingang setzen
|
||||||
|
pinMode(Taster_Rechts, INPUT_PULLUP);
|
||||||
|
pinMode(Schalter_1, INPUT_PULLUP); // Schalter Pins als Eingang setzen
|
||||||
|
pinMode(Schalter_2, INPUT_PULLUP);
|
||||||
|
pinMode(Schalter_3, INPUT_PULLUP);
|
||||||
|
pinMode(Schalter_4, INPUT_PULLUP);
|
||||||
|
|
||||||
|
servo.attach(SERVO_Pin); // Pin für Servo setzen
|
||||||
|
pinMode(Trigger, OUTPUT); // Pins für Ultraschallsensor setzen
|
||||||
|
digitalWrite(Trigger,LOW);
|
||||||
|
pinMode(Echo, INPUT);
|
||||||
|
|
||||||
|
pinMode(Motor_Links_Ein, OUTPUT); digitalWrite(Motor_Links_Ein,LOW); // Pins für Motore setzen
|
||||||
|
pinMode(Motor_Links_VorwaertsRueckwaerts, OUTPUT); digitalWrite(Motor_Links_VorwaertsRueckwaerts,LOW);
|
||||||
|
pinMode(Motor_Rechts_Ein, OUTPUT); digitalWrite(Motor_Rechts_Ein,LOW);
|
||||||
|
pinMode(Motor_Rechts_VorwaertsRueckwaerts, OUTPUT); digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,LOW);
|
||||||
|
ledcSetup(PWM_Links, 100, 8);
|
||||||
|
ledcAttachPin(Motor_Links_Ein, PWM_Links);
|
||||||
|
ledcWrite(PWM_Links, 0);
|
||||||
|
ledcSetup(PWM_Rechts, 100, 8);
|
||||||
|
ledcAttachPin(Motor_Rechts_Ein, PWM_Rechts);
|
||||||
|
ledcWrite(PWM_Rechts, 0);
|
||||||
|
|
||||||
|
// ledcSetup(7, 50, 8);
|
||||||
|
// ledcAttachPin(LED_6, 7);
|
||||||
|
// ledcWrite(7, 127);
|
||||||
|
|
||||||
|
pinMode(Geschwindigkeit_Links , INPUT); // Pins für Geschwindigkeitssensoren setzen und mit Interrupt Service Routine verknüpfen
|
||||||
|
pinMode(Geschwindigkeit_Rechts, INPUT);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(Geschwindigkeit_Links ), detectStepL, RISING);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(Geschwindigkeit_Rechts), detectStepR, RISING);
|
||||||
|
}
|
||||||
|
|
||||||
|
//-- Main ----------------------------------------------------------------------------------------------------------------
|
||||||
|
void loop(void)
|
||||||
|
{ byte TL, TR, S1, S2, S3, S4, b, brightness;
|
||||||
|
int speed, speedSet, speedSetL, speedSetR, speedL, speedR, g, minspeed, maxspeed, distance;
|
||||||
|
int DistanceL, DistanceR;
|
||||||
|
unsigned int StartL, StartR;
|
||||||
|
|
||||||
|
while (true)
|
||||||
|
{ servo.write(90);
|
||||||
|
|
||||||
|
TL = !digitalRead(Taster_Links );
|
||||||
|
TR = !digitalRead(Taster_Rechts);
|
||||||
|
S1 = !digitalRead(Schalter_1 );
|
||||||
|
S2 = !digitalRead(Schalter_2 );
|
||||||
|
S3 = !digitalRead(Schalter_3 );
|
||||||
|
S4 = !digitalRead(Schalter_4 );
|
||||||
|
|
||||||
|
Schalter = (S1<<3) | (S2<<2) | (S3<<1) | S4;
|
||||||
|
//Serial.println(Schalter);
|
||||||
|
|
||||||
|
switch(Schalter)
|
||||||
|
{ case 0: // Hindernissparcour 0
|
||||||
|
{ while( (distance=measureDistance()) > 15 ) // 7 ~ 10cm
|
||||||
|
{ ShowDistance(distance);
|
||||||
|
MotorLinks(Vorwaerts, 100);
|
||||||
|
MotorRechts(Vorwaerts, 100);
|
||||||
|
};
|
||||||
|
MotorLinks(Vorwaerts, 0);
|
||||||
|
MotorRechts(Vorwaerts, 0);
|
||||||
|
ShowDistance(distance);
|
||||||
|
servo.write(180);
|
||||||
|
delay(400);
|
||||||
|
DistanceL=measureDistance();
|
||||||
|
servo.write(0);
|
||||||
|
delay(400);
|
||||||
|
DistanceR=measureDistance();
|
||||||
|
servo.write(90);
|
||||||
|
delay(400);
|
||||||
|
if( DistanceL<DistanceR )
|
||||||
|
{ // drehe nach rechts
|
||||||
|
DreheRechts(16);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ // drehe nach linhs
|
||||||
|
DreheLinks(16);
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
/*case 15: //----------------------------------------------- Lauflicht
|
||||||
|
}
|
||||||
|
{ delay(100);
|
||||||
|
// Übung 0, Programmiere die Funktion Lauflicht. Den Rumpf des Unterprogramms findest du im Abschnitt Subroutines.
|
||||||
|
Lauflicht();
|
||||||
|
break;
|
||||||
|
};*/
|
||||||
|
/* case 1: //----------------------------------------------- measure battery voltage and show as bar
|
||||||
|
{ //delay(1000);
|
||||||
|
//LEDsoff();
|
||||||
|
ledcSetup(7, 50, 8);
|
||||||
|
ledcAttachPin(LED_6, 7);
|
||||||
|
for( brightness = 255; brightness > 0; brightness = brightness - 1)
|
||||||
|
{ delay(10);
|
||||||
|
ledcWrite(7, brightness);
|
||||||
|
};
|
||||||
|
for( brightness = 0; brightness < 254; brightness = brightness + 1)
|
||||||
|
{ delay(10);
|
||||||
|
ledcWrite(7, brightness);
|
||||||
|
};
|
||||||
|
ledcDetachPin(LED_6);
|
||||||
|
pinMode(LED_6, OUTPUT);
|
||||||
|
digitalWrite(LED_6,LOW);
|
||||||
|
break;
|
||||||
|
};*/
|
||||||
|
|
||||||
|
case 2: //----------------------------------------------- move Servo
|
||||||
|
{ LEDsoff(); delay(100);
|
||||||
|
if( TL && TR )
|
||||||
|
{ servo.write(90);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else if( TL )
|
||||||
|
{ servo.write(180);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else if( TR )
|
||||||
|
{ servo.write(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ break;
|
||||||
|
};
|
||||||
|
};
|
||||||
|
case 3: //----------------------------------------------- measure distance and show as binary number
|
||||||
|
{ delay(200);
|
||||||
|
distance = measureDistance();
|
||||||
|
Serial.println(distance);
|
||||||
|
digitalWrite(LED_1, bitRead(distance,6));
|
||||||
|
digitalWrite(LED_2, bitRead(distance,5));
|
||||||
|
digitalWrite(LED_3, bitRead(distance,4));
|
||||||
|
digitalWrite(LED_4, bitRead(distance,3));
|
||||||
|
digitalWrite(LED_5, bitRead(distance,2));
|
||||||
|
digitalWrite(LED_6, bitRead(distance,1));
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 4: //----------------------------------------------- measure distance and show as bar
|
||||||
|
{ delay(200);
|
||||||
|
distance = measureDistance();
|
||||||
|
Serial.println(distance);
|
||||||
|
// Übung 1, case 3 als Balken Anzeige für die Werteintervalle bis 4, 8, 12, 16, 20, 24
|
||||||
|
digitalWrite(LED_6, distance > 4 );
|
||||||
|
digitalWrite(LED_5, distance > 8 );
|
||||||
|
digitalWrite(LED_4, distance > 12 );
|
||||||
|
digitalWrite(LED_3, distance > 16 );
|
||||||
|
digitalWrite(LED_2, distance > 20 );
|
||||||
|
digitalWrite(LED_1, distance > 24 );
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 5: //----------------------------------------------- Motoren vorwärts
|
||||||
|
{ LEDsoff(); delay(100);
|
||||||
|
if( TL )
|
||||||
|
{ digitalWrite(Motor_Links_VorwaertsRueckwaerts, HIGH);
|
||||||
|
ledcWrite(PWM_Links, 255);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Links, 0);
|
||||||
|
};
|
||||||
|
// Übung 2, Ergänzen für den rechten Motor
|
||||||
|
if( TR )
|
||||||
|
{ digitalWrite(Motor_Rechts_VorwaertsRueckwaerts, HIGH);
|
||||||
|
ledcWrite(PWM_Rechts, 255);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Rechts, 0);
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 6: //----------------------------------------------- Motoren rückwärts
|
||||||
|
{ LEDsoff(); delay(100);
|
||||||
|
// Übung 3, case 5 ändern für Motoren rückwärts
|
||||||
|
if( TL )
|
||||||
|
{ digitalWrite(Motor_Links_VorwaertsRueckwaerts, LOW);
|
||||||
|
ledcWrite(PWM_Links, 255);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Links, 0);
|
||||||
|
};
|
||||||
|
|
||||||
|
if( TR )
|
||||||
|
{ digitalWrite(Motor_Rechts_VorwaertsRueckwaerts, LOW);
|
||||||
|
ledcWrite(PWM_Rechts, 255);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Rechts, 0);
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 7: //----------------------------------------------- Motor Links vorwärts/rückwärts
|
||||||
|
{ LEDsoff(); delay(100);
|
||||||
|
// Übung 4, linker Motor vorwärts wenn Taste_Links gedrückt und rückwärts wenn Taste_Rechts gedrückt
|
||||||
|
if( TL )
|
||||||
|
{ digitalWrite(Motor_Links_VorwaertsRueckwaerts,HIGH);
|
||||||
|
ledcWrite(PWM_Links, 255);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Links, 0);
|
||||||
|
};
|
||||||
|
if( TR )
|
||||||
|
{ digitalWrite(Motor_Links_VorwaertsRueckwaerts,LOW);
|
||||||
|
ledcWrite(PWM_Links, 255);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Links, 0);
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 8: //----------------------------------------------- Motor Rechts vorwärts/rückwärts
|
||||||
|
{ LEDsoff(); delay(100);
|
||||||
|
// Übung 5, rechter Motor vorwärts wenn Taste_Links gedrückt und rückwärts wenn Taste_Rechts gedrückt
|
||||||
|
if( TL )
|
||||||
|
{ digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,HIGH);
|
||||||
|
ledcWrite(PWM_Rechts, 255);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Rechts, 0);
|
||||||
|
};
|
||||||
|
if( TR )
|
||||||
|
{ digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,LOW);
|
||||||
|
ledcWrite(PWM_Rechts, 255);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ ledcWrite(PWM_Rechts, 0);
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 9: //----------------------------------------------- Fahren, 2 Sekunden nach loslassen der Taste_Links fährt der CodeRacer 5 Sekunden vorwärts
|
||||||
|
{ LEDsoff(); delay(100);
|
||||||
|
if( TL )
|
||||||
|
{ while(!digitalRead(Taster_Links )) {}; // wait until button is released
|
||||||
|
// Übung 6, 2 Sekunden nach loslassen der Taste_Links soll der CodeRacer 5 Sekunden vorwärts fahren und dann wieder halten
|
||||||
|
delay(2000);
|
||||||
|
digitalWrite(Motor_Links_VorwaertsRueckwaerts, HIGH);
|
||||||
|
digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,HIGH);
|
||||||
|
ledcWrite(PWM_Links, 100);
|
||||||
|
ledcWrite(PWM_Rechts, 100);
|
||||||
|
delay(3000);
|
||||||
|
ledcWrite(PWM_Links, 0);
|
||||||
|
ledcWrite(PWM_Rechts, 0);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 10: //----------------------------------------------- Variable Geschwindigkeit für beide Motoren und anzeigen des Zählers mit den LEDs
|
||||||
|
{ LEDsoff(); delay(100); // Start 2 Sekunden nach loslassen der Taste_Links
|
||||||
|
if( TL )
|
||||||
|
{ while(!digitalRead(Taster_Links )) {}; // wait until button is released
|
||||||
|
delay(2000);
|
||||||
|
digitalWrite(Motor_Links_VorwaertsRueckwaerts, HIGH);
|
||||||
|
digitalWrite(Motor_Rechts_VorwaertsRueckwaerts,HIGH);
|
||||||
|
for( speed = 80; speed <= 255; speed = speed + 4 )
|
||||||
|
{ delay(20);
|
||||||
|
ledcWrite(PWM_Links, speed);
|
||||||
|
ledcWrite(PWM_Rechts, speed);
|
||||||
|
Serial.println(speed);
|
||||||
|
digitalWrite(LED_1, bitRead(speed,8));
|
||||||
|
digitalWrite(LED_2, bitRead(speed,7));
|
||||||
|
digitalWrite(LED_3, bitRead(speed,6));
|
||||||
|
digitalWrite(LED_4, bitRead(speed,5));
|
||||||
|
digitalWrite(LED_5, bitRead(speed,4));
|
||||||
|
digitalWrite(LED_6, bitRead(speed,3));
|
||||||
|
};
|
||||||
|
delay(2000);
|
||||||
|
for( speed = 255; speed >= 80; speed = speed - 4 )
|
||||||
|
{ delay(20);
|
||||||
|
ledcWrite(PWM_Links, speed);
|
||||||
|
ledcWrite(PWM_Rechts, speed);
|
||||||
|
Serial.println(speed);
|
||||||
|
digitalWrite(LED_1, bitRead(speed,6));
|
||||||
|
digitalWrite(LED_2, bitRead(speed,5));
|
||||||
|
digitalWrite(LED_3, bitRead(speed,4));
|
||||||
|
digitalWrite(LED_4, bitRead(speed,3));
|
||||||
|
digitalWrite(LED_5, bitRead(speed,2));
|
||||||
|
digitalWrite(LED_6, bitRead(speed,1));
|
||||||
|
};
|
||||||
|
ledcWrite(PWM_Links, 0);
|
||||||
|
ledcWrite(PWM_Rechts, 0);
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
};
|
||||||
|
case 11: //----------------------------------------------- circle left and right
|
||||||
|
{ LEDsoff(); delay(100); // Start 2 Sekunden nach loslassen der linken oder rechten Taste
|
||||||
|
if( TL )
|
||||||
|
{ while(!digitalRead(Taster_Links )) {}; // wait until button is released
|
||||||
|
delay(2000);
|
||||||
|
DreheLinks(16); // 65 ganze Drehung
|
||||||
|
};
|
||||||
|
if( TR )
|
||||||
|
{ while(!digitalRead(Taster_Rechts )) {}; // wait until button is released
|
||||||
|
delay(2000);
|
||||||
|
DreheRechts(16); // 65 ganze Drehung
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
/*case 0: //----------------------------------------------- Fahre Qudrat
|
||||||
|
{ //delay(100);
|
||||||
|
if( TL )
|
||||||
|
{ while(!digitalRead(Taster_Links )) {}; // wait until button is released
|
||||||
|
delay(2000);
|
||||||
|
for( i = 0; i < 4; i = i + 1 )
|
||||||
|
{//1. Strecke
|
||||||
|
StartL = StL;
|
||||||
|
StartR = StR;
|
||||||
|
MotorLinks(Vorwaerts, 70);
|
||||||
|
MotorRechts(Vorwaerts, 80);
|
||||||
|
while ( (StL-StartL)<50 && (StR-StartR)<50 ) {};
|
||||||
|
//MotorLinks(Vorwaerts, 0);
|
||||||
|
//MotorRechts(Vorwaerts, 0);
|
||||||
|
//1. Kurve
|
||||||
|
StartL = StL;
|
||||||
|
StartR = StR;
|
||||||
|
MotorLinks(Vorwaerts, 70);
|
||||||
|
MotorRechts(Vorwaerts, 0);
|
||||||
|
while ( (StL-StartL)<17 ) {};
|
||||||
|
MotorLinks(Vorwaerts, 0);
|
||||||
|
MotorRechts(Vorwaerts, 0);
|
||||||
|
};
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};*/
|
||||||
|
case 1: //----------------------------------------------- Geregelte Geradeausfahrt
|
||||||
|
{ if( TL ) // CodeRacer starten
|
||||||
|
{ delay(1000);
|
||||||
|
MotorLinks(Vorwaerts, 80);
|
||||||
|
MotorRechts(Vorwaerts, 80);
|
||||||
|
timeLPrev = micros();
|
||||||
|
timeRPrev = micros();
|
||||||
|
countL = 0;
|
||||||
|
countR = 0;
|
||||||
|
speedSet = 30000; speedSetL = 20000; speedSetR = 20000;
|
||||||
|
};
|
||||||
|
if( TR ) // CodeRacer stoppen
|
||||||
|
{ MotorLinks(Vorwaerts, 0);
|
||||||
|
MotorRechts(Vorwaerts, 0);
|
||||||
|
speedSet = 0;
|
||||||
|
};
|
||||||
|
if(diffL > 25000)
|
||||||
|
{ g = 2; minspeed=60; maxspeed=150;
|
||||||
|
digitalWrite(LED_3,HIGH);
|
||||||
|
digitalWrite(LED_4,LOW);
|
||||||
|
digitalWrite(LED_5,LOW);
|
||||||
|
if( (isrLFlag == true) || (isrRFlag == true) )
|
||||||
|
{ if( countL > countR )
|
||||||
|
{ speedL=speedL-g;
|
||||||
|
speedR=speedR+g;
|
||||||
|
};
|
||||||
|
if( countR > countL )
|
||||||
|
{ speedL=speedL+g;
|
||||||
|
speedR=speedR-g;
|
||||||
|
};
|
||||||
|
speedL++;
|
||||||
|
speedR++;
|
||||||
|
//Serial.print("links : "); Serial.print(countL); Serial.print(" : "); Serial.print(diffL); Serial.print(" : "); Serial.println(speedL);
|
||||||
|
//Serial.print("rechts: "); Serial.print(countR); Serial.print(" : "); Serial.print(diffR); Serial.print(" : "); Serial.println(speedR);
|
||||||
|
if( speedL > maxspeed ) {speedL = maxspeed;};
|
||||||
|
if( speedL < minspeed ) {speedL = minspeed;};
|
||||||
|
if( speedR > maxspeed ) {speedR = maxspeed;};
|
||||||
|
if( speedR < minspeed ) {speedR = minspeed;};
|
||||||
|
MotorLinks(Vorwaerts, speedL);
|
||||||
|
MotorRechts(Vorwaerts, speedR);
|
||||||
|
isrLFlag = false;
|
||||||
|
isrRFlag = false;
|
||||||
|
};
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ g=1; minspeed=60; maxspeed=255;
|
||||||
|
digitalWrite(LED_3,LOW);
|
||||||
|
digitalWrite(LED_4,HIGH);
|
||||||
|
digitalWrite(LED_5,HIGH);
|
||||||
|
if( isrLFlag == true )
|
||||||
|
{ if( diffL > speedSetL ) {speedL=speedL+g;};
|
||||||
|
if( diffL < speedSetL ) {speedL=speedL-g;};
|
||||||
|
if( speedL > maxspeed ) {speedL = maxspeed;};
|
||||||
|
if( speedL < minspeed ) {speedL = minspeed;};
|
||||||
|
//Serial.print("links : "); Serial.print(countL); Serial.print(" : "); Serial.print(diffL); Serial.print(" : "); Serial.println(speedL);
|
||||||
|
MotorLinks(Vorwaerts, speedL);
|
||||||
|
isrLFlag = false;
|
||||||
|
};
|
||||||
|
if( isrRFlag == true )
|
||||||
|
{ if( diffR > speedSetR ) {speedR=speedR+g;};
|
||||||
|
if( diffR < speedSetR ) {speedR=speedR-g;};
|
||||||
|
if( speedR > maxspeed ) {speedR = maxspeed;};
|
||||||
|
if( speedR < minspeed ) {speedR = minspeed;};
|
||||||
|
//Serial.print("rechts: "); Serial.print(countR); Serial.print(" : "); Serial.print(diffR); Serial.print(" : "); Serial.println(speedR);
|
||||||
|
MotorRechts(Vorwaerts, speedR);
|
||||||
|
isrRFlag = false;
|
||||||
|
};
|
||||||
|
};
|
||||||
|
};
|
||||||
|
|
||||||
|
/* case 0: //----------------------------------------------- Starten der Geradeausfahrt
|
||||||
|
{ if( TL ) // CodeRacer starten
|
||||||
|
{ delay(1000);
|
||||||
|
speedL=70; // Startgeschwindigkeit
|
||||||
|
speedR=70;
|
||||||
|
MotorLinks(Vorwaerts, speedL);
|
||||||
|
MotorRechts(Vorwaerts, speedR);
|
||||||
|
timeLPrev = micros();
|
||||||
|
timeRPrev = micros();
|
||||||
|
countL = 0;
|
||||||
|
countR = 0;
|
||||||
|
};
|
||||||
|
if( TR ) // CodeRacer stoppen
|
||||||
|
{ speedL=0;
|
||||||
|
speedR=0;
|
||||||
|
MotorLinks(Vorwaerts, speedL);
|
||||||
|
MotorRechts(Vorwaerts, speedR);
|
||||||
|
speedSet = 0;
|
||||||
|
};
|
||||||
|
g = 3; minspeed=60; maxspeed=90;
|
||||||
|
if( (isrLFlag == true) || (isrRFlag == true) )
|
||||||
|
{ if( countL > countR )
|
||||||
|
{ speedL=speedL-g;
|
||||||
|
speedR=speedR+g;
|
||||||
|
};
|
||||||
|
if( countR > countL )
|
||||||
|
{ speedL=speedL+g;
|
||||||
|
speedR=speedR-g;
|
||||||
|
};
|
||||||
|
//Serial.print("links : "); Serial.print(countL); Serial.print(" : "); Serial.print(diffL); Serial.print(" : "); Serial.println(speedL);
|
||||||
|
//Serial.print("rechts: "); Serial.print(countR); Serial.print(" : "); Serial.print(diffR); Serial.print(" : "); Serial.println(speedR);
|
||||||
|
if( speedL > maxspeed ) {speedL = maxspeed;};
|
||||||
|
if( speedL < minspeed ) {speedL = minspeed;};
|
||||||
|
if( speedR > maxspeed ) {speedR = maxspeed;};
|
||||||
|
if( speedR < minspeed ) {speedR = minspeed;};
|
||||||
|
MotorLinks(Vorwaerts, speedL);
|
||||||
|
MotorRechts(Vorwaerts, speedR);
|
||||||
|
isrLFlag = false;
|
||||||
|
isrRFlag = false;
|
||||||
|
};
|
||||||
|
break;
|
||||||
|
};*/
|
||||||
|
/* case 13: //----------------------------------------------- circle left/right
|
||||||
|
{ delay(1000);
|
||||||
|
digitalWrite(Motor_Links_VorwaertsRueckwaerts,HIGH);
|
||||||
|
for( speed = 0; speed <= 255; speed = speed + 1)
|
||||||
|
{ delay(100);
|
||||||
|
ledcWrite(PWM_Links, speed);
|
||||||
|
digitalWrite(LED_1, bitRead(speed,7));
|
||||||
|
digitalWrite(LED_2, bitRead(speed,6));
|
||||||
|
digitalWrite(LED_3, bitRead(speed,5));
|
||||||
|
digitalWrite(LED_4, bitRead(speed,4));
|
||||||
|
digitalWrite(LED_5, bitRead(speed,3));
|
||||||
|
digitalWrite(LED_6, bitRead(speed,2));
|
||||||
|
};
|
||||||
|
delay(5000);
|
||||||
|
for( speed = 255; speed > 0; speed = speed - 1)
|
||||||
|
{ delay(100);
|
||||||
|
ledcWrite(PWM_Links, speed);
|
||||||
|
digitalWrite(LED_1, bitRead(speed,7));
|
||||||
|
digitalWrite(LED_2, bitRead(speed,6));
|
||||||
|
digitalWrite(LED_3, bitRead(speed,5));
|
||||||
|
digitalWrite(LED_4, bitRead(speed,4));
|
||||||
|
digitalWrite(LED_5, bitRead(speed,3));
|
||||||
|
digitalWrite(LED_6, bitRead(speed,2));
|
||||||
|
};
|
||||||
|
//ledcWrite(PWM_Links, 0);
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case 14: //----------------------------------------------- drive straigt ahead
|
||||||
|
{ delay(1000);
|
||||||
|
digitalWrite(Motor_Links_VorwaertsRueckwaerts,HIGH);
|
||||||
|
for( speed = 0; speed <= 255; speed = speed + 1)
|
||||||
|
{ delay(100);
|
||||||
|
ledcWrite(PWM_Links, speed);
|
||||||
|
digitalWrite(LED_1, bitRead(speed,7));
|
||||||
|
digitalWrite(LED_2, bitRead(speed,6));
|
||||||
|
digitalWrite(LED_3, bitRead(speed,5));
|
||||||
|
digitalWrite(LED_4, bitRead(speed,4));
|
||||||
|
digitalWrite(LED_5, bitRead(speed,3));
|
||||||
|
digitalWrite(LED_6, bitRead(speed,2));
|
||||||
|
};
|
||||||
|
delay(5000);
|
||||||
|
for( speed = 255; speed > 0; speed = speed - 1)
|
||||||
|
{ delay(100);
|
||||||
|
ledcWrite(PWM_Links, speed);
|
||||||
|
digitalWrite(LED_1, bitRead(speed,7));
|
||||||
|
digitalWrite(LED_2, bitRead(speed,6));
|
||||||
|
digitalWrite(LED_3, bitRead(speed,5));
|
||||||
|
digitalWrite(LED_4, bitRead(speed,4));
|
||||||
|
digitalWrite(LED_5, bitRead(speed,3));
|
||||||
|
digitalWrite(LED_6, bitRead(speed,2));
|
||||||
|
};
|
||||||
|
//ledcWrite(PWM_Links, 0);
|
||||||
|
break;
|
||||||
|
};*/
|
||||||
|
/*case 15: //----------------------------------------------- Serial read
|
||||||
|
{ while( HIGH ) {};
|
||||||
|
break;
|
||||||
|
};*/
|
||||||
|
};
|
||||||
|
};
|
||||||
|
}
|
|
@ -1,44 +1,46 @@
|
||||||
#include <ESP32Servo.h>
|
#include <ESP32Servo.h>
|
||||||
|
|
||||||
#define SERVOPIN 16 // Pin an dem der Servomotor angeschlossen ist. 'GPIO' muss man weglassen -> also nicht GPIO88 sondern nur 88.
|
#define SERVO_LINKS 136 // Wert um den Servo 45 Grad nach links zu drehen ... der kann je nach Servo anders sein
|
||||||
#define SERVO_45GRAD_LINKS 136 // Wert um den Servo 45 Grad nach links zu drehen ... der kann je nach Servo anders sein
|
#define SERVO_RECHTS 45 // Wert um den Servo 45 Grad nach rechtss zu drehen ... der kann je nach Servo anders sein
|
||||||
#define SERVO_45GRAD_RECHTS 45 // Wert um den Servo 45 Grad nach rechtss zu drehen ... der kann je nach Servo anders sein
|
#define SERVO_MITTE 90 // Wert um den Servo in die Mitte zu drehen ... der kann je nach Servo anders sein
|
||||||
#define SERVO_0GRAD_MITTE 90 // Wert um den Servo in die Mitte zu drehen ... der kann je nach Servo anders sein
|
|
||||||
|
|
||||||
Servo myservo; // ein Servo-Objekt anlegen, um den Servo Motor steuern zu können
|
Servo myservo[8]; // ein Servo-Objekt anlegen, um den Servo Motor steuern zu können
|
||||||
|
// 0 1 2 3 4 5 6 7
|
||||||
|
const unsigned int myservo_pin[] = {21, 32, 12, 13, 22, 19, 16, 23 };
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
|
|
||||||
Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
||||||
|
for(unsigned int serv=0;serv<=7;serv++)
|
||||||
myservo.attach(SERVOPIN); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist
|
{
|
||||||
|
myservo[serv].attach(myservo_pin[serv]); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist
|
||||||
|
delay(200);
|
||||||
|
myservo[serv].write(SERVO_MITTE);
|
||||||
|
delay(500);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
ServoMitte();
|
for(unsigned int serv = 0; serv <= 7; serv++)
|
||||||
ServoRechts();
|
{
|
||||||
ServoMitte();
|
setServo(serv, SERVO_LINKS);
|
||||||
ServoLinks();
|
setServo(serv, SERVO_RECHTS);
|
||||||
|
setServo(serv, SERVO_MITTE);
|
||||||
|
Serial.println(".");
|
||||||
|
Serial.println("---------------------------------------------------");
|
||||||
|
delay(2000);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setServo(unsigned int serv, unsigned int angel)
|
||||||
//-------------- Funktionen und Prozeduren -------------------------
|
{
|
||||||
|
Serial.print("Servo ");
|
||||||
void ServoRechts(void){
|
Serial.print(serv);
|
||||||
Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
|
Serial.print(" set to ");
|
||||||
myservo.write(SERVO_45GRAD_RECHTS); // Servo auf den Winkel rechts drehen
|
Serial.print(angel);
|
||||||
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
myservo[serv].write(angel);
|
||||||
}
|
delay(1000);
|
||||||
|
|
||||||
void ServoLinks(void){
|
|
||||||
Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben
|
|
||||||
myservo.write(SERVO_45GRAD_LINKS); // Servo auf den Winkel links drehen
|
|
||||||
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
|
||||||
}
|
|
||||||
|
|
||||||
void ServoMitte(void){
|
|
||||||
Serial.println("SERVO_MITTE"); // Meldung am Monitor ausgeben
|
|
||||||
myservo.write(SERVO_0GRAD_MITTE); // Servo auf den Winkel links drehen
|
|
||||||
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
BIN
CoderRacerMurnau2019/Docu/Anmeldung.docx
Normal file
BIN
CoderRacerMurnau2019/Docu/Anmeldung.docx
Normal file
Binary file not shown.
BIN
CoderRacerMurnau2019/Docu/Anmeldung.pdf
Normal file
BIN
CoderRacerMurnau2019/Docu/Anmeldung.pdf
Normal file
Binary file not shown.
BIN
CoderRacerMurnau2019/Docu/Bauteile CodeRacer 190308.xlsx
Normal file
BIN
CoderRacerMurnau2019/Docu/Bauteile CodeRacer 190308.xlsx
Normal file
Binary file not shown.
BIN
CoderRacerMurnau2019/Docu/Preisliste Bausatz CodeRacer.docx
Normal file
BIN
CoderRacerMurnau2019/Docu/Preisliste Bausatz CodeRacer.docx
Normal file
Binary file not shown.
10
CoderRacerMurnau2019/Docu/Sonderkonditionen 190318.txt
Normal file
10
CoderRacerMurnau2019/Docu/Sonderkonditionen 190318.txt
Normal file
|
@ -0,0 +1,10 @@
|
||||||
|
Betref: Sonderkonditionen für MakerLab
|
||||||
|
Sehr geehrte Damen und Herren,
|
||||||
|
in kürze startet bei uns im MakerLab Murnau e.V. wieder ein CodeRacer Kurs für Kinder und Jugendliche. Innerhalb des Kurses bauen und Programmiern die Kids ein autonomes Fahrzeug.
|
||||||
|
Siehe Bild aus dem letzen Kurs.
|
||||||
|
<Bild>
|
||||||
|
Dafür wollen wir bei Ihnen einige Bauteile bestellen und meine Frage ist, ob Sie uns Sonderkonditionen für das MakerLab Murnau einräumen?
|
||||||
|
|
||||||
|
Viele Grüße
|
||||||
|
Ralf Kraume
|
||||||
|
S++
|
BIN
Doku/Coderacer MKII/ESP32-Pinout.png
Normal file
BIN
Doku/Coderacer MKII/ESP32-Pinout.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 394 KiB |
BIN
Doku/Coderacer MKII/Schaltplan.pdf
Normal file
BIN
Doku/Coderacer MKII/Schaltplan.pdf
Normal file
Binary file not shown.
BIN
Doku/education/coderacercode.pdf
Normal file
BIN
Doku/education/coderacercode.pdf
Normal file
Binary file not shown.
Binary file not shown.
60
readme.md
60
readme.md
|
@ -1,30 +1,30 @@
|
||||||
![Build Status](https://git.itsblue.de/Fenoglio/coderacer/badges/master/build.svg)
|
![Build Status](https://git.itsblue.de/Fenoglio/coderacer/badges/master/build.svg)
|
||||||
![Flyer](/Doku/Bilder/coderace_get_in_contact_pic.png)
|
![Flyer](/Doku/Bilder/coderace_get_in_contact_pic.png)
|
||||||
## Repo Overview
|
## Repo Overview
|
||||||
This is fun in progress and for sure not covering all questions and topics.
|
This is fun in progress and for sure not covering all questions and topics.
|
||||||
Hopefully you will get an idea of what that project means and is able to do.
|
Hopefully you will get an idea of what that project means and is able to do.
|
||||||
Have fun and let us know what you think.
|
Have fun and let us know what you think.
|
||||||
|
|
||||||
Repo dir | Description
|
Repo dir | Description
|
||||||
---------|--------------
|
---------|--------------
|
||||||
Arduino/libraries | arduino stuff and libraries
|
Arduino/libraries | arduino stuff and libraries
|
||||||
Doku | HowTo as well as doxygen documentation. To view doxygen documentation repository has to be downloaded (no rendering through gitlab)
|
Doku | HowTo as well as doxygen documentation. To view doxygen documentation repository has to be downloaded (no rendering through gitlab)
|
||||||
Install | Everything to get your dev IDE running on your PC
|
Install | Everything to get your dev IDE running on your PC
|
||||||
AppInventor | Module to load into AppInventor or directly to your phone.
|
AppInventor | Module to load into AppInventor or directly to your phone.
|
||||||
Fritzing | Schematics and stuff
|
Fritzing | Schematics and stuff
|
||||||
Bilder | Pictures of racers and events;-)
|
Bilder | Pictures of racers and events;-)
|
||||||
|
|
||||||
## Full API Docs
|
## Full API Docs
|
||||||
A full API Documentation is available [here](https://fenoglio.pages.itsblue.de/coderacer/)
|
A full API Documentation is available [here](https://fenoglio.pages.itsblue.de/coderacer/)
|
||||||
|
|
||||||
## How to start
|
## How to start
|
||||||
* Start reading the [{code}racer HowTo](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf)
|
* Start reading the [{code}racer HowTo](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf)
|
||||||
* Learn about the [{code}racer API](https://fenoglio.pages.itsblue.de/coderacer/)
|
* Learn about the [{code}racer API](https://fenoglio.pages.itsblue.de/coderacer/)
|
||||||
* Download the {code}racer Repo and install the IDE on your PC (see [CodeRacer HowTo Page.8](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
* Download the {code}racer Repo and install the IDE on your PC (see [CodeRacer HowTo Page.8](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
* Installation of used libraries (see [{code}racer HowTo Page.10](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
* Installation of used libraries (see [{code}racer HowTo Page.10](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
* Compile example (esp32_coderacer_beispiel) (see [{code}racer HowTo Page.11](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
* Compile example (esp32_coderacer_beispiel) (see [{code}racer HowTo Page.11](https://git.itsblue.de/Fenoglio/coderacer/tree/master/Doku/coderacer_handbuch.pdf))
|
||||||
* Work on your OWN CodeRacer Algo
|
* Work on your OWN CodeRacer Algo
|
||||||
|
|
||||||
## Feedback/Questions
|
## Feedback/Questions
|
||||||
* Please write your questions/feedback to development@itsblue.de
|
* Please write your questions/feedback to development@itsblue.de
|
||||||
|
|
||||||
|
|
5
vsode/esp32_coderacer/.gitignore
vendored
Normal file
5
vsode/esp32_coderacer/.gitignore
vendored
Normal file
|
@ -0,0 +1,5 @@
|
||||||
|
.pio
|
||||||
|
.vscode/.browse.c_cpp.db*
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
.vscode/launch.json
|
||||||
|
.vscode/ipch
|
67
vsode/esp32_coderacer/.travis.yml
Normal file
67
vsode/esp32_coderacer/.travis.yml
Normal file
|
@ -0,0 +1,67 @@
|
||||||
|
# Continuous Integration (CI) is the practice, in software
|
||||||
|
# engineering, of merging all developer working copies with a shared mainline
|
||||||
|
# several times a day < https://docs.platformio.org/page/ci/index.html >
|
||||||
|
#
|
||||||
|
# Documentation:
|
||||||
|
#
|
||||||
|
# * Travis CI Embedded Builds with PlatformIO
|
||||||
|
# < https://docs.travis-ci.com/user/integration/platformio/ >
|
||||||
|
#
|
||||||
|
# * PlatformIO integration with Travis CI
|
||||||
|
# < https://docs.platformio.org/page/ci/travis.html >
|
||||||
|
#
|
||||||
|
# * User Guide for `platformio ci` command
|
||||||
|
# < https://docs.platformio.org/page/userguide/cmd_ci.html >
|
||||||
|
#
|
||||||
|
#
|
||||||
|
# Please choose one of the following templates (proposed below) and uncomment
|
||||||
|
# it (remove "# " before each line) or use own configuration according to the
|
||||||
|
# Travis CI documentation (see above).
|
||||||
|
#
|
||||||
|
|
||||||
|
|
||||||
|
#
|
||||||
|
# Template #1: General project. Test it using existing `platformio.ini`.
|
||||||
|
#
|
||||||
|
|
||||||
|
# language: python
|
||||||
|
# python:
|
||||||
|
# - "2.7"
|
||||||
|
#
|
||||||
|
# sudo: false
|
||||||
|
# cache:
|
||||||
|
# directories:
|
||||||
|
# - "~/.platformio"
|
||||||
|
#
|
||||||
|
# install:
|
||||||
|
# - pip install -U platformio
|
||||||
|
# - platformio update
|
||||||
|
#
|
||||||
|
# script:
|
||||||
|
# - platformio run
|
||||||
|
|
||||||
|
|
||||||
|
#
|
||||||
|
# Template #2: The project is intended to be used as a library with examples.
|
||||||
|
#
|
||||||
|
|
||||||
|
# language: python
|
||||||
|
# python:
|
||||||
|
# - "2.7"
|
||||||
|
#
|
||||||
|
# sudo: false
|
||||||
|
# cache:
|
||||||
|
# directories:
|
||||||
|
# - "~/.platformio"
|
||||||
|
#
|
||||||
|
# env:
|
||||||
|
# - PLATFORMIO_CI_SRC=path/to/test/file.c
|
||||||
|
# - PLATFORMIO_CI_SRC=examples/file.ino
|
||||||
|
# - PLATFORMIO_CI_SRC=path/to/test/directory
|
||||||
|
#
|
||||||
|
# install:
|
||||||
|
# - pip install -U platformio
|
||||||
|
# - platformio update
|
||||||
|
#
|
||||||
|
# script:
|
||||||
|
# - platformio ci --lib="." --board=ID_1 --board=ID_2 --board=ID_N
|
7
vsode/esp32_coderacer/.vscode/extensions.json
vendored
Normal file
7
vsode/esp32_coderacer/.vscode/extensions.json
vendored
Normal file
|
@ -0,0 +1,7 @@
|
||||||
|
{
|
||||||
|
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||||
|
// for the documentation about the extensions.json format
|
||||||
|
"recommendations": [
|
||||||
|
"platformio.platformio-ide"
|
||||||
|
]
|
||||||
|
}
|
39
vsode/esp32_coderacer/include/README
Normal file
39
vsode/esp32_coderacer/include/README
Normal file
|
@ -0,0 +1,39 @@
|
||||||
|
|
||||||
|
This directory is intended for project header files.
|
||||||
|
|
||||||
|
A header file is a file containing C declarations and macro definitions
|
||||||
|
to be shared between several project source files. You request the use of a
|
||||||
|
header file in your project source file (C, C++, etc) located in `src` folder
|
||||||
|
by including it, with the C preprocessing directive `#include'.
|
||||||
|
|
||||||
|
```src/main.c
|
||||||
|
|
||||||
|
#include "header.h"
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
Including a header file produces the same results as copying the header file
|
||||||
|
into each source file that needs it. Such copying would be time-consuming
|
||||||
|
and error-prone. With a header file, the related declarations appear
|
||||||
|
in only one place. If they need to be changed, they can be changed in one
|
||||||
|
place, and programs that include the header file will automatically use the
|
||||||
|
new version when next recompiled. The header file eliminates the labor of
|
||||||
|
finding and changing all the copies as well as the risk that a failure to
|
||||||
|
find one copy will result in inconsistencies within a program.
|
||||||
|
|
||||||
|
In C, the usual convention is to give header files names that end with `.h'.
|
||||||
|
It is most portable to use only letters, digits, dashes, and underscores in
|
||||||
|
header file names, and at most one dot.
|
||||||
|
|
||||||
|
Read more about using header files in official GCC documentation:
|
||||||
|
|
||||||
|
* Include Syntax
|
||||||
|
* Include Operation
|
||||||
|
* Once-Only Headers
|
||||||
|
* Computed Includes
|
||||||
|
|
||||||
|
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
1345
vsode/esp32_coderacer/lib/CodeRacer/CodeRacer.cpp
Normal file
1345
vsode/esp32_coderacer/lib/CodeRacer/CodeRacer.cpp
Normal file
File diff suppressed because it is too large
Load diff
282
vsode/esp32_coderacer/lib/CodeRacer/CodeRacer.h
Normal file
282
vsode/esp32_coderacer/lib/CodeRacer/CodeRacer.h
Normal file
|
@ -0,0 +1,282 @@
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include <algorithm> // std::swap
|
||||||
|
#include <ESP32Servo.h> // Servo drive support for ESP32
|
||||||
|
#include "esp32-hal-ledc.h" // Part of ESP32 board files - Analog output
|
||||||
|
#include "BluetoothSerial.h" // Bluetooth enablement - part of ESP or standart Arduino lib
|
||||||
|
#include <vector> // support for vectors
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#if !defined(CONFIG_BT_ENABLED) || !defined(CONFIG_BLUEDROID_ENABLED)
|
||||||
|
#error Bluetooth is not enabled! Please run `make menuconfig` to and enable it
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef __CodeRacer_H__
|
||||||
|
#define __CodeRacer_H__
|
||||||
|
|
||||||
|
//----- Fun stuff ---------
|
||||||
|
#define FUN_MIN_PAUSE_MS 120000 // minimum and maximum pause between to rounds fun
|
||||||
|
#define FUN_MAX_PAUSE_MS 300000
|
||||||
|
#define LED_SWITCH_MS 50 // speed of knight rider lights
|
||||||
|
//----- Button ------------
|
||||||
|
#define H_BUTTON_PIN 17
|
||||||
|
#define BUTTON_BOUNCING_TIME_MS 200 // bouncing delay
|
||||||
|
//----- Servo -----
|
||||||
|
#define H_SERVO_PIN 16
|
||||||
|
#define H_SERVO_LEFT_POS 145 // left position of the servo
|
||||||
|
#define H_SERVO_CENTER_LEFT 100 // left-center position of the servo
|
||||||
|
#define H_SERVO_RIGHT_POS 35 // right position of the servo
|
||||||
|
#define H_SERVO_CENTER_RIGHT 80 // right-center position of the servo
|
||||||
|
#define H_SERVO_CENTER_POS 90 // center position of the servo
|
||||||
|
#define H_SERVO_SWEEP_LEFT_POS 140 // most left sweep position of the servo
|
||||||
|
#define H_SERVO_SWEEP_RIGHT_POS 40 // most right sweep position of the servo
|
||||||
|
#define SERVO_SWEEP_TO_LEFT_STEP 5 // sweep step to the left
|
||||||
|
#define SERVO_SWEEP_TO_RIGHT_STEP -5 // sweep step to the right
|
||||||
|
#define SERVO_SWEEP_MS 10 // duration of time betwee to sweep steps
|
||||||
|
#define SERVO_MAX_POSITION 170 // maximum servo position
|
||||||
|
#define SERVO_MIN_POSITION 10 // minimum servo position
|
||||||
|
#define SERVO_SET_1TICK_POSITION_DELAY_MS 3 // minimum duration of time between two servo steps
|
||||||
|
|
||||||
|
//----- Ultrasonic sensor -----
|
||||||
|
#define H_US_TRIG_PIN 12
|
||||||
|
#define H_US_ECHO_PIN 14
|
||||||
|
#define H_US_STOP_DISTANCE_CM 25 // if the measured distance is smaller the racer maybe stopped
|
||||||
|
#define US_MAX_ECHO_TIME_US 6000 // timeout for ultrasonic sensor measurements - this is about 100cm
|
||||||
|
|
||||||
|
//----- Drives -----
|
||||||
|
#define H_DRIVE_RIGHT_SPEED 255 // default speed of right side drive. 0 ...255
|
||||||
|
#define H_DRIVE_LEFT_SPEED 255 // default speed of left side drive. 0 ...255
|
||||||
|
#define H_DRIVE_RIGHT_ENABLE_PIN 2
|
||||||
|
#define H_DRIVE_RIGHT_FWRD_PIN 4
|
||||||
|
#define H_DRIVE_RIGHT_BACK_PIN 15
|
||||||
|
#define H_DRIVE_LEFT_ENABLE_PIN 21
|
||||||
|
#define H_DRIVE_LEFT_FWRD_PIN 22
|
||||||
|
#define H_DRIVE_LEFT_BACK_PIN 23
|
||||||
|
#define H_RACER_TURN_LEFT_FOR_MS 400 // duration of time the racer will turn to left
|
||||||
|
#define H_RACER_TURN_RIGHT_FOR_MS 400 // duration of time the racer will turn to right
|
||||||
|
|
||||||
|
#define DRIVE_PWM_LEFT_CHANNEL 5 // PWM-channel for left side drive
|
||||||
|
#define DRIVE_PWM_RIGHT_CHANNEL 6 // PWM-channel for right side drive
|
||||||
|
|
||||||
|
//----- LEDs -----
|
||||||
|
#define H_LED_FRWD_PIN 26
|
||||||
|
#define H_LED_STOP_PIN 25
|
||||||
|
#define H_LED_LEFT_PIN 33
|
||||||
|
#define H_LED_RIGHT_PIN 27
|
||||||
|
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
static volatile bool coderracer_activ = false;;
|
||||||
|
static volatile unsigned long button_last_pressed_at_ms = millis();
|
||||||
|
|
||||||
|
enum ledstate {
|
||||||
|
LEDOFF,
|
||||||
|
LEDON
|
||||||
|
};
|
||||||
|
|
||||||
|
enum drivestate {
|
||||||
|
DRIVESTOP,
|
||||||
|
DRIVEFRWD,
|
||||||
|
DRIVEBACK
|
||||||
|
};
|
||||||
|
|
||||||
|
//--- this is as preparation of the class creation
|
||||||
|
class CodeRacer {
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
//bluetooth
|
||||||
|
std::vector<String> _bt_ignoremsgs;
|
||||||
|
std::vector<String> _bt_onlymsgs;
|
||||||
|
bool _bluetoothcreated;
|
||||||
|
unsigned long _bt_stopOnLostConnection_timeout_ms;
|
||||||
|
unsigned long _bt_lastmessagereceived;
|
||||||
|
BluetoothSerial* _BTSerial;
|
||||||
|
|
||||||
|
//pins
|
||||||
|
uint8_t _button_pin;
|
||||||
|
uint8_t _servo_pin;
|
||||||
|
uint8_t _us_trigger_pin;
|
||||||
|
uint8_t _us_echo_pin;
|
||||||
|
uint8_t _drive_left_frwd_pin;
|
||||||
|
uint8_t _drive_left_back_pin;
|
||||||
|
uint8_t _drive_left_enable_pin;
|
||||||
|
uint8_t _drive_right_frwd_pin;
|
||||||
|
uint8_t _drive_right_back_pin;
|
||||||
|
uint8_t _drive_right_enable_pin;
|
||||||
|
uint8_t _led_frwd_pin;
|
||||||
|
uint8_t _led_stop_pin;
|
||||||
|
uint8_t _led_left_pin;
|
||||||
|
uint8_t _led_right_pin;
|
||||||
|
|
||||||
|
//servo variables
|
||||||
|
int8_t _servo_sweep_step;
|
||||||
|
uint8_t _servo_position;
|
||||||
|
unsigned long _servo_position_set_at_ms;
|
||||||
|
unsigned long _servo_position_eta_in_ms;
|
||||||
|
|
||||||
|
//drives variables
|
||||||
|
uint8_t _drive_left_speed;
|
||||||
|
uint8_t _drive_right_speed;
|
||||||
|
unsigned long _turn_left_for_ms;
|
||||||
|
unsigned long _turn_right_for_ms;
|
||||||
|
|
||||||
|
// ultrasonic variables
|
||||||
|
bool _coderacer_stopped_at_min_distance;
|
||||||
|
bool _coderacer_stop_at_distance_enabled;
|
||||||
|
unsigned long _usonic_stop_distance_cm;
|
||||||
|
unsigned long _usonic_stop_distance_us;
|
||||||
|
unsigned long _usonic_distance_us;
|
||||||
|
unsigned long _usonic_distance_cm;
|
||||||
|
|
||||||
|
//fun stuff variables
|
||||||
|
unsigned long _last_led_switched_at_ms;
|
||||||
|
uint8_t _led_count;
|
||||||
|
uint8_t _last_led_on;
|
||||||
|
unsigned long _servo_look_around_at_ms;
|
||||||
|
|
||||||
|
|
||||||
|
unsigned long _min_distance_cm;
|
||||||
|
bool _drive;
|
||||||
|
unsigned long _drive_set_at_ms;
|
||||||
|
bool _servo_sweep;
|
||||||
|
bool _coderracer_activ;
|
||||||
|
|
||||||
|
//objects
|
||||||
|
Servo* _servo;
|
||||||
|
Servo* _servo_dummy;
|
||||||
|
|
||||||
|
static void _set_button_state();
|
||||||
|
void _analog_write(uint8_t pin, uint8_t speed);
|
||||||
|
unsigned long _servo_set_position(uint8_t position);
|
||||||
|
|
||||||
|
public:
|
||||||
|
//properties
|
||||||
|
bool coderacer_fun_enabled;
|
||||||
|
|
||||||
|
uint8_t servo_center_pos; /**< The position the servo is looking straight forward. Default is 90 . Allowed are values 10<=pos<=170 */
|
||||||
|
uint8_t servo_left_pos; /**< The position the servo is looking to the left. Default is 170 . Allowed are values 10<=pos<=170 */
|
||||||
|
uint8_t servo_right_pos; /**< The position the servo is looking to the right. Default is 0 . Allowed are values 10<=pos<=170 */
|
||||||
|
uint8_t servo_sweep_left_pos; /**< When the servo is sweeping this is the left most position */
|
||||||
|
uint8_t servo_sweep_right_pos; /**< When the servo is sweeping this is the right most position */
|
||||||
|
|
||||||
|
//methods
|
||||||
|
CodeRacer();
|
||||||
|
|
||||||
|
CodeRacer(uint8_t button_pin, uint8_t servo_pin,
|
||||||
|
uint8_t us_trigger_pin, uint8_t us_echo_pin,
|
||||||
|
uint8_t drive_left_frwd_pin, uint8_t drive_left_back_pin, uint8_t drive_left_enable_pin,
|
||||||
|
uint8_t drive_right_frwd_pin, uint8_t drive_right_back_pin, uint8_t drive_right_enable_pin,
|
||||||
|
uint8_t led_frwd_pin, uint8_t led_stop_pin, uint8_t led_left_pin, uint8_t led_right_pin);
|
||||||
|
|
||||||
|
void set_inactive();
|
||||||
|
void set_active();
|
||||||
|
|
||||||
|
void begin();
|
||||||
|
|
||||||
|
// getters
|
||||||
|
bool is_active();
|
||||||
|
bool is_driving();
|
||||||
|
bool stopped_at_min_distance();
|
||||||
|
unsigned long usonic_distance_cm();
|
||||||
|
unsigned long usonic_distance_us();
|
||||||
|
uint8_t servo_position();
|
||||||
|
unsigned long servo_position_set_at_ms();
|
||||||
|
unsigned long servo_position_eta_in_ms();
|
||||||
|
uint8_t drive_left_speed();
|
||||||
|
uint8_t drive_right_speed();
|
||||||
|
unsigned long turn_left_for_ms();
|
||||||
|
unsigned long turn_right_for_ms();
|
||||||
|
|
||||||
|
// higher level {code}racer services
|
||||||
|
void stop_driving();
|
||||||
|
void drive_forward();
|
||||||
|
void drive_forward(uint8_t left_speed, uint8_t right_speed);
|
||||||
|
void drive_backward();
|
||||||
|
void drive_backward(uint8_t left_speed, uint8_t right_speed);
|
||||||
|
void turn_left();
|
||||||
|
void turn_left(unsigned long turn_for_ms);
|
||||||
|
void turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
|
||||||
|
void turn_right();
|
||||||
|
void turn_right(unsigned long turn_for_ms);
|
||||||
|
void turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
|
||||||
|
|
||||||
|
void start_stop_at_min_distance();
|
||||||
|
void start_stop_at_min_distance(unsigned long min_distance_cm);
|
||||||
|
void stop_stop_at_min_distance();
|
||||||
|
|
||||||
|
// Bluetooth
|
||||||
|
void bt_enable_stopOnLostConnection();
|
||||||
|
void bt_enable_stopOnLostConnection(unsigned long timeout);
|
||||||
|
void bt_disable_stopOnLostConnection();
|
||||||
|
void bt_start(String name);
|
||||||
|
String bt_getString();
|
||||||
|
String bt_getString(uint8_t delimiterbyte);
|
||||||
|
bool bt_msgavailable();
|
||||||
|
void bt_addStringToIgnoreList(String stringtoignore);
|
||||||
|
void bt_clearIgnoreList();
|
||||||
|
void bt_removeStringFromIgnoreList(String stringtoignore);
|
||||||
|
|
||||||
|
// LEDs
|
||||||
|
void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled);
|
||||||
|
void set_leds_all(ledstate alleds);
|
||||||
|
void set_leds_all_off();
|
||||||
|
void set_leds_all_on();
|
||||||
|
|
||||||
|
// Drives
|
||||||
|
void drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms);
|
||||||
|
void set_drives_states_left_right(drivestate stateleft, drivestate stateright);
|
||||||
|
void set_drive_left_state(drivestate state);
|
||||||
|
void set_drive_right_state(drivestate state);
|
||||||
|
void set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin);
|
||||||
|
void set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright);
|
||||||
|
void set_drive_left_speed(uint8_t speed);
|
||||||
|
void set_drive_right_speed(uint8_t speed);
|
||||||
|
void set_drive_speed(uint8_t speed, uint8_t enablepin);
|
||||||
|
void set_drives_stop_left_right();
|
||||||
|
|
||||||
|
// Ultrasonic sensor
|
||||||
|
unsigned long usonic_measure_cm();
|
||||||
|
unsigned long usonic_measure_us();
|
||||||
|
unsigned long usonic_measure_cm(unsigned long max_echo_run_time_us);
|
||||||
|
unsigned long usonic_measure_us(unsigned long max_echo_run_time_us);
|
||||||
|
unsigned long usonic_measure_single_shot_cm();
|
||||||
|
unsigned long usonic_measure_single_shot_us();
|
||||||
|
unsigned long usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us);
|
||||||
|
unsigned long usonic_measure_single_shot_us(unsigned long max_echo_run_time_us);
|
||||||
|
void usonic_set_stop_distance_cm(unsigned long stop_distance_cm);
|
||||||
|
void usonic_set_stop_distance_us(unsigned long stop_distance_us);
|
||||||
|
|
||||||
|
// Servo drive
|
||||||
|
void servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos);
|
||||||
|
uint8_t servo_set_position_wait(uint8_t position);
|
||||||
|
unsigned long servo_set_position(uint8_t position);
|
||||||
|
void servo_set_to_right();
|
||||||
|
void servo_set_to_left();
|
||||||
|
void servo_set_to_center();
|
||||||
|
void servo_sweep();
|
||||||
|
|
||||||
|
// just for fun
|
||||||
|
void kitt();
|
||||||
|
void look_around();
|
||||||
|
|
||||||
|
// previous OBSOLETE german language definitions of the methods - still needed to support MakerLab Murnau {code}racer project
|
||||||
|
// - but use the english ones for new implementations
|
||||||
|
void servo_einstellungen(uint8_t winkel_mitte, uint8_t winkel_links, uint8_t winkel_rechts, uint8_t schwenk_links, uint8_t schwenk_rechts);
|
||||||
|
void motor_einstellungen(uint8_t motor_links_tempo, uint8_t motor_rechts_tempo, unsigned long drehung_links_ms, unsigned long drehung_rechts_ms);
|
||||||
|
void anhalten();
|
||||||
|
void vorwaerts();
|
||||||
|
void rueckwaerts();
|
||||||
|
void links();
|
||||||
|
void rechts();
|
||||||
|
void servo_rechts();
|
||||||
|
void servo_links();
|
||||||
|
void servo_mitte();
|
||||||
|
unsigned long abstand_messen();
|
||||||
|
void servo_schwenk();
|
||||||
|
bool start_stop();
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,56 @@
|
||||||
|
|
||||||
|
// Full API description of the coderacer.h can be found here: https://fenoglio.pages.itsblue.de/coderacer/
|
||||||
|
// Repository with all needed data and users guide is here: https://git.itsblue.de/Fenoglio/coderacer/tree/master
|
||||||
|
// An example for a application to control the coderacer via bluetooth can be found here: https://git.itsblue.de/Fenoglio/coderacer/tree/master/AppInventor/SimpleBTCoderacer
|
||||||
|
// - this app was developed with MIT App Inventor and can be uploaded to your account to rework it.
|
||||||
|
|
||||||
|
#include <CodeRacer.h>
|
||||||
|
|
||||||
|
CodeRacer coderacer;
|
||||||
|
String recvddata = ""; //Variable in der der Bluetooth Befehl gespeichert wird
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
coderacer.begin();
|
||||||
|
coderacer.bt_start("CodeRacer"); //Bluetooth für den Coderacer anschalten
|
||||||
|
coderacer.bt_enable_stopOnLostConnection(); //Coderacer anhalten, wenn 1 Sekunde nichts per Bluetooth empfangen wurde
|
||||||
|
coderacer.bt_addStringToIgnoreList("."); //das "." Zeichen wird beim empfangen ignoriert
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// Prüfen ob Bluetooth Nachrichten angekommen sind und die gleich abholen ...
|
||||||
|
recvddata = coderacer.bt_getString(); //die Nachtricht merken (sie steht jetzt in recvdata und kann später benutzt werden)
|
||||||
|
if (recvddata != "") //wenn eine Nachricht empfangen wurde, in der was drin steht ...
|
||||||
|
{
|
||||||
|
Serial.println(recvddata);
|
||||||
|
|
||||||
|
if(recvddata == "stop")
|
||||||
|
{
|
||||||
|
coderacer.stop_driving();
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata == "vor")
|
||||||
|
{
|
||||||
|
coderacer.drive_forward(255,255);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata.startsWith("rueck"))
|
||||||
|
{
|
||||||
|
coderacer.drive_backward(255,255);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata.startsWith("links"))
|
||||||
|
{
|
||||||
|
coderacer.turn_left();
|
||||||
|
}
|
||||||
|
|
||||||
|
if(recvddata.startsWith("rechts"))
|
||||||
|
{
|
||||||
|
coderacer.turn_right();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
delay(20);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,82 @@
|
||||||
|
#include <CodeRacer.h>
|
||||||
|
|
||||||
|
//----- settings for the ultrasonic sensor -----
|
||||||
|
#define US_STOP_ABSTAND_CM 20 // if distance goes below that - stop the racer
|
||||||
|
|
||||||
|
//----- variables we need
|
||||||
|
unsigned long distance_cm = 0;
|
||||||
|
|
||||||
|
//---- construct the coderacer object
|
||||||
|
CodeRacer coderacer;
|
||||||
|
|
||||||
|
//---- set up code - executed ones
|
||||||
|
void setup() {
|
||||||
|
// start serial monitor
|
||||||
|
Serial.begin(115200);
|
||||||
|
// initialize the coderacer
|
||||||
|
coderacer.begin();
|
||||||
|
// enable fun stuff
|
||||||
|
coderacer.coderacer_fun_enabled = true;
|
||||||
|
// look to the left, to the right and to center... :-)
|
||||||
|
coderacer.servo_set_to_left();
|
||||||
|
delay(100);
|
||||||
|
coderacer.servo_set_to_right();
|
||||||
|
delay(100);
|
||||||
|
coderacer.servo_set_to_center();
|
||||||
|
delay(100);
|
||||||
|
}
|
||||||
|
|
||||||
|
//---- 'endless' loop
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
// check if the racer was started (button was toggled to coderacer active state
|
||||||
|
if(true == coderacer.start_stop()){
|
||||||
|
|
||||||
|
Serial.print("Speed of right side drive: ");
|
||||||
|
Serial.println(coderacer.drive_right_speed());
|
||||||
|
Serial.print("Speed of left side drive: ");
|
||||||
|
Serial.println(coderacer.drive_left_speed());
|
||||||
|
|
||||||
|
// measure the distance - at the position of the servo
|
||||||
|
distance_cm = coderacer.usonic_measure_cm();
|
||||||
|
|
||||||
|
coderacer.start_stop_at_min_distance(US_STOP_ABSTAND_CM);
|
||||||
|
while(!coderacer.stopped_at_min_distance()){
|
||||||
|
|
||||||
|
Serial.print("Distanc in cm: ");
|
||||||
|
Serial.println(distance_cm);
|
||||||
|
|
||||||
|
if(distance_cm > 50){
|
||||||
|
coderacer.drive_forward();
|
||||||
|
coderacer.servo_sweep();
|
||||||
|
}
|
||||||
|
else if(distance_cm > 40){
|
||||||
|
coderacer.turn_right();
|
||||||
|
}
|
||||||
|
else if(distance_cm > 30){
|
||||||
|
coderacer.turn_left();
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
|
||||||
|
coderacer.drive_backward();
|
||||||
|
}
|
||||||
|
|
||||||
|
// measure the distance - at the position of the servo
|
||||||
|
distance_cm = coderacer.usonic_measure_cm();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println("***** STOPPED ***** ");
|
||||||
|
Serial.print("Measured stop distanc of cm: ");
|
||||||
|
Serial.println(distance_cm);
|
||||||
|
Serial.print("Measured at servo position of: ");
|
||||||
|
Serial.println(coderacer.servo_position());
|
||||||
|
|
||||||
|
coderacer.set_inactive();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
15
vsode/esp32_coderacer/lib/CodeRacer/keywords.txt
Normal file
15
vsode/esp32_coderacer/lib/CodeRacer/keywords.txt
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
CodeRacer KEYWORD1
|
||||||
|
begin KEYWORD2
|
||||||
|
servo_einstellungen KEYWORD2
|
||||||
|
motor_einstellungen KEYWORD2
|
||||||
|
anhalten KEYWORD2
|
||||||
|
normal_tempo KEYWORD2
|
||||||
|
vorwaerts KEYWORD2
|
||||||
|
links KEYWORD2
|
||||||
|
rechts KEYWORD2
|
||||||
|
servo_rechts KEYWORD2
|
||||||
|
servo_links KEYWORD2
|
||||||
|
servo_mitte KEYWORD2
|
||||||
|
abstand_messen KEYWORD2
|
||||||
|
servo_schwenk KEYWORD2
|
||||||
|
start_stop KEYWORD2
|
46
vsode/esp32_coderacer/lib/README
Normal file
46
vsode/esp32_coderacer/lib/README
Normal file
|
@ -0,0 +1,46 @@
|
||||||
|
|
||||||
|
This directory is intended for project specific (private) libraries.
|
||||||
|
PlatformIO will compile them to static libraries and link into executable file.
|
||||||
|
|
||||||
|
The source code of each library should be placed in a an own separate directory
|
||||||
|
("lib/your_library_name/[here are source files]").
|
||||||
|
|
||||||
|
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||||
|
|
||||||
|
|--lib
|
||||||
|
| |
|
||||||
|
| |--Bar
|
||||||
|
| | |--docs
|
||||||
|
| | |--examples
|
||||||
|
| | |--src
|
||||||
|
| | |- Bar.c
|
||||||
|
| | |- Bar.h
|
||||||
|
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||||
|
| |
|
||||||
|
| |--Foo
|
||||||
|
| | |- Foo.c
|
||||||
|
| | |- Foo.h
|
||||||
|
| |
|
||||||
|
| |- README --> THIS FILE
|
||||||
|
|
|
||||||
|
|- platformio.ini
|
||||||
|
|--src
|
||||||
|
|- main.c
|
||||||
|
|
||||||
|
and a contents of `src/main.c`:
|
||||||
|
```
|
||||||
|
#include <Foo.h>
|
||||||
|
#include <Bar.h>
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
PlatformIO Library Dependency Finder will find automatically dependent
|
||||||
|
libraries scanning project source files.
|
||||||
|
|
||||||
|
More information about PlatformIO Library Dependency Finder
|
||||||
|
- https://docs.platformio.org/page/librarymanager/ldf.html
|
15
vsode/esp32_coderacer/platformio.ini
Normal file
15
vsode/esp32_coderacer/platformio.ini
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
;PlatformIO Project Configuration File
|
||||||
|
;
|
||||||
|
; Build options: build flags, source filter
|
||||||
|
; Upload options: custom upload port, speed and extra flags
|
||||||
|
; Library options: dependencies, extra library storages
|
||||||
|
; Advanced options: extra scripting
|
||||||
|
;
|
||||||
|
; Please visit documentation for the other options and examples
|
||||||
|
; https://docs.platformio.org/page/projectconf.html
|
||||||
|
|
||||||
|
[env:esp32dev]
|
||||||
|
platform = espressif32
|
||||||
|
board = esp32dev
|
||||||
|
framework = arduino
|
||||||
|
|
128
vsode/esp32_coderacer/src/esp32_coderacer.cpp
Normal file
128
vsode/esp32_coderacer/src/esp32_coderacer.cpp
Normal file
|
@ -0,0 +1,128 @@
|
||||||
|
#include "CodeRacer.h"
|
||||||
|
|
||||||
|
#include <ESP32Servo.h>
|
||||||
|
#include "esp32-hal-ledc.h"
|
||||||
|
|
||||||
|
//----- Werte für den Ultraschallsensor -----
|
||||||
|
#define US_STOP_ABSTAND_CM 20 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
||||||
|
#define US_MIN_ABSTAND_LI_RE 8 // Wenn der Unterschied zwischen linkem und und rechtem Abstand kleiner ist, dann drehe in dieselbe Richtugn wie vorher weiter
|
||||||
|
#define MAX_ANZAHL_DREHUNGEN 10 // Wenn der Coderacer sich schon so oft gedreht hat ohne eine Stelle zu finden, wo es Platz gibt - fahren wir mal ein Stück rückwärts ...
|
||||||
|
|
||||||
|
//----- Variablen, die wir brauchen um uns Werte zu merken ----
|
||||||
|
long abstand_vorn_cm, abstand_links_cm, abstand_rechts_cm;
|
||||||
|
enum drehrichtung {links=0, rechts};
|
||||||
|
drehrichtung drehung = links;
|
||||||
|
unsigned int anzahl_drehung = 0;
|
||||||
|
CodeRacer coderacer;
|
||||||
|
|
||||||
|
//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ----
|
||||||
|
void setup() {
|
||||||
|
// Monitor
|
||||||
|
Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
||||||
|
|
||||||
|
// CodeRacer initialisieren
|
||||||
|
coderacer.begin();
|
||||||
|
|
||||||
|
coderacer.servo_links();
|
||||||
|
delay(10);
|
||||||
|
coderacer.servo_rechts();
|
||||||
|
delay(10);
|
||||||
|
coderacer.servo_mitte();
|
||||||
|
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
drehung = links;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
//---- Hier startet unsere endlose Schleife - die immer wieder von vorn angefangen wird, wenn wir am Ende angekommen sind. Da ist unser "Fahr"Code drin, der den CodeRacer steuert
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
|
||||||
|
// Abstand messen -> nach vorn ... um zu sehen, ob was passiert messen wir immer ... auch wenn der Racer nicht fahren soll
|
||||||
|
abstand_vorn_cm = coderacer.abstand_messen();
|
||||||
|
|
||||||
|
// Abfragen ob der Racer fahren soll oder nicht ...
|
||||||
|
if(true == coderacer.start_stop()){
|
||||||
|
|
||||||
|
// Abstandssensor schon verstellen ... dann hat er das bis zur nächsten Messung auch geschafft
|
||||||
|
coderacer.servo_schwenk();
|
||||||
|
|
||||||
|
// Ist die Bahn frei?
|
||||||
|
if(abstand_vorn_cm < US_STOP_ABSTAND_CM){
|
||||||
|
// Nein! Der Abstand nach vorn ist kleiner als erlaubt!
|
||||||
|
// Racer anhalten
|
||||||
|
coderacer.anhalten();
|
||||||
|
// Nach links schauen!
|
||||||
|
coderacer.servo_links();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_links_cm = coderacer.abstand_messen();
|
||||||
|
// Nach rechts schauen!
|
||||||
|
coderacer.servo_rechts();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_rechts_cm = coderacer.abstand_messen();
|
||||||
|
|
||||||
|
|
||||||
|
// Ist der Abstand links oder rechts groß genug genug?
|
||||||
|
// Wenn nicht - wenn der Racer sich bisher noch nicht gedreht hat - fahre ein Stück rückwarts. Wenn der Racer sich gerade schon gedreht hat, drehe in dieselbe Richtung wie vorher.
|
||||||
|
if((abstand_links_cm < US_MIN_ABSTAND_LI_RE) && (abstand_rechts_cm < US_MIN_ABSTAND_LI_RE)){
|
||||||
|
if(anzahl_drehung == 0){
|
||||||
|
coderacer.rueckwaerts();
|
||||||
|
delay(300);
|
||||||
|
coderacer.anhalten();
|
||||||
|
//noch mal Abstand messen ...
|
||||||
|
coderacer.servo_links();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_links_cm = coderacer.abstand_messen();
|
||||||
|
// Nach rechts schauen!
|
||||||
|
coderacer.servo_rechts();
|
||||||
|
// Abstand messen und merken.
|
||||||
|
abstand_rechts_cm = coderacer.abstand_messen();
|
||||||
|
}
|
||||||
|
if( anzahl_drehung > MAX_ANZAHL_DREHUNGEN ){
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
} else {
|
||||||
|
anzahl_drehung ++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// wenn der Racer sich noch nicht gedreht hat (anzahl_drehung == 0) - oder gerade rückwärts gefahren ist (anzahl_drehung == 1) drehe jetzt dahin wo mehr Platz ist;
|
||||||
|
if(anzahl_drehung <= 1){
|
||||||
|
// Welcher Abstand ist größer?
|
||||||
|
if(abstand_links_cm > abstand_rechts_cm){
|
||||||
|
// Links ist mehr Platz!
|
||||||
|
drehung = links;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
// Rechts ist mehr Platz!
|
||||||
|
drehung = rechts;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
switch(drehung){
|
||||||
|
case links:
|
||||||
|
coderacer.links();
|
||||||
|
coderacer.servo_mitte();
|
||||||
|
break;
|
||||||
|
case rechts:
|
||||||
|
coderacer.links();
|
||||||
|
coderacer.servo_mitte();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
// Ja! Die Bahn ist frei
|
||||||
|
// Wenn die Bahn richtig frei ist, dann können wir den Zähler fürs drehen auf 0 setzen ...
|
||||||
|
if( abstand_vorn_cm > (US_STOP_ABSTAND_CM + US_MIN_ABSTAND_LI_RE)){
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
}
|
||||||
|
coderacer.vorwaerts();
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
anzahl_drehung = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
11
vsode/esp32_coderacer/test/README
Normal file
11
vsode/esp32_coderacer/test/README
Normal file
|
@ -0,0 +1,11 @@
|
||||||
|
|
||||||
|
This directory is intended for PIO Unit Testing and project tests.
|
||||||
|
|
||||||
|
Unit Testing is a software testing method by which individual units of
|
||||||
|
source code, sets of one or more MCU program modules together with associated
|
||||||
|
control data, usage procedures, and operating procedures, are tested to
|
||||||
|
determine whether they are fit for use. Unit testing finds problems early
|
||||||
|
in the development cycle.
|
||||||
|
|
||||||
|
More information about PIO Unit Testing:
|
||||||
|
- https://docs.platformio.org/page/plus/unit-testing.html
|
Loading…
Reference in a new issue