added library example - removed old stuff
This commit is contained in:
parent
a8d9d4ac85
commit
a1470a2b21
8 changed files with 546 additions and 3 deletions
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
393
libraries/CodeRacer/CodeRacer.cpp
Normal file
393
libraries/CodeRacer/CodeRacer.cpp
Normal file
|
@ -0,0 +1,393 @@
|
||||||
|
// the compiler switch for an ESP8266 is looking like this: #elif defined(ARDUINO_ARCH_ESP8266)
|
||||||
|
|
||||||
|
#include "CodeRacer.h"
|
||||||
|
|
||||||
|
//Konstruktor ohne Pins ... alle Vorgaben kommen aus dem CodeRacer.h Header file
|
||||||
|
CodeRacer::CodeRacer()
|
||||||
|
{
|
||||||
|
_taster_pin = H_TASTERPIN;
|
||||||
|
_servopin = H_SERVOPIN;
|
||||||
|
_us_trigger_pin = H_US_TRIG;
|
||||||
|
_us_echo_pin = H_US_ECHO;
|
||||||
|
_motor_links_frwd_pin = H_MOTORLI_FWRD;
|
||||||
|
_motor_links_back_pin = H_MOTORLI_BACK;
|
||||||
|
_motor_links_enable_pin = H_MOTORLI_SPEED;
|
||||||
|
_motor_rechts_frwd_pin = H_MOTORRE_FWRD;
|
||||||
|
_motor_rechts_back_pin = H_MOTORRE_BACK;
|
||||||
|
_motor_rechts_enable_pin = H_MOTORRE_SPEED;
|
||||||
|
_led_frwd_pin = H_LED_VORWAERTS;
|
||||||
|
_led_stop_pin = H_LED_STOP;
|
||||||
|
_led_links_pin = H_LED_LINKS;
|
||||||
|
_led_rechts_pin = H_LED_RECHTS;
|
||||||
|
|
||||||
|
_servo_dummy = new Servo();
|
||||||
|
_servo = new Servo();
|
||||||
|
|
||||||
|
_servo_mitte = H_SERVO_MITTE;
|
||||||
|
_servo_links = H_SERVO_LINKS;
|
||||||
|
_servo_rechts = H_SERVO_RECHTS;
|
||||||
|
_schwenk_links = H_SERVO_SCHWENK_LINKS;
|
||||||
|
_schwenk_rechts = H_SERVO_SCHWENK_RECHTS;
|
||||||
|
|
||||||
|
_schwenk_position = _servo_mitte;
|
||||||
|
_schwenk_richtung = SERVO_SCHWENK_LI;
|
||||||
|
_schwenk_millis = millis();
|
||||||
|
|
||||||
|
_motor_links_tempo = H_MOTORLI_TEMPO;
|
||||||
|
_motor_rechts_tempo = H_MOTORRE_TEMPO;
|
||||||
|
_drehung_links_ms = H_RACER_LINKS_MS;
|
||||||
|
_drehung_rechts_ms = H_RACER_RECHTS_MS;
|
||||||
|
|
||||||
|
coderracer_activ = false;
|
||||||
|
_coderracer_activ = true;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Konstruktor mit pin Übergaben ...
|
||||||
|
|
||||||
|
CodeRacer::CodeRacer(int tasterpin , int servopin,
|
||||||
|
int us_trigger_pin, int us_echo_pin,
|
||||||
|
int motor_links_frwd_pin, int motor_links_back_pin, int motor_links_enable_pin,
|
||||||
|
int motor_rechts_frwd_pin, int motor_rechts_back_pin, int motor_rechts_enable_pin,
|
||||||
|
int led_frwd, int led_stop, int led_links, int led_rechts
|
||||||
|
)
|
||||||
|
{
|
||||||
|
_taster_pin = tasterpin;
|
||||||
|
_servopin = servopin;
|
||||||
|
_us_trigger_pin = us_trigger_pin;
|
||||||
|
_us_echo_pin = us_echo_pin;
|
||||||
|
_motor_links_frwd_pin = motor_links_frwd_pin;
|
||||||
|
_motor_links_back_pin = motor_links_back_pin;
|
||||||
|
_motor_links_enable_pin = motor_links_enable_pin;
|
||||||
|
_motor_rechts_frwd_pin = motor_rechts_frwd_pin;
|
||||||
|
_motor_rechts_back_pin = motor_rechts_back_pin;
|
||||||
|
_motor_rechts_enable_pin = motor_rechts_enable_pin;
|
||||||
|
_led_frwd_pin = led_frwd;
|
||||||
|
_led_stop_pin = led_stop;
|
||||||
|
_led_links_pin = led_links;
|
||||||
|
_led_rechts_pin = led_rechts;
|
||||||
|
|
||||||
|
_servo_dummy = new Servo();
|
||||||
|
_servo = new Servo();
|
||||||
|
|
||||||
|
_servo_mitte = H_SERVO_MITTE;
|
||||||
|
_servo_links = H_SERVO_LINKS;
|
||||||
|
_servo_rechts = H_SERVO_RECHTS;
|
||||||
|
_schwenk_links = H_SERVO_SCHWENK_LINKS;
|
||||||
|
_schwenk_rechts = H_SERVO_SCHWENK_RECHTS;
|
||||||
|
|
||||||
|
_schwenk_position = _servo_mitte;
|
||||||
|
_schwenk_richtung = SERVO_SCHWENK_LI;
|
||||||
|
_schwenk_millis = millis();
|
||||||
|
|
||||||
|
_motor_links_tempo = H_MOTORLI_TEMPO;
|
||||||
|
_motor_rechts_tempo = H_MOTORRE_TEMPO;
|
||||||
|
_drehung_links_ms = H_RACER_LINKS_MS;
|
||||||
|
_drehung_rechts_ms = H_RACER_RECHTS_MS;
|
||||||
|
|
||||||
|
coderracer_activ = false;
|
||||||
|
_coderracer_activ = true;
|
||||||
|
_drive_forward = false;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void CodeRacer::begin() {
|
||||||
|
|
||||||
|
// Ultraschallsensor
|
||||||
|
pinMode(_us_trigger_pin, OUTPUT); // Ultraschallsensor: TRIG ist ein Ausgangspin. Es wird ein Signal zum Ultraschallsensor gesendet
|
||||||
|
pinMode(_us_echo_pin, INPUT); // Ultraschallsensor: ECHO ist ein Eingangspin. Es wird ein Signal vom Ultraschallsensor empfangen
|
||||||
|
|
||||||
|
// Servo
|
||||||
|
_servo->attach(_servopin); // dem Servo Objekt "sagen" an welchen Pin am Schaltkreis der Server angeschlossen ist
|
||||||
|
|
||||||
|
// Linker Motor
|
||||||
|
pinMode(_motor_links_frwd_pin, OUTPUT); // Linker Motor FORWARD ist ein Ausgang.
|
||||||
|
pinMode(_motor_links_back_pin, OUTPUT); // Linker Motor BACKWARD ist ein Ausgang.
|
||||||
|
ledcSetup(MOTORPWM_LINKS, 5000, 8); // channel 1, 50 Hz, 8-bit width
|
||||||
|
ledcAttachPin(_motor_links_enable_pin, MOTORPWM_LINKS); // Linker Motor SPEED mit Kanal 1 verbunden
|
||||||
|
analog_write(_motor_links_enable_pin, 0); // Linken Motor sicherheitshalber ausschalten :-)
|
||||||
|
|
||||||
|
// Rechter Motor
|
||||||
|
pinMode(_motor_rechts_frwd_pin, OUTPUT); // Rechter Motor FORWARD ist ein Ausgang.
|
||||||
|
pinMode(_motor_rechts_back_pin, OUTPUT); // Rechter Motor BACKWARD ist ein Ausgang.
|
||||||
|
ledcSetup(MOTORPWM_RECHTS, 5000, 8); // channel 2, 50 Hz, 8-bit width
|
||||||
|
ledcAttachPin(_motor_rechts_enable_pin, MOTORPWM_RECHTS); // Rechter Motor SPEED mit Kanal 2 verbunden
|
||||||
|
analog_write(_motor_rechts_enable_pin, 0); // Rechten Motor sicherheitshalber ausschalten :-)
|
||||||
|
|
||||||
|
// LEDs
|
||||||
|
pinMode(_led_frwd_pin, OUTPUT); // LED Vorwärts ist ein Ausgang
|
||||||
|
pinMode(_led_stop_pin, OUTPUT); // LED Stop ist ein Ausgang
|
||||||
|
pinMode(_led_links_pin, OUTPUT); // LED Links ist ein Ausgang
|
||||||
|
pinMode(_led_rechts_pin, OUTPUT); // LED Rechts ist ein Ausgang
|
||||||
|
// alle LEDS aus
|
||||||
|
digitalWrite(_led_frwd_pin, LOW);
|
||||||
|
digitalWrite(_led_stop_pin, LOW);
|
||||||
|
digitalWrite(_led_links_pin, LOW);
|
||||||
|
digitalWrite(_led_rechts_pin, LOW);
|
||||||
|
|
||||||
|
// Taster
|
||||||
|
taster_last_pressed_ms = 0;
|
||||||
|
pinMode(_taster_pin, INPUT_PULLUP);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(_taster_pin), set_taster_state, FALLING);
|
||||||
|
|
||||||
|
Serial.println("CodeRacer initialisiert ... ");
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::servo_einstellungen(int winkel_mitte, int winkel_links, int winkel_rechts, int schwenk_links, int schwenk_rechts)
|
||||||
|
{
|
||||||
|
_servo_mitte = winkel_mitte;
|
||||||
|
_servo_links = winkel_links;
|
||||||
|
_servo_rechts = winkel_rechts;
|
||||||
|
_schwenk_links = schwenk_links;
|
||||||
|
_schwenk_rechts = schwenk_rechts;
|
||||||
|
|
||||||
|
_schwenk_position = _servo_mitte;
|
||||||
|
_schwenk_richtung = SERVO_SCHWENK_LI;
|
||||||
|
_schwenk_millis = millis();
|
||||||
|
|
||||||
|
Serial.println("CodeRacer Servo eingestellt ... ");
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::motor_einstellungen(int motor_links_tempo, int motor_rechts_tempo, int drehung_links_ms, int drehung_rechts_ms)
|
||||||
|
{
|
||||||
|
_motor_links_tempo = motor_links_tempo;
|
||||||
|
_motor_rechts_tempo = motor_rechts_tempo;
|
||||||
|
_drehung_links_ms = drehung_links_ms;
|
||||||
|
_drehung_rechts_ms = drehung_rechts_ms;
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::analog_write(int pin, int speed) {
|
||||||
|
if (pin == _motor_links_enable_pin) { ledcWrite(MOTORPWM_LINKS, speed); }
|
||||||
|
if (pin == _motor_rechts_enable_pin) { ledcWrite(MOTORPWM_RECHTS, speed); }
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::anhalten() {
|
||||||
|
Serial.println("RACER_ANHALTEN"); // Meldung am Monitor ausgeben
|
||||||
|
_drive_forward = false;
|
||||||
|
//Rechten Motor abschalten
|
||||||
|
digitalWrite(_motor_rechts_frwd_pin, LOW);
|
||||||
|
digitalWrite(_motor_rechts_back_pin, LOW);
|
||||||
|
// Linken Motor abschalten
|
||||||
|
digitalWrite(_motor_links_frwd_pin, LOW);
|
||||||
|
digitalWrite(_motor_links_back_pin, LOW);
|
||||||
|
// Motoren beide ausschalten
|
||||||
|
analog_write(_motor_rechts_enable_pin, 0);
|
||||||
|
analog_write(_motor_links_enable_pin, 0);
|
||||||
|
// LEDs setzen
|
||||||
|
digitalWrite(_led_frwd_pin, LOW);
|
||||||
|
digitalWrite(_led_stop_pin, HIGH);
|
||||||
|
digitalWrite(_led_links_pin, LOW);
|
||||||
|
digitalWrite(_led_rechts_pin, LOW);
|
||||||
|
delay(1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void CodeRacer::normal_tempo()
|
||||||
|
{
|
||||||
|
//Serial.println("RACER_NORMAL_TEMPO"); // Meldung am Monitor ausgeben
|
||||||
|
analog_write(_motor_rechts_enable_pin, _motor_rechts_tempo);
|
||||||
|
analog_write(_motor_links_enable_pin, _motor_links_tempo);
|
||||||
|
_drive_forward = true;
|
||||||
|
_drive_normal_forward = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::vorwaerts()
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial.println("RACER_VORWAERTS"); // Meldung am Monitor ausgeben
|
||||||
|
|
||||||
|
if (false == _drive_forward) {
|
||||||
|
// Rechten Motor auf vorwärts stellen
|
||||||
|
digitalWrite(_motor_rechts_frwd_pin, HIGH);
|
||||||
|
digitalWrite(_motor_rechts_back_pin, LOW);
|
||||||
|
// Linken Motor auf vorwärts stellen
|
||||||
|
digitalWrite(_motor_links_frwd_pin, HIGH);
|
||||||
|
digitalWrite(_motor_links_back_pin, LOW);
|
||||||
|
// Motoren beide anschalten
|
||||||
|
analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO);
|
||||||
|
analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO);
|
||||||
|
// LEDs setzen
|
||||||
|
digitalWrite(_led_frwd_pin, HIGH);
|
||||||
|
digitalWrite(_led_stop_pin, LOW);
|
||||||
|
digitalWrite(_led_links_pin, LOW);
|
||||||
|
digitalWrite(_led_rechts_pin, LOW);
|
||||||
|
|
||||||
|
_drive_forward = true;
|
||||||
|
_drive_normal_forward = false;
|
||||||
|
_drive_forward_ms = millis();
|
||||||
|
|
||||||
|
} else {
|
||||||
|
if (false == _drive_normal_forward) {
|
||||||
|
if ((millis() - _drive_forward_ms) > MOTOR_MAX_SPEED_START_MS) {
|
||||||
|
normal_tempo();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::links()
|
||||||
|
{
|
||||||
|
Serial.println("RACER_LINKS"); // Meldung am Monitor ausgeben
|
||||||
|
_drive_forward = false;
|
||||||
|
// LEDs setzen
|
||||||
|
digitalWrite(_led_frwd_pin, LOW);
|
||||||
|
digitalWrite(_led_stop_pin, LOW);
|
||||||
|
digitalWrite(_led_links_pin, HIGH);
|
||||||
|
digitalWrite(_led_rechts_pin, LOW);
|
||||||
|
// Rechten Motor auf vorwärts stellen
|
||||||
|
digitalWrite(_motor_rechts_frwd_pin, HIGH);
|
||||||
|
digitalWrite(_motor_rechts_back_pin, LOW);
|
||||||
|
// Linken Motor auf rückwärts stellen
|
||||||
|
digitalWrite(_motor_links_frwd_pin, LOW);
|
||||||
|
digitalWrite(_motor_links_back_pin, HIGH);
|
||||||
|
// Motoren beide anschalten
|
||||||
|
analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO);
|
||||||
|
analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO);
|
||||||
|
// Warten bis der RAcer sich gedreht hat
|
||||||
|
delay(_drehung_links_ms);
|
||||||
|
// Motoren wieder auschalten
|
||||||
|
analog_write(_motor_rechts_enable_pin, 0);
|
||||||
|
analog_write(_motor_links_enable_pin, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::rechts()
|
||||||
|
{
|
||||||
|
Serial.println("RACER_RECHTS"); // Meldung am Monitor ausgeben
|
||||||
|
_drive_forward = false;
|
||||||
|
// LEDs setzen
|
||||||
|
digitalWrite(_led_frwd_pin, LOW);
|
||||||
|
digitalWrite(_led_stop_pin, LOW);
|
||||||
|
digitalWrite(_led_links_pin, LOW);
|
||||||
|
digitalWrite(_led_rechts_pin, HIGH);
|
||||||
|
// Rechten Motor auf rückwärts stellen
|
||||||
|
digitalWrite(_motor_rechts_frwd_pin, LOW);
|
||||||
|
digitalWrite(_motor_rechts_back_pin, HIGH);
|
||||||
|
// Linken Motor auf vorwärts stellen
|
||||||
|
digitalWrite(_motor_links_frwd_pin, HIGH);
|
||||||
|
digitalWrite(_motor_links_back_pin, LOW);
|
||||||
|
// Motoren beide anschalten
|
||||||
|
analog_write(_motor_rechts_enable_pin, MOTORRE_MAX_TEMPO);
|
||||||
|
analog_write(_motor_links_enable_pin, MOTORLI_MAX_TEMPO);
|
||||||
|
// Warten bis der RAcer sich gedreht hat
|
||||||
|
delay(_drehung_rechts_ms);
|
||||||
|
// Motoren wieder auschalten
|
||||||
|
analog_write(_motor_rechts_enable_pin, 0);
|
||||||
|
analog_write(_motor_links_enable_pin, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::servo_rechts()
|
||||||
|
{
|
||||||
|
Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben
|
||||||
|
_servo->write(_servo_rechts); // Servo auf den Winkel rechts drehen
|
||||||
|
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::servo_links()
|
||||||
|
{
|
||||||
|
Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben
|
||||||
|
_servo->write(_servo_links); // Servo auf den Winkel links drehen
|
||||||
|
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::servo_mitte()
|
||||||
|
{
|
||||||
|
Serial.println("SERVO_MITTE"); // Meldung am Monitor ausgeben
|
||||||
|
_servo->write(_servo_mitte); // Servo auf den Winkel links drehen
|
||||||
|
_schwenk_position = _servo_mitte; // Servo schaut direkt nach vorn
|
||||||
|
_schwenk_millis = millis();
|
||||||
|
delay(1000); // Kurz warten, dass der Servo die Stellung erreicht
|
||||||
|
}
|
||||||
|
|
||||||
|
void CodeRacer::servo_schwenk()
|
||||||
|
{
|
||||||
|
if (millis() - _schwenk_millis > SERVO_SCHWENK_MS) {
|
||||||
|
_schwenk_position = _schwenk_position + _schwenk_richtung;
|
||||||
|
if (_schwenk_position >= _schwenk_links) {
|
||||||
|
_schwenk_position = _schwenk_links;
|
||||||
|
_schwenk_richtung = SERVO_SCHWENK_RE;
|
||||||
|
}
|
||||||
|
if (_schwenk_position <= _schwenk_rechts) {
|
||||||
|
_schwenk_position = _schwenk_rechts;
|
||||||
|
_schwenk_richtung = SERVO_SCHWENK_LI;
|
||||||
|
}
|
||||||
|
_servo->write(_schwenk_position); // Servo auf den Winkel links drehen
|
||||||
|
_schwenk_millis = millis();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
long CodeRacer::abstand_messen()
|
||||||
|
{
|
||||||
|
long abstand_cm;
|
||||||
|
long single_echo_dauer_us;
|
||||||
|
long long echo_dauer_us;
|
||||||
|
int messnr = 0;
|
||||||
|
|
||||||
|
echo_dauer_us = 0;
|
||||||
|
do{
|
||||||
|
// Messung starten - ein kurzer Pulse "HIGH" wird zum TRIG pin des Ultraschallsensors geschickt
|
||||||
|
pinMode(_us_echo_pin, OUTPUT);
|
||||||
|
pinMode(_us_echo_pin, INPUT);
|
||||||
|
digitalWrite(_us_trigger_pin, LOW);
|
||||||
|
delayMicroseconds(2);
|
||||||
|
digitalWrite(_us_trigger_pin, HIGH);
|
||||||
|
delayMicroseconds(10);
|
||||||
|
digitalWrite(_us_trigger_pin, LOW);
|
||||||
|
|
||||||
|
// Messung der Dauer in Mikrosekundenmeasure bis das ECHO Pin vom Ultraschallsensor HIGH wird
|
||||||
|
single_echo_dauer_us = pulseIn(_us_echo_pin, HIGH, US_MAX_ECHO_TIME_US);
|
||||||
|
if (single_echo_dauer_us == 0) {
|
||||||
|
echo_dauer_us = echo_dauer_us + US_MAX_ECHO_TIME_US;
|
||||||
|
messnr++;
|
||||||
|
} else {
|
||||||
|
if (single_echo_dauer_us > 200) {
|
||||||
|
echo_dauer_us = echo_dauer_us + single_echo_dauer_us;
|
||||||
|
messnr++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} while (messnr < 1);
|
||||||
|
//echo_dauer_us = echo_dauer_us >> 4;
|
||||||
|
// 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_us * 0.0172;
|
||||||
|
|
||||||
|
//Messwert am Monitor anzeigen
|
||||||
|
Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):");
|
||||||
|
Serial.println(abstand_cm);
|
||||||
|
|
||||||
|
return(abstand_cm);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool CodeRacer::start_stop() {
|
||||||
|
if (_coderracer_activ != coderracer_activ) {
|
||||||
|
_coderracer_activ = coderracer_activ;
|
||||||
|
if (true == _coderracer_activ) {
|
||||||
|
digitalWrite(_led_stop_pin, LOW);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
anhalten();
|
||||||
|
servo_mitte();
|
||||||
|
digitalWrite(_led_stop_pin, HIGH);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return(_coderracer_activ);
|
||||||
|
}
|
||||||
|
|
||||||
|
void IRAM_ATTR CodeRacer::set_taster_state() {
|
||||||
|
if ((millis() - taster_last_pressed_ms) > 200) {
|
||||||
|
taster_last_pressed_ms = millis();
|
||||||
|
if (false == coderracer_activ) {
|
||||||
|
coderracer_activ = true;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
coderracer_activ = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
138
libraries/CodeRacer/CodeRacer.h
Normal file
138
libraries/CodeRacer/CodeRacer.h
Normal file
|
@ -0,0 +1,138 @@
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include <ESP32Servo.h>
|
||||||
|
#include "esp32-hal-ledc.h"
|
||||||
|
|
||||||
|
#ifndef __CodeRacer_H__
|
||||||
|
#define __CodeRacer_H__
|
||||||
|
|
||||||
|
//----- Taster ------------
|
||||||
|
#define H_TASTERPIN 17
|
||||||
|
//----- Servo -----
|
||||||
|
#define H_SERVOPIN 16 // Pin an dem der Servomotor angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||||
|
#define H_SERVO_LINKS 140 // Wert um den Servo 45 Grad nach links zu drehen ... der kann je nach Servo anders sein
|
||||||
|
#define H_SERVO_RECHTS 35 // Wert um den Servo 45 Grad nach rechtss zu drehen ... der kann je nach Servo anders sein
|
||||||
|
#define H_SERVO_MITTE 90 // Wert um den Servo in die Mitte zu drehen ... der kann je nach Servo anders sein
|
||||||
|
#define H_SERVO_SCHWENK_LINKS 135
|
||||||
|
#define H_SERVO_SCHWENK_RECHTS 40
|
||||||
|
|
||||||
|
#define SERVO_SCHWENK_LI 5
|
||||||
|
#define SERVO_SCHWENK_RE -5
|
||||||
|
#define SERVO_SCHWENK_MS 10
|
||||||
|
|
||||||
|
//----- Ultraschallsensor -----
|
||||||
|
#define H_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 H_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 H_US_STOP_ABSTAND_CM 5 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
||||||
|
#define US_MAX_ECHO_TIME_US 6000 // Wenn die Zeit für das Echo länger dauert als diese Zeit, ist der Racer weit genug weg und wir müssen nicht weiter warten.
|
||||||
|
|
||||||
|
//----- Motoren -----
|
||||||
|
#define H_MOTORRE_TEMPO 205 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255
|
||||||
|
#define H_MOTORLI_TEMPO 200 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255
|
||||||
|
#define H_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 H_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 H_MOTORRE_BACK 15 // 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 H_MOTORLI_SPEED 21 // 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 H_MOTORLI_FWRD 22 // 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 H_MOTORLI_BACK 23 // 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 H_RACER_LINKS_MS 200 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach links zu drehen
|
||||||
|
#define H_RACER_RECHTS_MS 200 // Die Zeit in Millisekunden, die der Racer braucht um sich 45 Grad nach rechts zu drehen
|
||||||
|
|
||||||
|
#define MOTORPWM_LINKS 5 // PWM-Kanal für linken Motor
|
||||||
|
#define MOTORPWM_RECHTS 6 // PWM-Kanal für rechten Motor
|
||||||
|
#define MOTORRE_MAX_TEMPO 240 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255
|
||||||
|
#define MOTORLI_MAX_TEMPO 240 // Geschwindigkeit Motor1 ... ein Wert zwischen 0 und 255
|
||||||
|
|
||||||
|
#define MOTOR_MAX_SPEED_START_MS 10
|
||||||
|
|
||||||
|
//----- Werte für die LEDs -----
|
||||||
|
#define H_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 H_LED_STOP 25 // Pin an dem die STOP LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||||
|
#define H_LED_LINKS 27 // Pin an dem die LINKS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||||
|
#define H_LED_RECHTS 33 // Pin an dem die RECHTS LED angeschlossen ist. 'GPIO' muss man weglassen -> also z.B. nicht GPIO88 sondern nur 88.
|
||||||
|
|
||||||
|
static volatile bool coderracer_activ;
|
||||||
|
static volatile unsigned long taster_last_pressed_ms;
|
||||||
|
|
||||||
|
//--- this is as preparation of the class creation
|
||||||
|
class CodeRacer {
|
||||||
|
|
||||||
|
private:
|
||||||
|
int _taster_pin;
|
||||||
|
int _servopin;
|
||||||
|
int _us_trigger_pin;
|
||||||
|
int _us_echo_pin;
|
||||||
|
int _motor_links_frwd_pin;
|
||||||
|
int _motor_links_back_pin;
|
||||||
|
int _motor_links_enable_pin;
|
||||||
|
int _motor_rechts_frwd_pin;
|
||||||
|
int _motor_rechts_back_pin;
|
||||||
|
int _motor_rechts_enable_pin;
|
||||||
|
int _led_frwd_pin;
|
||||||
|
int _led_stop_pin;
|
||||||
|
int _led_links_pin;
|
||||||
|
int _led_rechts_pin;
|
||||||
|
|
||||||
|
int _servo_mitte;
|
||||||
|
int _servo_links;
|
||||||
|
int _servo_rechts;
|
||||||
|
int _schwenk_links;
|
||||||
|
int _schwenk_rechts;
|
||||||
|
|
||||||
|
int _schwenk_position;
|
||||||
|
int _schwenk_richtung;
|
||||||
|
long _schwenk_millis;
|
||||||
|
|
||||||
|
int _motor_links_tempo;
|
||||||
|
int _motor_rechts_tempo;
|
||||||
|
int _drehung_links_ms;
|
||||||
|
int _drehung_rechts_ms;
|
||||||
|
|
||||||
|
bool _drive_forward;
|
||||||
|
long _drive_forward_ms;
|
||||||
|
bool _drive_normal_forward;
|
||||||
|
|
||||||
|
|
||||||
|
static void set_taster_state();
|
||||||
|
|
||||||
|
Servo* _servo;
|
||||||
|
Servo* _servo_dummy;
|
||||||
|
|
||||||
|
void analog_write(int pin, int speed);
|
||||||
|
int _coderracer_activ;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
|
||||||
|
CodeRacer();
|
||||||
|
|
||||||
|
CodeRacer(int tasterpin, int servopin,
|
||||||
|
int us_trigger_pin, int us_echo_pin,
|
||||||
|
int motor_links_frwd_pin, int motor_links_back_pin, int motor_links_enable_pin,
|
||||||
|
int motor_rechts_frwd_pin, int motor_rechts_back_pin, int motor_rechts_enable_pin,
|
||||||
|
int led_frwd, int led_stop, int led_links, int led_rechts
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
|
void begin();
|
||||||
|
|
||||||
|
void servo_einstellungen(int winkel_mitte, int winkel_links, int winkel_rechts, int schwenk_links, int schwenk_rechts);
|
||||||
|
void motor_einstellungen(int motor_links_tempo, int motor_rechts_tempo, int drehung_links_ms, int drehung_rechts_ms);
|
||||||
|
|
||||||
|
void anhalten();
|
||||||
|
void normal_tempo();
|
||||||
|
void vorwaerts();
|
||||||
|
void links();
|
||||||
|
void rechts();
|
||||||
|
void servo_rechts();
|
||||||
|
void servo_links();
|
||||||
|
void servo_mitte();
|
||||||
|
long abstand_messen();
|
||||||
|
void servo_schwenk();
|
||||||
|
|
||||||
|
bool start_stop();
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
|
@ -1,8 +1,5 @@
|
||||||
#include <CodeRacer.h>
|
#include <CodeRacer.h>
|
||||||
|
|
||||||
#include <ESP32Servo.h>
|
|
||||||
#include "esp32-hal-ledc.h"
|
|
||||||
|
|
||||||
//----- Werte für den Ultraschallsensor -----
|
//----- Werte für den Ultraschallsensor -----
|
||||||
#define US_STOP_ABSTAND_CM 15 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
#define US_STOP_ABSTAND_CM 15 // Wenn der gemessene Abstand kleiner ist, hält der CodeRacer an
|
||||||
|
|
15
libraries/CodeRacer/keywords.txt
Normal file
15
libraries/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
|
Loading…
Reference in a new issue