Added Fritzing parts and some code
This commit is contained in:
parent
a86aaa0c8d
commit
ad5d8228f9
7 changed files with 568 additions and 38 deletions
BIN
Fritzingparts/my_parts.fzbz
Normal file
BIN
Fritzingparts/my_parts.fzbz
Normal file
Binary file not shown.
BIN
coderacer.fzz
BIN
coderacer.fzz
Binary file not shown.
246
esp32_coderacer/esp32_coderacer.ino
Normal file
246
esp32_coderacer/esp32_coderacer.ino
Normal file
|
@ -0,0 +1,246 @@
|
|||
#include <ESP32Servo.h>
|
||||
|
||||
//----- Werte für den Servo -----
|
||||
#define SERVOPIN 16 // Pin an dem der Servomotor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define SERVO_45GRAD_LINKS 136 // Wert um den Servo 45 Grad nach links 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_0GRAD_MITTE 90 // Wert um den Servo in die Mitte zu drehen ... der kann je nach Servo anders sein
|
||||
|
||||
//----- Werte für den Ultraschallsensor -----
|
||||
#define US_TRIG 12 // Pin an dem der TRIG Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define US_ECHO 14 // Pin an dem der ECHO Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define US_STOP_ABSTAND_CM 20 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
||||
|
||||
//----- Werte für die Motoren -----
|
||||
#define MOTORRE_SPEED 2 // Pin an dem der SPEED/ENABLE Pin des rechten Motors angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORRE_FWRD 4 // Pin an dem der FORWÄRTS Pin des rechten Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORRE_BACK 0 // Pin an dem der RÜCKWÄRTS Pin des rechten Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORLI_SPEED 17 // Pin an dem der SPEED/ENABLE Pin des linken Motors angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORLI_FWRD 18 // Pin an dem der FORWÄRTS Pin des linken Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORLI_BACK 5 // Pin an dem der RÜCKWÄRTS Pin des linken Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define RACER_LINKS_MS 200 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach links zu drehen
|
||||
#define RACER_RECHTS_MS 200 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach rechts zu drehen
|
||||
|
||||
//----- Werte für die LEDs -----
|
||||
#define LED_VORWAERTS 26 // Pin an dem die VORWÄRTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define LED_STOP 25 // Pin an dem die STOP LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define LED_LINKS 27 // Pin an dem die LINKS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define LED_RECHTS 33 // Pin an dem die RECHTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
|
||||
//----- Variablen, die wir brauchen um uns Werte zu merken ----
|
||||
long abstand_vorn_cm, abstand_links_cm, abstand_rechts_cm;
|
||||
|
||||
//----- Objekte die wir haben. z.B. den Servo ----
|
||||
Servo myservo; // ein Servo-Objekt anlegen, um den Servo Motor steuern zu können
|
||||
|
||||
//---- 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.
|
||||
|
||||
// Ultraschallsensor
|
||||
pinMode(US_TRIG, OUTPUT); // Ultraschallsensor: TRIG ist ein Ausgangspin. Es wird ein Signal zum Ultraschallsensor gesendet
|
||||
pinMode(US_ECHO, INPUT); // Ultraschallsensor: ECHO ist ein Eingangspin. Es wird ein Signal vom Ultraschallsensor empfangen
|
||||
|
||||
// Servo
|
||||
myservo.attach(SERVOPIN); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist
|
||||
|
||||
// Linker Motor
|
||||
pinMode(MOTORLI_FWRD,OUTPUT); // Linker Motor FORWARD ist ein Ausgang.
|
||||
pinMode(MOTORLI_BACK,OUTPUT); // Linker Motor BACKWARD ist ein Ausgang.
|
||||
pinMode(MOTORLI_SPEED,OUTPUT); // Linker Motor SPEED ist ein Ausgang.
|
||||
digitalWrite(MOTORLI_SPEED,LOW); // Linken Motor sicherheitshalber ausschalten
|
||||
|
||||
// Rechter Motor
|
||||
pinMode(MOTORRE_FWRD,OUTPUT); // Rechter Motor FORWARD ist ein Ausgang.
|
||||
pinMode(MOTORRE_BACK,OUTPUT); // Rechter Motor BACKWARD ist ein Ausgang.
|
||||
pinMode(MOTORRE_SPEED,OUTPUT); // Rechter Motor SPEED ist ein Ausgang.
|
||||
digitalWrite(MOTORRE_SPEED,LOW); // Rechten Motor sicherheitshalber ausschalten
|
||||
|
||||
// LEDs
|
||||
pinMode(LED_VORWAERTS, OUTPUT); // LED Vorwärts ist ein Ausgang
|
||||
pinMode(LED_STOP, OUTPUT); // LED Stop ist ein Ausgang
|
||||
pinMode(LED_LINKS, OUTPUT); // LED Links ist ein Ausgang
|
||||
pinMode(LED_RECHTS, OUTPUT); // LED Rechts ist ein Ausgang
|
||||
|
||||
// alle LEDS aus
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
|
||||
// Servo am Anfang in die Mitte Stellen
|
||||
ServoMitte();
|
||||
}
|
||||
|
||||
//---- 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
|
||||
abstand_vorn_cm = AbstandMessen();
|
||||
|
||||
// Ist die Bahn frei?
|
||||
if(abstand_vorn_cm < US_STOP_ABSTAND_CM){
|
||||
// Nein! Der Abstand nach vorn ist kleiner als erlaubt!
|
||||
// Racer anhalten
|
||||
RacerAnhalten();
|
||||
// Nach links schauen!
|
||||
ServoLinks();
|
||||
// Abstand messen und merken.
|
||||
abstand_links_cm = AbstandMessen();
|
||||
// Nach rechts schauen!
|
||||
ServoRechts();
|
||||
// Abstand messen und merken.
|
||||
abstand_rechts_cm = AbstandMessen();
|
||||
|
||||
// Welcher Abstand ist größer?
|
||||
if(abstand_links_cm > abstand_rechts_cm){
|
||||
// Links ist mehr Platz!
|
||||
RacerLinks();
|
||||
}
|
||||
else{
|
||||
// Rechts ist mehr Platz!
|
||||
RacerRechts();
|
||||
}
|
||||
|
||||
// Servo am Anfang in die Mitte Stellen
|
||||
ServoMitte();
|
||||
}
|
||||
else{
|
||||
// Ja! Die Bahn ist frei
|
||||
RacerVorwaerts();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//-------------- Funktionen und Prozeduren -------------------------
|
||||
|
||||
void RacerAnhalten(void){
|
||||
Serial.println("RACER_ANHALTEN"); // Meldung am Monitor ausgeben
|
||||
// Rechten Motor abschalten
|
||||
digitalWrite(MOTORRE_FWRD, LOW);
|
||||
digitalWrite(MOTORRE_BACK, LOW);
|
||||
// Linken Motor abschalten
|
||||
digitalWrite(MOTORLI_FWRD, LOW);
|
||||
digitalWrite(MOTORLI_BACK, LOW);
|
||||
// Motoren beide ausschalten
|
||||
digitalWrite(MOTORRE_SPEED,LOW);
|
||||
digitalWrite(MOTORLI_SPEED,LOW);
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, HIGH);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
}
|
||||
|
||||
void RacerVorwaerts(void){
|
||||
Serial.println("RACER_VORWAERTS"); // Meldung am Monitor ausgeben
|
||||
// Rechten Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORRE_FWRD, HIGH);
|
||||
digitalWrite(MOTORRE_BACK, LOW);
|
||||
// Linken Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORLI_FWRD, HIGH);
|
||||
digitalWrite(MOTORLI_BACK, LOW);
|
||||
// Motoren beide anschalten
|
||||
digitalWrite(MOTORRE_SPEED, HIGH);
|
||||
digitalWrite(MOTORLI_SPEED, HIGH);
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, HIGH);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
|
||||
}
|
||||
|
||||
void RacerLinks(void){
|
||||
Serial.println("RACER_LINKS"); // Meldung am Monitor ausgeben
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, HIGH);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
// Rechten Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORRE_FWRD, HIGH);
|
||||
digitalWrite(MOTORRE_BACK, LOW);
|
||||
// Linken Motor auf rückwärts stellen
|
||||
digitalWrite(MOTORLI_FWRD, LOW);
|
||||
digitalWrite(MOTORLI_BACK, HIGH);
|
||||
// Motoren beide anschalten
|
||||
digitalWrite(MOTORRE_SPEED, HIGH);
|
||||
digitalWrite(MOTORLI_SPEED, HIGH);
|
||||
// Warten bis der RAcer sich gedreht hat
|
||||
delay(RACER_LINKS_MS);
|
||||
// Motoren wieder auschalten
|
||||
digitalWrite(MOTORRE_SPEED,LOW);
|
||||
digitalWrite(MOTORLI_SPEED,LOW);
|
||||
}
|
||||
|
||||
void RacerRechts(void){
|
||||
Serial.println("RACER_RECHTS"); // Meldung am Monitor ausgeben
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, HIGH);
|
||||
// Rechten Motor auf rückwärts stellen
|
||||
digitalWrite(MOTORRE_FWRD, LOW);
|
||||
digitalWrite(MOTORRE_BACK, HIGH);
|
||||
// Linken Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORLI_FWRD, HIGH);
|
||||
digitalWrite(MOTORLI_BACK, LOW);
|
||||
// Motoren beide anschalten
|
||||
digitalWrite(MOTORRE_SPEED, HIGH);
|
||||
digitalWrite(MOTORLI_SPEED, HIGH);
|
||||
// Warten bis der RAcer sich gedreht hat
|
||||
delay(RACER_RECHTS_MS);
|
||||
// Motoren wieder auschalten
|
||||
digitalWrite(MOTORRE_SPEED,LOW);
|
||||
digitalWrite(MOTORLI_SPEED,LOW);
|
||||
}
|
||||
|
||||
void ServoRechts(void){
|
||||
Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
|
||||
myservo.write(SERVO_45GRAD_RECHTS); // Servo auf den Winkel rechts drehen
|
||||
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
||||
}
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
long AbstandMessen(){
|
||||
long abstand_cm,echo_dauer;
|
||||
// Messung starten - ein kurzer Pulse "HIGH" wird zum TRIG pin des Ultraschallsensors geschickt
|
||||
digitalWrite(US_TRIG,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(US_TRIG,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(US_TRIG,LOW);
|
||||
|
||||
// Messung der Dauer in Mikrosekundenmeasure bis das ECHO Pin vom Ultraschallsensor HIGH wird
|
||||
echo_dauer = pulseIn(US_ECHO,HIGH);
|
||||
|
||||
// convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec
|
||||
// the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one
|
||||
// distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172
|
||||
// distance_cm = (echo_duration/2) / 29.1;
|
||||
abstand_cm = echo_dauer * 0.0172;
|
||||
|
||||
//Messwert am Monitor anzeigen
|
||||
Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist:");
|
||||
Serial.println(abstand_cm);
|
||||
|
||||
return(abstand_cm);
|
||||
}
|
||||
|
||||
|
253
esp32_coderacer/esp32_coderacer_analogWrite.ino_
Normal file
253
esp32_coderacer/esp32_coderacer_analogWrite.ino_
Normal file
|
@ -0,0 +1,253 @@
|
|||
#include <ESP32Servo.h>
|
||||
#include "esp32-hal-ledc.h"
|
||||
|
||||
//----- Werte für den Servo -----
|
||||
#define SERVOPIN 16 // Pin an dem der Servomotor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define SERVO_45GRAD_LINKS 136 // Wert um den Servo 45 Grad nach links 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_0GRAD_MITTE 90 // Wert um den Servo in die Mitte zu drehen ... der kann je nach Servo anders sein
|
||||
|
||||
//----- Werte für den Ultraschallsensor -----
|
||||
#define US_TRIG 35 // Pin an dem der TRIG Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define US_ECHO 34 // Pin an dem der ECHO Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define US_STOP_ABSTAND_CM 10 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
||||
|
||||
//----- Werte für die Motoren -----
|
||||
#define MOTORRE_SPEED 2 // Pin an dem der SPEED/ENABLE Pin des rechten Motors angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORRE_FWRD 4 // Pin an dem der FORWÄRTS Pin des rechten Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORRE_BACK 0 // Pin an dem der RÜCKWÄRTS Pin des rechten Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORRE_TEMPO 150 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255
|
||||
#define MOTORLI_SPEED 17 // Pin an dem der SPEED/ENABLE Pin des linken Motors angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORLI_FWRD 18 // Pin an dem der FORWÄRTS Pin des linken Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORLI_BACK 5 // Pin an dem der RÜCKWÄRTS Pin des linken Motors angeschlossen ist. Was vorwärts und rückwärts ist, muss probiert und vielleicht umgesteckt werden.'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define MOTORLI_TEMPO 150 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255
|
||||
#define RACER_LINKS_MS 500 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach links zu drehen
|
||||
#define RACER_RECHTS_MS 500 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach rechts zu drehen
|
||||
|
||||
//----- Werte für die LEDs -----
|
||||
#define LED_VORWAERTS 26 // Pin an dem die VORWÄRTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define LED_STOP 25 // Pin an dem die STOP LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define LED_LINKS 27 // Pin an dem die LINKS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define LED_RECHTS 33 // Pin an dem die RECHTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
|
||||
//----- Variablen, die wir brauchen um uns Werte zu merken ----
|
||||
long abstand_vorn_cm, abstand_links_cm, abstand_rechts_cm;
|
||||
|
||||
//----- Objekte die wir haben. z.B. den Servo ----
|
||||
Servo myservo; // ein Servo-Objekt anlegen, um den Servo Motor steuern zu können
|
||||
|
||||
//---- 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.
|
||||
|
||||
// Ultraschallsensor
|
||||
pinMode(US_TRIG, OUTPUT); // Ultraschallsensor: TRIG ist ein Ausgangspin. Es wird ein Signal zum Ultraschallsensor gesendet
|
||||
pinMode(US_ECHO, INPUT); // Ultraschallsensor: ECHO ist ein Eingangspin. Es wird ein Signal vom Ultraschallsensor empfangen
|
||||
|
||||
// Servo
|
||||
myservo.attach(SERVOPIN); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist
|
||||
|
||||
// Linker Motor
|
||||
pinMode(MOTORLI_FWRD,OUTPUT); // Linker Motor FORWARD ist ein Ausgang.
|
||||
pinMode(MOTORLI_BACK,OUTPUT); // Linker Motor BACKWARD ist ein Ausgang.
|
||||
ledcSetup(15, 5000, 8); // channel 1, 50 Hz, 8-bit width
|
||||
ledcAttachPin(MOTORLI_SPEED, 1); // Linker Motor SPEED mit Kanal 1 verbunden
|
||||
analogWrite(MOTORLI_SPEED, 0); // Linken Motor sicherheitshalber ausschalten :-)
|
||||
|
||||
// Rechter Motor
|
||||
pinMode(MOTORRE_FWRD,OUTPUT); // Rechter Motor FORWARD ist ein Ausgang.
|
||||
pinMode(MOTORRE_BACK,OUTPUT); // Rechter Motor BACKWARD ist ein Ausgang.
|
||||
ledcSetup(14, 5000, 8); // channel 2, 50 Hz, 8-bit width
|
||||
ledcAttachPin(MOTORRE_SPEED, 2); // Rechter Motor SPEED mit Kanal 2 verbunden
|
||||
analogWrite(MOTORRE_SPEED, 0); // Rechten Motor sicherheitshalber ausschalten :-)
|
||||
|
||||
pinMode(MOTORRE_SPEED,OUTPUT); // Rechter Motor SPEED ist ein Ausgang.
|
||||
digitalWrite(MOTORRE_SPEED, 0); // Rechten Motor sicherheitshalber ausschalten :-)
|
||||
|
||||
// LEDs
|
||||
pinMode(LED_VORWAERTS, OUTPUT); // LED Vorwärts ist ein Ausgang
|
||||
pinMode(LED_STOP, OUTPUT); // LED Stop ist ein Ausgang
|
||||
pinMode(LED_LINKS, OUTPUT); // LED Links ist ein Ausgang
|
||||
pinMode(LED_RECHTS, OUTPUT); // LED Rechts ist ein Ausgang
|
||||
|
||||
// alle LEDS aus
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
}
|
||||
|
||||
//---- 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() {
|
||||
|
||||
// Servo in die Mitte Stellen
|
||||
ServoMitte();
|
||||
|
||||
// Abstand messen -> nach vorn
|
||||
abstand_vorn_cm = AbstandMessen();
|
||||
|
||||
// Ist die Bahn frei?
|
||||
if(abstand_vorn_cm < US_STOP_ABSTAND_CM){
|
||||
// Nein! Der Abstand nach vorn ist kleiner als erlaubt!
|
||||
// Racer anhalten
|
||||
RacerAnhalten();
|
||||
// Nach links schauen!
|
||||
ServoLinks();
|
||||
// Abstand messen und merken.
|
||||
abstand_links_cm = AbstandMessen();
|
||||
// Nach rechts schauen!
|
||||
ServoRechts();
|
||||
// Abstand messen und merken.
|
||||
abstand_rechts_cm = AbstandMessen();
|
||||
|
||||
// Welcher Abstand ist größer?
|
||||
if(abstand_links_cm > abstand_rechts_cm){
|
||||
// Links ist mehr Platz!
|
||||
RacerLinks();
|
||||
}
|
||||
else{
|
||||
// Rechts ist mehr Platz!
|
||||
RacerRechts();
|
||||
}
|
||||
}
|
||||
else{
|
||||
// Ja! Die Bahn ist frei
|
||||
RacerVorwaerts();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//-------------- Funktionen und Prozeduren -------------------------
|
||||
|
||||
void RacerAnhalten(void){
|
||||
Serial.println("RACER_ANHALTEN"); // Meldung am Monitor ausgeben
|
||||
// Rechten Motor abschalten
|
||||
digitalWrite(MOTORRE_FWRD, LOW);
|
||||
digitalWrite(MOTORRE_BACK, LOW);
|
||||
// Linken Motor abschalten
|
||||
digitalWrite(MOTORLI_FWRD, LOW);
|
||||
digitalWrite(MOTORLI_BACK, LOW);
|
||||
// Motoren beide ausschalten
|
||||
analogWrite(MOTORRE_SPEED, 0);
|
||||
analogWrite(MOTORLI_SPEED, 0);
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, HIGH);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
}
|
||||
|
||||
void RacerVorwaerts(void){
|
||||
Serial.println("RACER_VORWAERTS"); // Meldung am Monitor ausgeben
|
||||
// Rechten Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORRE_FWRD, HIGH);
|
||||
digitalWrite(MOTORRE_BACK, LOW);
|
||||
// Linken Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORLI_FWRD, HIGH);
|
||||
digitalWrite(MOTORLI_BACK, LOW);
|
||||
// Motoren beide anschalten
|
||||
analogWrite(MOTORRE_SPEED, MOTORRE_TEMPO);
|
||||
analogWrite(MOTORLI_SPEED, MOTORLI_TEMPO);
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, HIGH);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
|
||||
}
|
||||
|
||||
void RacerLinks(void){
|
||||
Serial.println("RACER_LINKS"); // Meldung am Monitor ausgeben
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, HIGH);
|
||||
digitalWrite(LED_RECHTS, LOW);
|
||||
// Rechten Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORRE_FWRD, HIGH);
|
||||
digitalWrite(MOTORRE_BACK, LOW);
|
||||
// Linken Motor auf rückwärts stellen
|
||||
digitalWrite(MOTORLI_FWRD, LOW);
|
||||
digitalWrite(MOTORLI_BACK, HIGH);
|
||||
// Motoren beide anschalten
|
||||
analogWrite(MOTORRE_SPEED, MOTORRE_TEMPO);
|
||||
analogWrite(MOTORLI_SPEED, MOTORLI_TEMPO);
|
||||
// Warten bis der RAcer sich gedreht hat
|
||||
delay(RACER_LINKS_MS);
|
||||
// Motoren wieder auschalten
|
||||
analogWrite(MOTORRE_SPEED, 0);
|
||||
analogWrite(MOTORLI_SPEED, 0);
|
||||
}
|
||||
|
||||
void RacerRechts(void){
|
||||
Serial.println("RACER_RECHTS"); // Meldung am Monitor ausgeben
|
||||
// LEDs setzen
|
||||
digitalWrite(LED_VORWAERTS, LOW);
|
||||
digitalWrite(LED_STOP, LOW);
|
||||
digitalWrite(LED_LINKS, LOW);
|
||||
digitalWrite(LED_RECHTS, HIGH);
|
||||
// Rechten Motor auf rückwärts stellen
|
||||
digitalWrite(MOTORRE_FWRD, LOW);
|
||||
digitalWrite(MOTORRE_BACK, HIGH);
|
||||
// Linken Motor auf vorwärts stellen
|
||||
digitalWrite(MOTORLI_FWRD, HIGH);
|
||||
digitalWrite(MOTORLI_BACK, LOW);
|
||||
// Motoren beide anschalten
|
||||
analogWrite(MOTORRE_SPEED, MOTORRE_TEMPO);
|
||||
analogWrite(MOTORLI_SPEED, MOTORLI_TEMPO);
|
||||
// Warten bis der RAcer sich gedreht hat
|
||||
delay(RACER_RECHTS_MS);
|
||||
// Motoren wieder auschalten
|
||||
analogWrite(MOTORRE_SPEED, 0);
|
||||
analogWrite(MOTORLI_SPEED, 0);
|
||||
}
|
||||
|
||||
void ServoRechts(void){
|
||||
Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
|
||||
myservo.write(SERVO_45GRAD_RECHTS); // Servo auf den Winkel rechts drehen
|
||||
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
||||
}
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
long AbstandMessen(){
|
||||
long abstand_cm,echo_dauer;
|
||||
// Messung starten - ein kurzer Pulse "HIGH" wird zum TRIG pin des Ultraschallsensors geschickt
|
||||
digitalWrite(US_TRIG,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(US_TRIG,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(US_TRIG,LOW);
|
||||
|
||||
// Messung der Dauer in Mikrosekundenmeasure bis das ECHO Pin vom Ultraschallsensor HIGH wird
|
||||
pinMode(US_ECHO,INPUT);
|
||||
echo_dauer = pulseIn(US_ECHO,HIGH);
|
||||
|
||||
// convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec
|
||||
// the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one
|
||||
// distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172
|
||||
// distance_cm = (echo_duration/2) / 29.1;
|
||||
abstand_cm = echo_dauer * 0.0172;
|
||||
|
||||
//Messwert am Monitor anzeigen
|
||||
Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist:");
|
||||
Serial.println(abstand_cm);
|
||||
|
||||
return(abstand_cm);
|
||||
}
|
||||
|
||||
void analogWrite(uint8_t pin, uint8_t speed){
|
||||
ledcWrite(1, speed);
|
||||
}
|
||||
|
|
@ -1,24 +1,44 @@
|
|||
#include <ESP32Servo.h>
|
||||
|
||||
Servo myservo; // create servo object to control a servo
|
||||
int servo_angle = 0; // variable to store the servo position
|
||||
#define SERVOPIN 14 // Recommended PWM GPIO pins on the ESP32 include 2,4,12-19,21-23,25-27,32-33
|
||||
#define SERVOPIN 16 // Pin an dem der Servomotor angeschlossen ist. 'GPIO' muss man weglassen -> also nicht GPIO88 sondern nur 88.
|
||||
#define SERVO_45GRAD_LINKS 136 // Wert um den Servo 45 Grad nach links 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_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
|
||||
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
myservo.attach(SERVOPIN); // attaches the servo on pin 18 to the servo object
|
||||
// using default min/max of 1000us and 2000us
|
||||
// different servos may require different min/max settings
|
||||
// for an accurate 0 to 180 sweep
|
||||
|
||||
Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
||||
|
||||
myservo.attach(SERVOPIN); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist
|
||||
}
|
||||
|
||||
void loop() {
|
||||
for (servo_angle = 0; servo_angle <= 180; servo_angle += 10) { // goes from 0 degrees to 180 degrees in steps of 1 degree
|
||||
myservo.write(servo_angle); // tell servo to go to position in variable 'pos'
|
||||
delay(50); // waits 15ms for the servo to reach the position
|
||||
}
|
||||
for (servo_angle = 180; servo_angle >= 0; servo_angle -= 10) { // goes from 180 degrees to 0 degrees
|
||||
myservo.write(servo_angle); // tell servo to go to position in variable 'pos'
|
||||
delay(50); // waits 15ms for the servo to reach the position
|
||||
}
|
||||
ServoMitte();
|
||||
ServoRechts();
|
||||
ServoMitte();
|
||||
ServoLinks();
|
||||
}
|
||||
|
||||
|
||||
//-------------- Funktionen und Prozeduren -------------------------
|
||||
|
||||
void ServoRechts(void){
|
||||
Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
|
||||
myservo.write(SERVO_45GRAD_RECHTS); // Servo auf den Winkel rechts drehen
|
||||
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
||||
}
|
||||
|
||||
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
|
||||
}
|
||||
|
||||
|
|
|
@ -2,14 +2,14 @@
|
|||
|
||||
Servo myservo; // create servo object to control a servo
|
||||
int servo_angle = 0; // variable to store the servo position
|
||||
#define SERVOPIN 14 // Recommended PWM GPIO pins on the ESP32 include 2,4,12-19,21-23,25-27,32-33
|
||||
#define SERVOPIN 16 // Recommended PWM GPIO pins on the ESP32 include 2,4,12-19,21-23,25-27,32-33
|
||||
#define SERVO_LEFT 45
|
||||
#define SERVO_RIGHT 135
|
||||
#define SERVO_FORWARD 90
|
||||
|
||||
|
||||
#define US_TRIG 13
|
||||
#define US_ECHO 12
|
||||
#define US_TRIG 12
|
||||
#define US_ECHO 14
|
||||
#define US_STOP_DISTANCE 10
|
||||
long distance_forward_cm,distance_left_cm,distance_right_cm;
|
||||
|
||||
|
|
|
@ -1,39 +1,50 @@
|
|||
#define US_TRIG 13
|
||||
#define US_ECHO 12
|
||||
//----- Werte für den Ultraschallsensor -----
|
||||
#define US_TRIG 12 // Pin an dem der TRIG Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
#define US_ECHO 14 // Pin an dem der ECHO Pin des Ultraschallsensor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||
|
||||
long distance_cm, echo_duration;
|
||||
long abstand_cm, echo_dauer;
|
||||
|
||||
void setup() {
|
||||
//Serial port
|
||||
Serial.begin(115200);
|
||||
// Monitor
|
||||
Serial.begin(115200); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
|
||||
|
||||
//Ultra sonic pins
|
||||
pinMode(US_TRIG, OUTPUT);
|
||||
pinMode(US_ECHO, INPUT);
|
||||
// Ultraschallsensor
|
||||
pinMode(US_TRIG, OUTPUT); // Ultraschallsensor: TRIG ist ein Ausgangspin. Es wird ein Signal zum Ultraschallsensor gesendet
|
||||
pinMode(US_ECHO, INPUT); // Ultraschallsensor: ECHO ist ein Eingangspin. Es wird ein Signal vom Ultraschallsensor empfangen
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// start measurment by a short high pulse of 10 microseconds length at the trig pin ...
|
||||
|
||||
AbstandMessen();
|
||||
|
||||
}
|
||||
|
||||
//-------------- Funktionen und Prozeduren -------------------------
|
||||
|
||||
long AbstandMessen(void){
|
||||
long abstand_cm,echo_dauer;
|
||||
// Messung starten - ein kurzer Pulse "HIGH" wird zum TRIG pin des Ultraschallsensors geschickt
|
||||
digitalWrite(US_TRIG,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(US_TRIG,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(US_TRIG,LOW);
|
||||
|
||||
// measure the duration in microseconds of the echo pin HIGH - this is the time the echo needs to be back at the sensor
|
||||
pinMode(US_ECHO,INPUT);
|
||||
echo_duration = pulseIn(US_ECHO,HIGH);
|
||||
// Messung der Dauer in Mikrosekundenmeasure bis das ECHO Pin vom Ultraschallsensor HIGH wird
|
||||
echo_dauer = pulseIn(US_ECHO,HIGH);
|
||||
|
||||
// convert into cm ... 344m/sec is the speed of noise - thus 34400cm/sec ... or 34,400cm/milisec ... or 0,0344cm/microsec
|
||||
// the echo has to go the distance twice - forth and back - so the duration has to be the half of the measured one
|
||||
// distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1
|
||||
distance_cm = (echo_duration/2) / 29.1;
|
||||
// distance_cm = echo_duration/2 * 0,0344 or distance_cm = echo_duration/2 / 29,1 or distance_cm = echo_duration * 0,0172
|
||||
// distance_cm = (echo_duration/2) / 29.1;
|
||||
abstand_cm = echo_dauer * 0.0172;
|
||||
|
||||
//print this result at the screen
|
||||
Serial.print("Distance in cm: ");
|
||||
Serial.println(distance_cm);
|
||||
//Messwert am Monitor anzeigen
|
||||
Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist:");
|
||||
Serial.println(abstand_cm);
|
||||
|
||||
//wait before next measurement
|
||||
delay(250); //ms
|
||||
//Kurz warten, bevor evetuell wieder eine Messung startet
|
||||
delay(250);
|
||||
|
||||
return(abstand_cm);
|
||||
}
|
||||
|
|
Loading…
Reference in a new issue