From 4a66883c2b1ee796abdaeb7edfd52d01cd0884d3 Mon Sep 17 00:00:00 2001 From: Jens Noack Date: Fri, 9 Jul 2021 15:32:32 +0200 Subject: [PATCH] removed lib code and added .json --- coderacer_mkII/.gitignore | 5 + coderacer_mkII/.travis.yml | 67 + coderacer_mkII/.vscode/extensions.json | 7 + coderacer_mkII/include/README | 39 + coderacer_mkII/platformio.ini | 16 + coderacer_mkII/src/CodeRacer_Example_Main.cpp | 223 +++ coderacer_mkII/src/coderacer_main.cpp | 250 +++ coderacer_mkII/test/README | 11 + esp32_coderacer/.gitignore | 5 + esp32_coderacer/.travis.yml | 67 + esp32_coderacer/.vscode/extensions.json | 7 + esp32_coderacer/include/README | 39 + esp32_coderacer/lib/CodeRacer/CodeRacer.cpp | 1345 +++++++++++++++++ esp32_coderacer/lib/CodeRacer/CodeRacer.h | 282 ++++ .../SimpleBTCoderacer/SimpleBTCoderacer.ino | 56 + .../esp32_coderacer_beispiel.ino | 82 + esp32_coderacer/lib/CodeRacer/keywords.txt | 15 + esp32_coderacer/lib/README | 46 + esp32_coderacer/platformio.ini | 15 + esp32_coderacer/src/esp32_coderacer.cpp | 128 ++ esp32_coderacer/test/README | 11 + 21 files changed, 2716 insertions(+) create mode 100644 coderacer_mkII/.gitignore create mode 100644 coderacer_mkII/.travis.yml create mode 100644 coderacer_mkII/.vscode/extensions.json create mode 100644 coderacer_mkII/include/README create mode 100644 coderacer_mkII/platformio.ini create mode 100644 coderacer_mkII/src/CodeRacer_Example_Main.cpp create mode 100644 coderacer_mkII/src/coderacer_main.cpp create mode 100644 coderacer_mkII/test/README create mode 100644 esp32_coderacer/.gitignore create mode 100644 esp32_coderacer/.travis.yml create mode 100644 esp32_coderacer/.vscode/extensions.json create mode 100644 esp32_coderacer/include/README create mode 100644 esp32_coderacer/lib/CodeRacer/CodeRacer.cpp create mode 100644 esp32_coderacer/lib/CodeRacer/CodeRacer.h create mode 100644 esp32_coderacer/lib/CodeRacer/examples/SimpleBTCoderacer/SimpleBTCoderacer.ino create mode 100644 esp32_coderacer/lib/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino create mode 100644 esp32_coderacer/lib/CodeRacer/keywords.txt create mode 100644 esp32_coderacer/lib/README create mode 100644 esp32_coderacer/platformio.ini create mode 100644 esp32_coderacer/src/esp32_coderacer.cpp create mode 100644 esp32_coderacer/test/README diff --git a/coderacer_mkII/.gitignore b/coderacer_mkII/.gitignore new file mode 100644 index 0000000..5762142 --- /dev/null +++ b/coderacer_mkII/.gitignore @@ -0,0 +1,5 @@ +.pio +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json +.vscode/ipch diff --git a/coderacer_mkII/.travis.yml b/coderacer_mkII/.travis.yml new file mode 100644 index 0000000..a8bbc57 --- /dev/null +++ b/coderacer_mkII/.travis.yml @@ -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 diff --git a/coderacer_mkII/.vscode/extensions.json b/coderacer_mkII/.vscode/extensions.json new file mode 100644 index 0000000..0f0d740 --- /dev/null +++ b/coderacer_mkII/.vscode/extensions.json @@ -0,0 +1,7 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "platformio.platformio-ide" + ] +} diff --git a/coderacer_mkII/include/README b/coderacer_mkII/include/README new file mode 100644 index 0000000..45496b1 --- /dev/null +++ b/coderacer_mkII/include/README @@ -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 diff --git a/coderacer_mkII/platformio.ini b/coderacer_mkII/platformio.ini new file mode 100644 index 0000000..c2479a9 --- /dev/null +++ b/coderacer_mkII/platformio.ini @@ -0,0 +1,16 @@ +; 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 +monitor_speed = 115200 +lib_deps = itsblue/CoderacerMKII@^1.0.0 diff --git a/coderacer_mkII/src/CodeRacer_Example_Main.cpp b/coderacer_mkII/src/CodeRacer_Example_Main.cpp new file mode 100644 index 0000000..30db360 --- /dev/null +++ b/coderacer_mkII/src/CodeRacer_Example_Main.cpp @@ -0,0 +1,223 @@ +// Example Code of a CodeRacer sketch with implementation of a webserver +#include "CodeRacer_MKII.h" +#include "Webserver.h" + +CodeRacerMKII Coderacer; // Inizialization of your CodeRacer +AsyncWebServer server(80); // IMPORTANT definition of the asynchronous Web server, including port number +int Distance; +int DemoMode=0; +int maximum= 0; +int Array[160]; +int Degrees[160]; +int location= 0; // Some numbers we need for later... +Codeserver Test((char*)"coderacer_ap", (char*)"007coderacer"); // Creation of the webserver. enter your network's SSID and password here + + +void setup() +{ + Coderacer.begin(); + Coderacer.servo_sweep_left_pos=120; // Just a few adjustments to the servo_sweep parameters- that way, the servo sweeps more narrowly + Coderacer.servo_sweep_right_pos= 60; + + /* One problem we came across during the testing of the Coderacer was, that the two engines don't run equally fast- meaning that even with + identical speed (let's say 130, 130), the Racer will slowly pull to one side on longer distances. To adjust this issue, all you can do for now is test + which engine is more powerful- and adjust your speed for the left and right side drives accordingly. */ + Coderacer.speed_settings(140, 130); + + Serial.begin(115200); + + Test.Run(); // Calls the Run() routine, which manages everything the webserver needs to work + Coderacer.wifi_printf("Activate a switch to choose a Demonstration program."); + wait_ms(1000); + /*the IP adress of the server is given out on the Serial monitor. It is currently connected to the CodeRacer we used for testing and programming this sample code. + If the IP adress of YOUR CodeRacer differs from the one specified in Webserver.cpp, you have to change the following part of the HTML char array: + var Url ="http://192.168.1.146/"; --> var Url ="your_IP_adress"; */ +} + +void loop() +/* the loop contains four demonstration example codes, seperated by switch/ case which are supposed to give you the idea of the +CodeRacer routines, what they do, how you can use them and what you need to consider before doing so. By turning on one of the switches, you select one of the demos. +Activate the CodeRacer by pressing the left button, and watch the CodeRacer doing (hopefully) what it is advised to. Don't hesitate to watch the Webserver as well, +instructions on how to get it running are shown and executed above. */ +{ + DemoMode= Coderacer.switch_check(); + switch (DemoMode) + { + case 0: + { + Coderacer.kitt(); // This is just some fun stuff happening while no program has been selected... feel free to edit it out :) + break; + } + case 1: + /* a Demo featuring: measuring the distance, driving forward until it falls below a certain value, then driving back + for a small amount of time and turning 90 degrees to the right. NOTE: if you want to print out debug message on the Webserver, + build in a certain delay time so the AJAX protocoll can process the message (otherwise it won't get displayed). */ + { + Coderacer.wifi_printf("Selected: Demo 1, activate your CodeRacer to start"); + Coderacer.set_leds_all_off(); + wait_ms(5000); + while(Coderacer.is_active()) // If the left button is pressed, the CodeRacer becomes active and the loop starts + { + wait_ms(300); + Distance= Coderacer.usonic_measure_single_shot_cm(); + while(Distance>25) + { + Distance=Coderacer.usonic_measure_single_shot_cm(); + Coderacer.servo_sweep(); + Coderacer.drive_forward(); + // tells the CodeRacer to drive forward while sweeping the servo from left to right (the sweeping range is defined eariler in this code) and measure the distance + } + Coderacer.stop_driving(); + Coderacer.servo_set_to_center(); + wait_ms(500); + Coderacer.drive_backward_for_ms(500); + wait_ms(500); + Coderacer.wifi_printf("Drehung!"); //prints out a message on the webserver + wait_ms(500); + Coderacer.turn_degree(80); // Due to the inertia of the wheels, lower the degrees of the turn a bit- in this case, although 80 are stated, the Racer does an almost perfect 90 degree turn... + wait_ms(500); + } + break; + } + case 2: + /* a more "intelligent" way to tell the CodeRacer where to drive. Basically the idea is to let the CodeRacer drive forward until a certain distance is reached (as done before). + Then, the servo sweeps from left to right filling an array of distances, getting the index of the highest value and then turning a precise amount of degrees, + depending on that value. The scheme of the code is explained below*/ + { + Coderacer.wifi_printf("Selected: Demo 2, activate your CodeRacer to start"); + Coderacer.set_leds_all_off(); + wait_ms(5000); + while(Coderacer.is_active()) + { + Distance= Coderacer.usonic_measure_cm(); + while (Distance>25) // Again a simple way to tell the Racer "drive until a distance of __ cm is reached" + { + Distance= Coderacer.usonic_measure_single_shot_cm(); + Coderacer.servo_sweep(); + Coderacer.drive_forward(210, 190); + } + Coderacer.stop_driving(); + wait_ms(1000); + + for(int i=0, k=10; i<160; i++, k++) // sweeps the servo from right to leftmost position and fills an array with the measured distances + { + Coderacer.servo_set_position_wait(k); + Array[i]=Coderacer.usonic_measure_single_shot_cm(); + } + + Coderacer.servo_set_to_center(); // Reset servo + wait_ms(200); + + maximum= Array[0]; // Defines the maximum value of the array at the index 0 + + for (int c = 0; c < 160; c++) // Emitts the highest value of the distance- array. One flaw: only the first time this value shows up is saved. + { + if (Array[c] > maximum) + { + maximum = Array[c]; + location = c; + } + } + + for(int i=0, k=80; i<160; i++, k--) // Finally, create an array of degrees from 80 to -80 (representing the distance array from 0 to 160) + { + Degrees[i]= k; + } + Coderacer.turn_degree(Degrees[location]); // ...And turn the servo by the number of degrees roughly representing the biggest distance! + wait_ms(500); + } + break; + } + + case 3: + /* a demo program featuring: an alternative way telling the CodeRacer to stop when a ceratin distance is reached. the Racer will drive around + happily, turning left and right until the specified value is measured. NOTE: it might occur that the Racer won't get to measure the stop distance + - if that is the case, just hold your hand in front of it so it breaks out of the while- loop ;) */ + { + Coderacer.wifi_printf("Selected: Demo 3, activate your CodeRacer to start"); + Coderacer.set_leds_all_off(); + wait_ms(5000); + while(Coderacer.is_active()) + { + Distance = Coderacer.usonic_measure_cm(); // measure the distance - at the position of the servo + Coderacer.start_stop_at_min_distance(20); // Select a distance- the CodeRacer will stop if the Usonic Sensor measures it + while(!Coderacer.stopped_at_min_distance()) // WHILE the CodeRacer hasn't stopped at the previous declared distance... + { + if(Distance > 50) + { + Coderacer.drive_forward(); + Coderacer.servo_sweep(); + } + else if(Distance > 40) + { + Coderacer.turn_right(); + } + else if(Distance > 30) + { + Coderacer.turn_left(); + } + else + { + Coderacer.drive_backward(); + } + + Distance = Coderacer.usonic_measure_cm(); + // Measure the distance again- be careful with usonic_measure_cm(), as this method takes a while to complete. Calling it too fast will crash your Code. + } + Coderacer.wifi_printf("Stopped at minimal stopped distance selected by user!!"); + wait_ms(2000); + Coderacer.set_inactive(); + } + break; + } + case 4: + /* a demo program showing the scheme of displaying messages in the Webserver. After doing so, take a look at the dashboard on the website! + the racer will drive a specific amounts of ticks for the left and right wheel afterwards, you can check if that works correctly looking into + the table. NOTE: you might want to disable the CodeRacer from driving away- no stopping condition built in this time, so it might + bump into something while driving... just let the wheels turn freely and watch the dashboard... */ + { + Coderacer.wifi_printf("Selected: Demo 4, activate CodeRacer to start"); + Coderacer.set_leds_all_off(); + wait_ms(5000); + + while(Coderacer.is_active()) + { + Coderacer.set_obstacle_stop(true); + Coderacer.wifi_printf("Welcome..."); + wait_ms(1000); + // As previously mentioned, the website resfrehes internally, but only in an interval of 750ms + // So if you want your message to be properly displayed, you got to build in a delay using wait_ms... + Coderacer.wifi_printf("Using wifi_printf"); + wait_ms(1000); + Coderacer.wifi_printf("You can display custom messages on the Webserver!"); + wait_ms(1000); + Coderacer.wifi_printf("But you knew that already!"); + wait_ms(1000); + Coderacer.wifi_printf("Dont forget to build in small waiting windows..."); + wait_ms(1000); + Coderacer.wifi_printf("So your message is transmitted properly!"); + wait_ms(1000); + Coderacer.wifi_printf("Also, check out the clear button!"); + wait_ms(1000); + Coderacer.wifi_printf("Now, watch the stepcounters in the table!"); + wait_ms(2000); + + Coderacer.drive_ticks_left(200, true); + while (true== Coderacer.is_driving()){} // IMPORTANT! halts the Code while the Racer is driving its __ steps on each side. + wait_ms(3000); + Coderacer.Reset_Stats(); // Resets the stats of the Racer, including stepcounters and speed settings to default. + Coderacer.speed_settings(255, 245); // New Speed settings for both drives... + wait_ms(3000); // The delay is once again needed so the debug message of reset_stats() is properly displayed... + Coderacer.drive_ticks_right(200, true); + while (true== Coderacer.is_driving()){} + Coderacer.wifi_printf("End of demo 3!"); + wait_ms(3000); + Coderacer.set_inactive(); + } + break; + } + + } + + +} \ No newline at end of file diff --git a/coderacer_mkII/src/coderacer_main.cpp b/coderacer_mkII/src/coderacer_main.cpp new file mode 100644 index 0000000..b86d624 --- /dev/null +++ b/coderacer_mkII/src/coderacer_main.cpp @@ -0,0 +1,250 @@ +#include "CodeRacer_MKII.h" + +#include +#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; +CodeRacerMKII coderacer; + +int aabstand[160]; +void filladistance(); +int adegree[160]; +unsigned int ispeed=0; +float fZeit= 0; +float fSpeedminleft= 0; +float fSpeedminright=0; +float fSpeedmaxleft=0; +float fSpeedmaxright=0; +int iTicks=101; +float callibration_drive(unsigned int tickstogo, float calfactor); + +unsigned int getcount_function(bool left_notright); +void set_speed_function(bool left_notright, unsigned int speed); +unsigned int get_inmin(bool left_notright); +void calculate_veliocity(unsigned int inleft, unsigned int inright, float* vleft, float* vright); + +const bool LEFT = true; +const bool RIGHT = false; +const unsigned int IN_MAX = 255; + +//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ---- +void setup2() { + // Monitor + Serial.begin(9600); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen. + + // CodeRacer initialisieren + coderacer.begin(); + + coderacer.servo_set_to_left(); + delay(10); + coderacer.servo_set_to_right(); + delay(10); + coderacer.servo_set_to_center(); + + anzahl_drehung = 0; + drehung = links; + coderacer.set_syncstop(true); + coderacer.set_obstacle_stop(false); + +} + +//---- 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 loop2() +{ + coderacer.drive_distance_mm(1000, 1000); + + bool started = false; + while(coderacer.start_stop()== 1) + { + if(false == started) + { + started = true; + wait_ms(1000); + } + + + + + + // below - mitteln + coderacer.stop_driving(); + unsigned int in_min_left = get_inmin(true); + wait_ms(1000); // do not use delay() this will create problems with interrupt routines! use the wait_ms() instead !!!! + unsigned int in_min_right = get_inmin(false); + Serial.printf("left in_min: %u right in_min: %u \n", in_min_left, in_min_right); + wait_ms(1000); + + calculate_veliocity(in_min_left, in_min_right, &fSpeedminleft, &fSpeedminright); + wait_ms(1000); + calculate_veliocity(IN_MAX, IN_MAX, &fSpeedmaxleft, &fSpeedmaxright); + Serial.printf("Left vmin:%f vmax:%f Right vmin:%f vmax: %f\n", fSpeedminleft, fSpeedmaxleft, fSpeedminright, fSpeedmaxright); + //above - mitteln + + + + float nLeft= (fSpeedmaxleft- fSpeedminleft)/(IN_MAX- in_min_left); + float mLeft= fSpeedmaxleft-nLeft*IN_MAX; + float nRight= (fSpeedmaxright- fSpeedminright)/(IN_MAX- in_min_right); + float mRight= fSpeedmaxright-nRight*IN_MAX; + + Serial.printf(" nleft: %f mleft:%f nright:%f mright:%f\n", nLeft, mLeft, nRight, mRight); + + wait_ms(5000); + unsigned int vracer = 35; + unsigned int inleft = (vracer - mLeft)/nLeft; + unsigned int inright = (vracer - mRight)/nRight; + Serial.printf("inleft: %u inright:%u\n", inleft, inright); + coderacer.speed_settings(inleft, inright); + unsigned int lticks = coderacer.show_left_stepcounter(); + unsigned int rticks = coderacer.show_right_stepcounter(); + coderacer.drive_ticks(100,100); + while(coderacer.is_driving()){} + rticks = coderacer.show_right_stepcounter() - rticks; + lticks = coderacer.show_left_stepcounter() - lticks; + Serial.printf("Cal. Steps left: %u right: %u \n", lticks, rticks); + wait_ms(1000); + + coderacer.speed_settings(inleft, inleft); + lticks = coderacer.show_left_stepcounter(); + rticks = coderacer.show_right_stepcounter(); + coderacer.drive_ticks(100,100); + while(coderacer.is_driving()){} + rticks = coderacer.show_right_stepcounter() - rticks; + lticks = coderacer.show_left_stepcounter() - lticks; + Serial.printf("Uncal.Steps left: %u right: %u \n", lticks, rticks); + + + wait_ms(1000); + coderacer.set_inactive(); + } +} + + +unsigned int get_inmin(bool left_notright ) +{ + unsigned int steps_before_driving = getcount_function(left_notright); + //Serial.printf("Steps before driving: %u \n", steps_before_driving ); + for(unsigned int pwm_in = 0; pwm_in < 255; pwm_in = pwm_in+5) + { + unsigned int steps_after_driving = getcount_function(left_notright); + if(steps_after_driving > steps_before_driving) + { + //Serial.printf("Steps after driving: %u \n", steps_after_driving ); + coderacer.stop_driving(); + return pwm_in*1.1; + } + set_speed_function(left_notright, pwm_in); + wait_ms(100); + } + coderacer.stop_driving(); + return 0 ; +} + +unsigned int getcount_function(bool left_notright) +{ + if(true == left_notright){return coderacer.show_left_stepcounter();} + else{return coderacer.show_right_stepcounter();} +} + +void set_speed_function(bool left_notright, unsigned int speed) +{ + if(true == left_notright){coderacer.drive_forward(speed,0);} + else{coderacer.drive_forward(0,speed);} +} + + + + +void calculate_veliocity(unsigned int inleft, unsigned int inright, float* vleft, float* vright) +{ + coderacer.speed_settings(inleft, inright); + coderacer.set_left_start_time(); + coderacer.set_right_start_time(); + unsigned int iStepsbefore_left = coderacer.show_left_stepcounter(); + unsigned int iStepsbefore_right = coderacer.show_right_stepcounter(); + coderacer.drive_ticks(iTicks, iTicks); + while(coderacer.is_driving()){}; + + unsigned int iStepsafter_left = coderacer.show_left_stepcounter(); + unsigned int iStepsafter_right = coderacer.show_right_stepcounter(); + + unsigned int iDifferenz_left = iStepsafter_left - iStepsbefore_left-1; + unsigned int iDifferenz_right = iStepsafter_right - iStepsbefore_right-1; + + Serial.printf("Schritte before left: %u right: %u Steps after left:%u right:%u Steps diff left: %u right %u\n", iStepsbefore_left , iStepsbefore_right, iStepsafter_left, iStepsafter_right, iDifferenz_left, iDifferenz_right); + + unsigned long lzeit_left = coderacer.show_left_time_of_last_tick()- coderacer.show_left_start_time(); + unsigned long lzeit_right = coderacer.show_right_time_of_last_tick()- coderacer.show_right_start_time(); + + //Serial.printf("Links Startzeit:%lu Endzeit:%lu Runtime:%lu\n", coderacer.show_left_start_time(),coderacer.show_left_time_of_last_tick(), lzeit_left); + //Serial.printf("Rechts Startzeit:%lu Endzeit:%lu Runtime:%lu\n", coderacer.show_right_start_time(), coderacer.show_right_time_of_last_tick(), lzeit_right); + + float fSpeedleft= iDifferenz_left/((float)lzeit_left/1000.0); + *vleft = fSpeedleft; + float fSpeedright= iDifferenz_right/((float)lzeit_right/1000.0); + *vright = fSpeedright; + //Serial.printf("Speed left: %f right: %f\n" , fSpeedleft, fSpeedright); +} + + +//Serial.printf("links %i\n", coderacer.show_left_stepcounter()); +//Serial.printf("rechts %i\n", coderacer.show_right_stepcounter()); +//Serial.printf("%i\n", coderacer.show_distance_mm()); + +float callibration_drive(unsigned int tickstogo, float calfactor) +{ + unsigned int stepsprevl; + unsigned int stepsprevr; + float GesamtSummeR = 0; + float GesamtSummeL=0; + unsigned int runcounter = 0; + int runs= 4; + float MittelSummeR; + float MittelSummeL; + unsigned int tickcheck= tickstogo*1.02; + for(unsigned int v= 190;v<=200;v=v+10) + { + unsigned int vr = v + calfactor*255; + unsigned int vl = v - calfactor*255; + runcounter ++; + coderacer.speed_settings(vl, vr); + Serial.println(vl); + Serial.println(vr); + int SummeR = 0; + int SummeL=0; + for (int i=1; i<=runs; i++) + { + stepsprevl = coderacer.show_left_stepcounter(); + stepsprevr = coderacer.show_right_stepcounter(); + coderacer.drive_ticks_left(tickstogo, true); + while (1== coderacer.is_driving()){} + delay(1000); + SummeR = SummeR + (coderacer.show_right_stepcounter() - stepsprevr); + SummeL= SummeL +(coderacer.show_left_stepcounter()- stepsprevl); + if (tickcheck<(coderacer.show_left_stepcounter() - stepsprevl)) + { + Serial.printf("ERROR: calibration failed"); + Serial.printf("links=%i\n" ,coderacer.show_left_stepcounter()- stepsprevl); + return 0; + } + Serial.printf("v=%i links=%i rechts=%i\n" ,v, coderacer.show_left_stepcounter()- stepsprevl, coderacer.show_right_stepcounter() - stepsprevr); + + } + GesamtSummeR = GesamtSummeR+ SummeR/4.0; + GesamtSummeL = GesamtSummeL+ SummeL/4.0; + } + MittelSummeR= GesamtSummeR/(float)runcounter; + MittelSummeL= GesamtSummeL/(float)runcounter; + float CalibrationFactor= MittelSummeL/ MittelSummeR; + return CalibrationFactor; +} + diff --git a/coderacer_mkII/test/README b/coderacer_mkII/test/README new file mode 100644 index 0000000..c3b0ed6 --- /dev/null +++ b/coderacer_mkII/test/README @@ -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 diff --git a/esp32_coderacer/.gitignore b/esp32_coderacer/.gitignore new file mode 100644 index 0000000..5762142 --- /dev/null +++ b/esp32_coderacer/.gitignore @@ -0,0 +1,5 @@ +.pio +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json +.vscode/ipch diff --git a/esp32_coderacer/.travis.yml b/esp32_coderacer/.travis.yml new file mode 100644 index 0000000..a8bbc57 --- /dev/null +++ b/esp32_coderacer/.travis.yml @@ -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 diff --git a/esp32_coderacer/.vscode/extensions.json b/esp32_coderacer/.vscode/extensions.json new file mode 100644 index 0000000..8281e64 --- /dev/null +++ b/esp32_coderacer/.vscode/extensions.json @@ -0,0 +1,7 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "platformio.platformio-ide" + ] +} \ No newline at end of file diff --git a/esp32_coderacer/include/README b/esp32_coderacer/include/README new file mode 100644 index 0000000..45496b1 --- /dev/null +++ b/esp32_coderacer/include/README @@ -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 diff --git a/esp32_coderacer/lib/CodeRacer/CodeRacer.cpp b/esp32_coderacer/lib/CodeRacer/CodeRacer.cpp new file mode 100644 index 0000000..ae52995 --- /dev/null +++ b/esp32_coderacer/lib/CodeRacer/CodeRacer.cpp @@ -0,0 +1,1345 @@ +// the compiler switch for an ESP8266 is looking like this: #elif defined(ARDUINO_ARCH_ESP8266) +#include "CodeRacer.h" + +using namespace std; + +/** @brief CodeRace constructor without pins. All pins settings taken from the coderacer header file +* @return nothing +*/ +CodeRacer::CodeRacer() +{ + _button_pin = H_BUTTON_PIN; + _servo_pin = H_SERVO_PIN; + _us_trigger_pin = H_US_TRIG_PIN; + _us_echo_pin = H_US_ECHO_PIN; + _drive_left_frwd_pin = H_DRIVE_LEFT_FWRD_PIN; + _drive_left_back_pin = H_DRIVE_LEFT_BACK_PIN; + _drive_left_enable_pin = H_DRIVE_LEFT_ENABLE_PIN; + _drive_right_frwd_pin = H_DRIVE_RIGHT_FWRD_PIN; + _drive_right_back_pin = H_DRIVE_RIGHT_BACK_PIN; + _drive_right_enable_pin = H_DRIVE_RIGHT_ENABLE_PIN; + _led_frwd_pin = H_LED_FRWD_PIN; + _led_stop_pin = H_LED_STOP_PIN; + _led_left_pin = H_LED_LEFT_PIN; + _led_right_pin = H_LED_RIGHT_PIN; +} + +/** @brief CodeRace constructor with pins.This will overwrite the default settings taken from the header file. +* @param button_pin Pin the external button is connected at +* @param servo_pin Pin the servo drive is connected at +* @param us_trigger_pin Pin the trigger signal of the ultrasonic sensor is connected at +* @param us_echo_pin Pin the echo signal of the ultrasonic sensor is connected at +* @param drive_left_frwd_pin Pin the forward pin of the left side drive device driver is connected at +* @param drive_left_back_pin Pin the backward pin of the left side drive device driver is connected at +* @param drive_left_enable_pin Pin the enable pin of the left side drive device driver is connected at +* @param drive_right_frwd_pin Pin the forward pin of the right side drive device driver is connected at +* @param drive_right_back_pin Pin the backward pin of the right side drive device driver is connected at +* @param drive_right_enable_pin Pin the enable pin of the right side drive device driver is connected at +* @param led_frwd_pin Pin the led that signals forward direction is connected at +* @param led_stop_pin Pin the led that signals that the drives are stopped is connected at +* @param led_left_pin Pin the led that signals left side direction is connected at +* @param led_right_pin Pin the led that signals right side direction is connected at +* @return nothing +*/ +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 +) +{ + _button_pin = button_pin; + _servo_pin = servo_pin; + _us_trigger_pin = us_trigger_pin; + _us_echo_pin = us_echo_pin; + _drive_left_frwd_pin = drive_left_frwd_pin; + _drive_left_back_pin = drive_left_back_pin; + _drive_left_enable_pin = drive_left_enable_pin; + _drive_right_frwd_pin = drive_right_frwd_pin; + _drive_right_back_pin = drive_right_back_pin; + _drive_right_enable_pin = drive_right_enable_pin; + _led_frwd_pin = led_frwd_pin; + _led_stop_pin = led_stop_pin; + _led_left_pin = led_left_pin; + _led_right_pin = led_right_pin; +} + +/** @brief Initialisation of all attributes and settings of the coderacer. Defaults are taken from the header file. +* @return nothing +*/ +void CodeRacer::begin() { + + // init of variables and objects + _bluetoothcreated = false; + _bt_stopOnLostConnection_timeout_ms = 0; + _bt_lastmessagereceived = millis(); + _bt_ignoremsgs.clear(); + _bt_onlymsgs.clear(); + + _servo_dummy = new Servo(); // the dummy is needed so far to avoid conflicts with analog write + _servo = new Servo(); + servo_center_pos = H_SERVO_CENTER_POS; + servo_left_pos = H_SERVO_LEFT_POS; + servo_right_pos = H_SERVO_RIGHT_POS; + servo_sweep_left_pos = H_SERVO_SWEEP_LEFT_POS; + servo_sweep_right_pos = H_SERVO_SWEEP_RIGHT_POS; + _servo_position = servo_center_pos; + _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP; + _servo_position_set_at_ms = millis(); + _servo_position_eta_in_ms = 0; + + _drive_left_speed = H_DRIVE_LEFT_SPEED; + _drive_right_speed = H_DRIVE_RIGHT_SPEED; + + _turn_left_for_ms = H_RACER_TURN_LEFT_FOR_MS; + _turn_right_for_ms = H_RACER_TURN_RIGHT_FOR_MS; + + coderracer_activ = false; + _coderracer_activ = true; + _drive = false; + _drive_set_at_ms = millis(); + _servo_sweep = false; + + _last_led_switched_at_ms = millis(); + _last_led_on = 0; + _led_count = 3; + + _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS); + + _usonic_stop_distance_cm = H_US_STOP_DISTANCE_CM; + usonic_set_stop_distance_cm(_usonic_stop_distance_cm); + _coderacer_stopped_at_min_distance = false; + + // Ultrasonic sensor + pinMode(_us_trigger_pin, OUTPUT); + pinMode(_us_echo_pin, INPUT); + + // Servo drive + _servo->attach(_servo_pin); + + // Left drive + pinMode(_drive_left_frwd_pin, OUTPUT); + pinMode(_drive_left_back_pin, OUTPUT); + set_drive_left_state(DRIVESTOP); + ledcSetup(DRIVE_PWM_LEFT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width + ledcAttachPin(_drive_left_enable_pin, DRIVE_PWM_LEFT_CHANNEL); // connect left drive enable with PWM channel + + // Right drive + pinMode(_drive_right_frwd_pin, OUTPUT); + pinMode(_drive_right_back_pin, OUTPUT); + set_drive_right_state(DRIVESTOP); + ledcSetup(DRIVE_PWM_RIGHT_CHANNEL, 5000, 8); // channel , 50 Hz, 8-bit width + ledcAttachPin(_drive_right_enable_pin, DRIVE_PWM_RIGHT_CHANNEL); // connect right drive enable pin with PWM channel + + // LEDs + pinMode(_led_frwd_pin, OUTPUT); + pinMode(_led_stop_pin, OUTPUT); + pinMode(_led_left_pin, OUTPUT); + pinMode(_led_right_pin, OUTPUT); + // all LEDS off + set_leds_all_off(); + + // Button & -interrupt + button_last_pressed_at_ms = 0; + pinMode(_button_pin, INPUT_PULLUP); + attachInterrupt(digitalPinToInterrupt(_button_pin), _set_button_state, FALLING); + + // Random + randomSeed(analogRead(0)); + + //fun stuff + coderacer_fun_enabled = false; + +} + +//************************************** +//*** Coderacer hihger level methods *** +//************************************** +/** @defgroup higherlevel Higher level methods, setters and getters +* @{ +*/ +/** @defgroup higherlevelmeths Methods +* @{ +*/ + +/** @brief Stops the racer and sets status LEDs. +* @return nothing +*/ +void CodeRacer::stop_driving() { + _servo_sweep = false; + _drive = false; + set_drives_stop_left_right(); + set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF); +} + +/** @brief Sets the speed and the directions of both drives so that it will move forward. +* +* The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section +* @return nothing +*/ +void CodeRacer::drive_forward() +{ + drive_forward(_drive_left_speed, _drive_right_speed); +} + +/** @brief Sets the speed as specified for both drives and the directions of both drives so that it will move forward. +* +* The specified speed values for both drives will be stored internaly so next time if you use e.g. drive_forward() exactly the here specified values will be taken. +* @param left_speed speed for the left side drive. 0<=speed<=255 +* @param right_speed speed for the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::drive_forward(uint8_t left_speed, uint8_t right_speed) +{ + set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD); + set_drives_speed_left_right(left_speed, right_speed); + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF); + _drive = true; + _drive_set_at_ms = millis(); +} + +/** @brief Sets the speed and the directions of both drives so that it will move backward. +* +* The speed is taken from the header file or set by one of the methods defined in the lower level drive methods section +* @return nothing +*/ +void CodeRacer::drive_backward() +{ + drive_backward(_drive_left_speed, _drive_right_speed); +} + +/** @brief Sets the speed as specified for both drives and the directions of both drives so that it will move backward. +* +* The specified speed values for both drives will be stored internaly so next time if you use e.g. drive_backward() exactly the here specified values will be taken. +* @param left_speed speed for the left side drive. 0<=speed<=255 +* @param right_speed speed for the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::drive_backward(uint8_t left_speed, uint8_t right_speed) +{ + set_drives_states_left_right(DRIVEBACK, DRIVEBACK); + set_drives_speed_left_right(left_speed, right_speed); + set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDON, LEDOFF); + _drive = true; + _drive_set_at_ms = millis(); +} + +/** @brief Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed. +* +* The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to left time can be set by thoose methods as well. +* The method is delayed until the racer has turned. +* @return nothing +*/ +void CodeRacer::turn_left() +{ + turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed); +} + +/** @brief Will turn the racer to the left for the specified time in ms and with the internally stored speed. +* +* The specified duration of time is stored internally and will be used next time by e.g. turn_left() +* @param turn_for_ms duration of time in ms to turn the racer +* @return nothing +*/ +void CodeRacer::turn_left(unsigned long turn_for_ms) +{ + turn_left(turn_for_ms, _drive_left_speed, _drive_right_speed); +} + +/** @brief Will turn the racer to the left for the specified time in ms and with the specified speed. +* +* The specified duration of time and the specified speeds are stored internally and will be used next time by e.g. turn_left() +* @param turn_for_ms duration of time in ms to turn the racer +* @param left_speed speed for the left side drive +* @param right_speed speed for the right side drive +* @return nothing +*/ +void CodeRacer::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed) +{ + _drive = false; + set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen + set_drives_states_left_right(DRIVEBACK, DRIVEFRWD); + set_drives_speed_left_right(left_speed, right_speed); + // wait set delay for the timed turn + _turn_left_for_ms = turn_for_ms; + delay(_turn_left_for_ms); + // stop drives again + set_drives_stop_left_right(); +} + +/** @brief Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed. +* +* The speed for both the left side and right side drive can be set by the methods described in the lower level drive section. The turn to right time can be set by thoose methods as well. +* The method is delayed until the racer has turned. +* @return nothing +*/ +void CodeRacer::turn_right() +{ + turn_right(_turn_right_for_ms, _drive_left_speed, _drive_right_speed); +} + +/** @brief Will turn the racer to the right for the specified time in ms and with the internally stored speed. +* +* The specified duration of time is stored internally and will be used next time by e.g. turn_right() +* @param turn_for_ms duration of time in ms to turn the racer +* @return nothing +*/ +void CodeRacer::turn_right(unsigned long turn_for_ms) +{ + turn_right(turn_for_ms, _drive_left_speed, _drive_right_speed); +} + +/** @brief Will turn the racer to the right for the specified time in ms and with the specified speed. +* +* The specified duration of time and the specified speeds are stored internally and will be used next time by e.g. turn_right() +* @param turn_for_ms duration of time in ms to turn the racer +* @param left_speed speed for the left side drive +* @param right_speed speed for the right side drive +* @return nothing +*/ +void CodeRacer::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed) +{ + _drive = false; + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); // LEDs setzen + set_drives_states_left_right(DRIVEFRWD, DRIVEBACK); + set_drives_speed_left_right(left_speed, right_speed); + // wait set delay for the timed turn + _turn_right_for_ms = turn_for_ms; + delay(_turn_right_for_ms); + // stop drives again + set_drives_stop_left_right(); +} + +/** @brief Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. +* +* This allow all of the none-single shot ultra sonic measurement methods to stopp the racer in the case the measured distance is smaller than minimal distance. This is just the enablement - you have to call one of the none-single-shot ultra sonic measurement methods continously while driving and maybe sweeping the servo. +* If the racer was stopped can be checked with stopped_at_min_distance() - it will return true in that case. +* The minimal distance can be set by the ultrasonic sensor setter methods. +* There is an example coming with the coderacer libary that you can load and get an idea how that works. +* @return nothing +*/ +void CodeRacer::start_stop_at_min_distance() { + start_stop_at_min_distance(_usonic_stop_distance_cm); +} + +/** @brief Enables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. +* +* This is almos the same as described for start_stop_at_min_distance(). You can specify the distance in cm here - this value will be stored internally and used by start_stop_at_min_distance() next time. +* @param min_distance_cm the minimal disctance in cm +* @return nothing +*/ +void CodeRacer::start_stop_at_min_distance(unsigned long min_distance_cm) { + if (false == _coderacer_stop_at_distance_enabled) { + _coderacer_stopped_at_min_distance = false; + usonic_set_stop_distance_cm(min_distance_cm); + _coderacer_stop_at_distance_enabled = true; + } +} + +/** @brief Disables to stopp the racer if during a distance measurement the measured distance is smaller then the specified minimal distance. +* @return nothing +*/ +void CodeRacer::stop_stop_at_min_distance() { + _coderacer_stop_at_distance_enabled = false; +} + +/** @brief This will return if the codracer is in active mode or not. +* +* There is a button used to toogle between active and inactive each time it is pressed This may help you to start driving and scanning the distance by pressing the button - and as well to stop the racer by pressing the button. +* This method will set the LEDs depending on the mode and sets the servo back to center and stopps the racer when leaving the active mode. You can leave or enter the active mode as well by setting using set_active() and set_inactive(). +* The button itself triggers and internall interrupt event and sets the active state - but you have to continously call that method to switch between inactive and active mode depending on the active state. +* If in inactive mode and fun is enabeld by just setting the coderacer_fun_enabled = true ... some fun will happen :-) +* +* @return True if the coderacer is in active mode. False if in inactive mode. +*/ +bool CodeRacer::start_stop() { + if (_coderracer_activ != coderracer_activ) { + _coderracer_activ = coderracer_activ; + if (true == _coderracer_activ) { + set_leds_all_off(); + delay(500); + } + else { + stop_driving(); + set_leds_all_on(); + delay(200); + servo_set_to_center(); + _servo_look_around_at_ms = millis() + random(20000, 120000); + } + } + + if ((false == _coderracer_activ) && (true == coderacer_fun_enabled)) { + kitt(); + look_around(); + } + + return(_coderracer_activ); +} + +/** @} */ // end of group higherlevelmeths + /** @defgroup higherlevelgetters Getters and setters + * @{ + */ + +/** @brief Returns true if the racer was stopped at minimum distance. This set to false each time start_stop_at_min_distance() is called. +* @return True if stopped. +*/ +bool CodeRacer::stopped_at_min_distance() { + return(_coderacer_stopped_at_min_distance); +} + +/** @brief Return true if the racer is driving - forward or backward +* @return True if driving forward or backward +*/ +bool CodeRacer::is_driving() { + return(_drive); +} + +/** @brief Returns the duration of time that is internally stored and used for turning the racer left +* @return Time to turn left in ms +*/ +unsigned long CodeRacer::turn_left_for_ms() { + return(_turn_left_for_ms); +} + +/** @brief Returns the duration of time that is internally stored and used for turning the racer left +* @return Time to turn left in ms +*/ +unsigned long CodeRacer::turn_right_for_ms() { + return(_turn_right_for_ms); +} + +/** @brief Sets the coderracer_active state to inactive. If start_stop() is used - the inactive mode will be entered. +* @return nothing +*/ +void CodeRacer::set_inactive() { + coderracer_activ = false; +} + +/** @brief Sets the coderracer_active state to active. If start_stop() is used - the active mode will be entered. +* @return nothing +*/ +void CodeRacer::set_active() { + coderracer_activ = true; +} + +/** @brief Checks if coderracer_activ is set. +* +* coderracer_activ is toggled each time the button is pressed. After power on coderracer_activ is set to False. +* @return True id coderracer_activ is set - False if not. +*/ +bool CodeRacer::is_active() { + return(coderracer_activ); +} + +/** @} */ // end of group higherlevelgetters +/** @} */ // end of group higherlevel + +//************************************** +//*** Just for fun *** +//************************************** +/** @defgroup lowerlevelfun Lower level fun stuff methods +* @{ +*/ +/** @brief Fun stuff - will move the servo around after a random amount of time +* @return nothing +*/ +void CodeRacer::look_around() +{ + if (_servo_look_around_at_ms < millis()) { + _servo_look_around_at_ms = millis() + random(FUN_MIN_PAUSE_MS, FUN_MAX_PAUSE_MS); + servo_set_to_left(); + delay(500); + servo_set_to_right(); + delay(800); + servo_set_to_center(); + delay(300); + servo_set_to_left(); + delay(100); + servo_set_to_center(); + } +} + +/** @brief Fun stuff - you know Knightrider... +* @return nothing +*/ +void CodeRacer::kitt() +{ + if (millis() - _last_led_switched_at_ms > LED_SWITCH_MS) { + _last_led_switched_at_ms = millis(); + if (_last_led_on >= 5) { + _led_count = -1; + } + else if (_last_led_on <= 0) { + _led_count = 1; + } + _last_led_on = _last_led_on + _led_count; + switch (_last_led_on) { + case 0: + set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); + break; + case 1: + set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF); + break; + case 2: + set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF); + break; + case 3: + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF); + break; + case 4: + case 5: + set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON); + break; + } + } +} + +/** @} */ // end of group lowerlevelfun + + +//************************************** +//*** Bluetooth *** +//************************************** +/** @defgroup lowerlevelbluetooth Lower level bluetooth methods +* @{ +*/ +/** @brief starting the bluetooth service for the coderacer if not already started +* @param name the device will be listed by that name in your bluetooth device lists +* @return nothing +*/ +void CodeRacer::bt_start(String name) +{ + if (false == _bluetoothcreated) { + _BTSerial = new BluetoothSerial(); + _BTSerial->begin(name); + _bluetoothcreated = true; + } +} + +/** @brief enables the code to stop if there was no incoming message for the specified time. This will be checked everytime bt_getXXX or bt_msgavailable is called. +* @param timeout after that duration of milliseconds without an incoming bluetooth message the coderacer will be stopped. 0 means this stoppinf is disabled. +* @return nothing +*/ +void CodeRacer::bt_enable_stopOnLostConnection(unsigned long timeout) +{ + _bt_stopOnLostConnection_timeout_ms = timeout; +} + +/** @brief enables the code to stop if there was no incoming message for 1 second. This will be checked everytime bt_getXXX or bt_msgavailable is called. +* @return nothing +*/ +void CodeRacer::bt_enable_stopOnLostConnection() +{ + _bt_stopOnLostConnection_timeout_ms = 1000; +} + +/** @brief Disables the code to stop if there was no incoming message for a certain duration of time. +* @return nothing +*/ +void CodeRacer::bt_disable_stopOnLostConnection() +{ + _bt_stopOnLostConnection_timeout_ms = 0; +} + +/** @brief gets the bluetooth message string until a delimiter of 0 +* @return will return the string. If nothing is availbale or the service is not started it will return an empty string. +*/ +String CodeRacer::bt_getString() +{ + return bt_getString(0); +} + +/** @brief gets the bluetooth message string until a specified delimiter +* @return will return the string. If nothing is availbale or the service is not started it will return an empty string. +*/ +String CodeRacer::bt_getString(uint8_t delimiterbyte) +{ + String readstring = ""; + if (bt_msgavailable()) + { + readstring = _BTSerial->readStringUntil(delimiterbyte); + if (find(_bt_ignoremsgs.begin(), _bt_ignoremsgs.end(), readstring) != _bt_ignoremsgs.end()) + { + readstring = ""; + } + } + return(readstring); +} + +/** @brief add a String to a list of Strings that will be ignored if this is received via blue tooth. Ignores means - it will be read from the pipe but not returned to user code. But it will reset the message timeout counter. +* @param stringtoignore the String that has to be ignored. Will be added to the internal list if not already there. +*/ +void CodeRacer::bt_addStringToIgnoreList(String stringtoignore) +{ + std::vector::iterator it; + if (stringtoignore.length() > 0) + { + it = find(_bt_ignoremsgs.begin(), _bt_ignoremsgs.end() ,stringtoignore); + if (it == _bt_ignoremsgs.end()) + { + _bt_ignoremsgs.push_back(stringtoignore); + } + } +} + +/** @brief removes a String from the list of Strings that will be ignored if this is received via blue tooth. Ignores means - it will be read from the pipe but not returned to user code. But it will reset the message timeout counter. +* @param stringtoignore the String that has to be removed from the ignore list. +*/ +void CodeRacer::bt_removeStringFromIgnoreList(String stringtoignore) +{ + std::vector::iterator it; + if (stringtoignore.length() > 0) + { + it = find(_bt_ignoremsgs.begin(), _bt_ignoremsgs.end(), stringtoignore); + if (it != _bt_ignoremsgs.end()) + { + _bt_ignoremsgs.erase(it); + } + } +} + +/** @brief Clears the list of Strings that will be ignored if this is received via blue tooth. All elements of the list will be deleted from the list. +*/ +void CodeRacer::bt_clearIgnoreList() +{ + _bt_ignoremsgs.clear(); +} + + +/** @brief checks if a bluetooth is available. Will also stop the coderacer if there was nor message received for a certain time - and if stopping was enabled . +* @return true if a message is available , false if not message is available or the service was not started +*/ +bool CodeRacer::bt_msgavailable() +{ + bool rc = false; + if (true == _bluetoothcreated) { + if(_BTSerial->available()) + { + rc = true; + _bt_lastmessagereceived = millis(); + } + if (_bt_stopOnLostConnection_timeout_ms > 0) + { + if ((millis() - _bt_lastmessagereceived) > _bt_stopOnLostConnection_timeout_ms) + { + stop_driving(); + } + } + + } + return rc; +} + +/** @} */ // end of group lowerlevelbluetooth + +//************************************** +//*** Servo drive lower level control *** +//************************************** +/** @defgroup lowerlevelservo Lower level servo drive methods and getters +* @{ +*/ +/** @defgroup lowerlevelservomeths Methods +* @{ +*/ +/** @brief Overwrites the default settings taken from header file by the parameters given to this method +* @param pos_center The postion at which the servo moves to straight forward. Default is 90. Allowed 10 <= pos_center <= 170. +* @param pos_left The postion at which the servo moves to the left. Default is 170. Allowed 10 <= pos_center <= 170. +* @param pos_right The postion at which the servo moves to the right. Default is 10. Allowed 10 <= pos_center <= 170. +* @param sweep_left_pos If the servo is sweeping from left to the right - this defines the most left postion. Default is 140. Allowed 10 <= pos_center <= 170. +* @param sweep_right_pos If the servo is sweeping from left to the right - this defines the most right postion. Default is 40. Allowed 10 <= pos_center <= 170. +* @return nothing +*/ +void CodeRacer::servo_settings(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos) +{ + servo_center_pos = pos_center; + servo_left_pos = pos_left; + servo_right_pos = pos_right; + servo_sweep_left_pos = sweep_left_pos; + servo_sweep_right_pos = sweep_right_pos; +} + +/** @brief Turns sweeping of the servo from left to right and back on. +* +* The sweeping range is defind by #servo_sweep_left_pos and #servo_sweep_right_pos attributes. Both can be set by either servo_settings() or as public members. +* Every time servo_sweep() is called the servo is driven by 5 steps until either #servo_sweep_left_pos or #servo_sweep_right_pos is reached. Then it will turn the +* direction and step to the other side every time this method is called. +* @return nothing +*/ +void CodeRacer::servo_sweep() +{ + uint8_t position; + _servo_sweep = true; + if (millis() - _servo_position_set_at_ms > SERVO_SWEEP_MS) { + position = _servo_position + _servo_sweep_step; + //sprintf(_debugmsg,"[%s] current position=%ld newpostion=%ld", __func__, _servo_position, position); + if ((position >= servo_sweep_left_pos) || (position >= SERVO_MAX_POSITION)) { + position = servo_sweep_left_pos; + _servo_sweep_step = SERVO_SWEEP_TO_RIGHT_STEP; + } + if ((position <= servo_sweep_right_pos) || (position <= SERVO_MIN_POSITION)) { + position = servo_sweep_right_pos; + _servo_sweep_step = SERVO_SWEEP_TO_LEFT_STEP; + } + _servo_set_position(position); + } +} + +/** @brief Drives the servo to the postion that is defined by #servo_right_pos +* @return nothing +*/ +void CodeRacer::servo_set_to_right() +{ + servo_set_position_wait(servo_right_pos); +} + +/** @brief Drives the servo to the postion that is defined by #servo_left_pos +* @return nothing +*/ +void CodeRacer::servo_set_to_left() +{ + servo_set_position_wait(servo_left_pos); +} + +/** @brief Drives the servo to the postion that is defined by #servo_center_pos +* @return nothing +*/ +void CodeRacer::servo_set_to_center() +{ + servo_set_position_wait(servo_center_pos); +} + +/** @brief Drive the servo to the postion given to this method +* +* The method will wait until the servo has reached its new position. +* @param position Position the servo will be drived to. Allowed are values 10<=postion<=170. 10 is at the right hand side, 170 at the left hand side. +* @return The new servo position +*/ +uint8_t CodeRacer::servo_set_position_wait(uint8_t position) +{ + _servo_sweep = false; + unsigned long wait_time_ms = _servo_set_position(position); + delay(wait_time_ms); + return(_servo_position); +} + +/** @brief Drive the servo to the postion given to this method +* +* The method will not wait until the servo has reached its new position. +* @param position Position the servo will be drived to. Allowed are values 10<=postion<=170. 10 is at the right hand side, 170 at the left hand side. +* @return The time in ms the servo will need to reach the new position +*/ +unsigned long CodeRacer::servo_set_position(uint8_t position) +{ + _servo_sweep = false; + unsigned long wait_time_ms = _servo_set_position(position); + return(wait_time_ms); +} + +unsigned long CodeRacer::_servo_set_position(uint8_t position) +{ + uint8_t _position = position; + uint8_t absdiff; + + if (position < SERVO_MIN_POSITION) { + _position = SERVO_MIN_POSITION; + } + else if (position > SERVO_MAX_POSITION) { + _position = SERVO_MAX_POSITION; + } + _servo->write(_position); + // wait minimal delay to avoid code collaps + delay(SERVO_SET_1TICK_POSITION_DELAY_MS); + absdiff = abs(_servo_position - _position); + if (absdiff > 1) { + _servo_position_eta_in_ms = absdiff * SERVO_SET_1TICK_POSITION_DELAY_MS; + } + else { + _servo_position_eta_in_ms = 0; + } + + _servo_position_set_at_ms = millis(); + _servo_position = _position; + + return(_servo_position_eta_in_ms); +} + +/** @} */ // end of group lowerlevelservomeths +/** @defgroup lowerlevelservogetters Getters +* @{ +*/ + +/** @brief Get the actual position of the servo +* @return Actual position of the servo +*/ +uint8_t CodeRacer::servo_position() { + return(_servo_position); +} + +/** @brief Get the system time in ms the servo was set to the actual position +* @return System time in ms the servo was set +*/ +unsigned long CodeRacer::servo_position_set_at_ms() { + return(_servo_position_set_at_ms); +} + +/** @brief Get the system time in ms the servo will reach its position +* This is an estimated time. +* If this is a time in the future, the servo may still moving. +* If this is a time in the past , the servo should have reached its postion already. +* @return System time in ms the servo will reach its position +*/ +unsigned long CodeRacer::servo_position_eta_in_ms() { + return(_servo_position_eta_in_ms); +} + +/** @} */ // end of group lowerlevelservogetters +/** @} */ // end of group lowerlevelservo + + +//************************************** +//*** Ultrasonic lower level control *** +//************************************** +/** @defgroup lowerlevelus Lower level ultra sonic methods and getters +* @{ +*/ +/** @defgroup lowerlevelusmeths Methods +* @{ +*/ + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is the medium one out of 3 measurements. The maximum measured distance is about 100cm and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_cm() +{ + return(usonic_measure_cm(US_MAX_ECHO_TIME_US)); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is the medium one out of 3 measurements. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_us() + { + return(usonic_measure_us(US_MAX_ECHO_TIME_US)); + } + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is the medium one out of 3 measurements. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time and by that the maximum of distance that can be measured. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_cm(unsigned long max_echo_run_time_us) +{ + unsigned long echo_runtime_us = usonic_measure_us(max_echo_run_time_us); + unsigned long distance_cm = echo_runtime_us * 0.0172; + //Serial.print("MEASURE_DISTANCE. Distance in cm is: "); + //Serial.println(distance_cm); + _usonic_distance_cm = distance_cm; + return(distance_cm); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is the medium one out of 3 measurements. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_us(unsigned long max_echo_run_time_us) +{ + unsigned long echo_runtime_us[3] = { 0,0,0 }; + uint8_t measnr = 0; + + do { + echo_runtime_us[measnr] = usonic_measure_single_shot_us(max_echo_run_time_us); + if (echo_runtime_us[measnr] > 200) { + measnr++; + } + } while (measnr < 3); + + // we will take the medium out of 3 values ... + if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); } + if (echo_runtime_us[1] > echo_runtime_us[2]) { std::swap(echo_runtime_us[1], echo_runtime_us[2]); } + if (echo_runtime_us[0] > echo_runtime_us[1]) { std::swap(echo_runtime_us[0], echo_runtime_us[1]); } + + //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: "); + //Serial.println(echo_runtime_us[1]); + + // if the stop at minimal distance is enabeled - check for minimal distance is reached + if (true == _coderacer_stop_at_distance_enabled) { + if (echo_runtime_us[1] <= _usonic_stop_distance_us) { + _coderacer_stopped_at_min_distance = true; + stop_driving(); + _coderacer_stop_at_distance_enabled = false; + } + } + _usonic_distance_us = echo_runtime_us[1]; + return(echo_runtime_us[1]); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_cm() +{ + return(usonic_measure_single_shot_cm(US_MAX_ECHO_TIME_US)); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is a one shot measurement. The maximum measured distance is about 6000 microseconds and defined by the US_MAX_ECHO_TIME_US setting in the header file. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_us() +{ + return(usonic_measure_single_shot_us(US_MAX_ECHO_TIME_US)); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in cm. +* +* This is a one shot measurement. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. +* @return The measured distance in cm. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_cm(unsigned long max_echo_run_time_us) +{ + // 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; + unsigned long echo_runtime_us = usonic_measure_single_shot_us(max_echo_run_time_us); + unsigned long distance_cm = echo_runtime_us * 0.0172; + //Serial.print("MEASURE_DISTANCE. Distance in cm is: "); + //Serial.println(distance_cm); + _usonic_distance_cm = distance_cm; + return(distance_cm); +} + +/** @brief Measures the distance to the next object in front of the ultra sonic sensor in microseconds. +* +* This is a one shot measurement. Be careful with high values for max_echo_run_time_us - this may increase run time due to the fact that if there is nothing in range of the sensor it will wait until this specified run time of the echo is over. +* The maximum range the sensor is specified for is about 300cm. +* @param max_echo_run_time_us Defines the maximum echo run time in microseconds and by that the maximum of distance that can be measured. +* @return The measured distance in microseconds. +*/ +unsigned long CodeRacer::usonic_measure_single_shot_us(unsigned long max_echo_run_time_us) + { + unsigned long echo_runtime_us; + // start measurement - send a short pulse "HIGH" to the TRIG pin of the ultrasonic sensor + 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); + // measure runtime in microseconds until the ECHO pin aof the sensor goes HIGH + echo_runtime_us = pulseInLong(_us_echo_pin, HIGH, max_echo_run_time_us); + if (echo_runtime_us == 0) { + echo_runtime_us = max_echo_run_time_us; // US_MAX_ECHO_TIME_US; + } + //Serial.print("MEASURE_DISTANCE_US. Echo runtime in us is: "); + //Serial.println(echo_runtime_us); + _usonic_distance_us = echo_runtime_us; + return(echo_runtime_us); + } + +/** @} */ // end of group lowerlevelusmethods +/** @defgroup lowerlevelusgetters Setters and getters +* @{ +*/ + +/** @brief Sets the stop distance in cm. +* +* If start_stop_at_min_distance() is used and distance measured with one of the measurement methods - the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. +* Internally the stop distance will be set as both - in cm and in microseconds. +* @param stop_distance_cm Distance in cm the racer will be stopped if that features was enabled by start_stop_at_min_distance() before. +* @return nothing +*/ +void CodeRacer::usonic_set_stop_distance_cm(unsigned long stop_distance_cm) +{ + _usonic_stop_distance_us = stop_distance_cm * 58.14; +} + +/** @brief Sets the stop distance in cm. +* +* If start_stop_at_min_distance() is used and distance measured with one of the measurement methods - the racer will be stopped immediately. All except the singe shot methods of the ultra sonic measurements methods supports that. +* Internally the stop distance will be set as both - in cm and in microseconds. +* @param stop_distance_us Distance in cm the racer will be stopped if that features was enabled by start_stop_at_min_distance() before. +* @return nothing +*/ +void CodeRacer::usonic_set_stop_distance_us(unsigned long stop_distance_us) +{ + _usonic_stop_distance_us = stop_distance_us; +} + +/** @brief Returns the last measured distance in microseconds +* @return Distance in microseconds +*/ +unsigned long CodeRacer::usonic_distance_us() { + return(_usonic_distance_us); +} + +/** @brief Returns the last measured distance in cm +* @return Distance in cm +*/ +unsigned long CodeRacer::usonic_distance_cm() { + return(_usonic_distance_cm); +} + +/** @} */ // end of group lowerlevelusgetters +/** @} */ // end of group lowerlevelus + + +//************************************** +//*** Drives lower level control *** +//************************************** + +/** @defgroup lowerleveldrives Lower level drives methods and getters +* @{ +*/ +/** @defgroup lowerleveldrivesmeths Methods +* @{ +*/ + +/** @brief Overwrites some drive settings. This will replace the defaults set by the values in the header file. +* @param drive_left_speed Speed of the left side drive +* @param drive_right_speed Speed of the right side drive +* @param turn_left_for_ms Time in ms the racer will turn to the left around its center if turn_left() is called +* @param turn_right_for_ms Time in ms the racer will turn to the right around its center if turn_right() is called +* @return nothing +*/ +void CodeRacer::drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_for_ms, unsigned long turn_right_for_ms) +{ + _drive_left_speed = drive_left_speed; + _drive_right_speed = drive_right_speed; + _turn_left_for_ms = turn_left_for_ms; + _turn_right_for_ms = turn_right_for_ms; +} + +/** @brief Stopps both drives +* @return nothing +*/ +void CodeRacer::set_drives_stop_left_right() { + set_drive_left_state(DRIVESTOP); + set_drive_right_state(DRIVESTOP); +} + +/** @brief Sets both of the drives to a specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param stateleft drivestate to set for the left side drive +* @param stateright drivestate to set for the right side drive +* @return nothing +*/ +void CodeRacer::set_drives_states_left_right(drivestate stateleft, drivestate stateright) { + set_drive_left_state(stateleft); + set_drive_right_state(stateright); +} + +/** @brief Sets the left side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param state drivestate to set for the left side drive +* @return nothing +*/ +void CodeRacer::set_drive_left_state(drivestate state) { + set_drive_state(state, _drive_left_frwd_pin, _drive_left_back_pin); +} + +/** @brief Sets the right side drive to the specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param state drivestate to set for the right side drive +* @return nothing +*/ +void CodeRacer::set_drive_right_state(drivestate state) { + set_drive_state(state, _drive_right_frwd_pin, _drive_right_back_pin); +} + +/** @brief Sets the specified drivestate for the drive connected to the sepecified pins (DRIVESTOP, DRIVEFRWD, DRIVEBACK) +* @param state drivestate to set for the connected drive +* @param frwdpin Pin the forward signal of the drive device driver is connected at +* @param backpin Pin the backward signal of the drive device driver is connected at +* @return nothing +*/ +void CodeRacer::set_drive_state(drivestate state, uint8_t frwdpin, uint8_t backpin) { + switch (state) { + case DRIVESTOP: + digitalWrite(frwdpin, LOW); + digitalWrite(backpin, LOW); + break; + case DRIVEFRWD: + digitalWrite(frwdpin, HIGH); + digitalWrite(backpin, LOW); + break; + case DRIVEBACK: + digitalWrite(frwdpin, LOW); + digitalWrite(backpin, HIGH); + break; + } +} + +/** @brief Sets the speed for both of the drives. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speedleft speed of the left side drive. 0<=speed<=255 +* @param speedright speed of the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::set_drives_speed_left_right(uint8_t speedleft, uint8_t speedright) { + set_drive_left_speed(speedleft); + set_drive_right_speed(speedright); +} + +/** @brief Sets the speed for the left side drive. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speed speed of the left side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::set_drive_left_speed(uint8_t speed) { + set_drive_speed(speed, _drive_left_enable_pin); +} + +/** @brief Sets the speed for the right side drive. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speed speed of the right side drive. 0<=speed<=255 +* @return nothing +*/ +void CodeRacer::set_drive_right_speed(uint8_t speed) { + set_drive_speed(speed, _drive_right_enable_pin); +} + +/** @brief Sets the speed for the drive of the enable pin connected to the specified pin. +* +* The drive will run with that speed afterwards. The direction of the drive has to be specfied with one of the set_drive_state methods before +* @param speed speed of the drive. 0<=speed<=255 +* @param enablepin Pin the drives device driver enable pin is connected at +* @return nothing +*/ +void CodeRacer::set_drive_speed(uint8_t speed, uint8_t enablepin) { + _analog_write(enablepin, (int)speed); +} + +/** @} */ // end of group lowerleveldrivesmethods +/** @defgroup lowerleveldrivesgetters Getters +* @{ +*/ + +/** @brief Get the setting for the speed of the right side drive +* @return Speed of the right side drive +*/ +uint8_t CodeRacer::drive_right_speed() { + return _drive_right_speed; +} + +/** @brief Get the setting for the speed of the left side drive +* @return Speed of the left side drive +*/ +uint8_t CodeRacer::drive_left_speed() { + return(_drive_left_speed); +} + +void CodeRacer::_analog_write(uint8_t pin, uint8_t speed) { + if (pin == _drive_left_enable_pin) { + _drive_left_speed = speed; + ledcWrite(DRIVE_PWM_LEFT_CHANNEL, speed); + } + if (pin == _drive_right_enable_pin) { + _drive_right_speed = speed; + ledcWrite(DRIVE_PWM_RIGHT_CHANNEL, speed); + } +} + +/** @} */ // end of group lowerleveldrivesgetters +/** @} */ // end of group lowerleveldrives + + +//************************************** +//*** LED lower level control *** +//************************************** +/** @defgroup lowerlevelled Lower level LED methods +* @{ +*/ +/** @defgroup lowerlevelledmeths Methods +* @{ +*/ + +/** @brief Sets all of the 4 LEDs to a ledstate (LEDON, LEDOFF) +* @param leftled set state of status left LED (most left yellow led) +* @param stopled set state of status stop LED (red led) +* @param frwdled set state of status forward LED (green or blue led) +* @param rightled set state of status right LED (most right yellow led) +* @return nothing +*/ +void CodeRacer::set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled) { + digitalWrite(_led_left_pin, leftled); + digitalWrite(_led_frwd_pin, frwdled); + digitalWrite(_led_right_pin, rightled); + digitalWrite(_led_stop_pin, stopled); +} + +/** @brief Sets all of the 4 LEDs to the same ledstate (LEDON, LEDOFF) +* @param alleds set state to all status LEDs +* @return nothing +*/ +void CodeRacer::set_leds_all(ledstate alleds) { + digitalWrite(_led_left_pin, alleds); + digitalWrite(_led_frwd_pin, alleds); + digitalWrite(_led_right_pin, alleds); + digitalWrite(_led_stop_pin, alleds); +} + +/** @brief Sets all of the 4 LEDs to the ledstate LEDOFF +* @return nothing +*/ +void CodeRacer::set_leds_all_off() { + set_leds_all(LEDOFF); +} + +/** @brief Sets all of the 4 LEDs to the ledstate LEDON +* @return nothing +*/ +void CodeRacer::set_leds_all_on() { + set_leds_all(LEDON); +} + +/** @} */ // end of group lowerlevelledmets +/** @} */ // end of group lowerlevelled + + +//************************************** +//*** ISRs *** +//************************************** +//IRAM_ATTR is used to load the code into DRAM and not to Flash to make it faster - required for ISRs +void IRAM_ATTR CodeRacer::_set_button_state() { + if ((millis() - button_last_pressed_at_ms) > BUTTON_BOUNCING_TIME_MS) { + button_last_pressed_at_ms = millis(); // simplest debouncing - just wait ;-) + coderracer_activ = !coderracer_activ; + } +} + + +//********************************************************************************************************************** +//** Methods below this are obsolete and only in here for compatiblity to other projects - do not use them anymore !!! +//********************************************************************************************************************** +void CodeRacer::motor_einstellungen(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_for_ms, unsigned long turn_right_for_ms) +{ + drives_settings(drive_left_speed, drive_right_speed, turn_left_for_ms, turn_right_for_ms); +} + +void CodeRacer::servo_einstellungen(uint8_t pos_center, uint8_t pos_left, uint8_t pos_right, uint8_t sweep_left_pos, uint8_t sweep_right_pos) +{ + servo_settings(pos_center, pos_left, pos_right, sweep_left_pos, sweep_right_pos); +} + +void CodeRacer::servo_rechts() +{ + Serial.println("SERVO_RECHTS"); // Meldung am Monitor ausgeben + servo_set_to_right(); // Servo auf den Winkel rechts drehen +} + +void CodeRacer::servo_links() +{ + Serial.println("SERVO_LINKS"); // Meldung am Monitor ausgeben + servo_set_to_left(); // Servo auf den Winkel links drehen +} + +void CodeRacer::servo_mitte() +{ + Serial.println("SERVO_MITTE"); + servo_set_to_center(); +} + +void CodeRacer::servo_schwenk() +{ + servo_sweep(); +} + +void CodeRacer::links() +{ + Serial.println("CODERACER_LINKS"); + turn_left(); +} + +void CodeRacer::rechts() +{ + Serial.println("CODERACER_RECHTS"); + turn_right(); +} + +void CodeRacer::anhalten() +{ + Serial.println("CODERACER_ANHALTEN"); + stop_driving(); +} + +void CodeRacer::vorwaerts() +{ + Serial.println("CODERACER_VORWAERTS"); + drive_forward(); +} + +void CodeRacer::rueckwaerts() +{ + Serial.println("CODERACER_RUECKWAERTS"); + drive_backward(); +} + +unsigned long CodeRacer::abstand_messen() +{ + return(0); + + unsigned long distance_cm = 0; + unsigned long min_distance_cm = 1000; + int8_t servo_turn_direction = 0; + + + // while driving or sweeping there will be only one value be measured - else there will be mutiple measurements and the servor will be turning + if (((true == _drive) || (servo_center_pos == _servo_position) || _servo_sweep == true)) { + // while driving ... + //Serial.println("ABSTAND_MESSEN im fahren, direkt nach vorn oder Schwenk() ist aktiv ..."); + min_distance_cm = usonic_measure_cm(); + } else { + // no sweep, not driving ... + //Serial.println("ABSTAND_MESSEN im Stand nach links oder rechts..."); + // are we already ath left or right with the servo ? + if (servo_left_pos == _servo_position) { + //Serial.println("ABSTAND_MESSEN. Linke Seite."); + //left ... + servo_turn_direction = SERVO_SWEEP_TO_RIGHT_STEP; + } + if (servo_right_pos == _servo_position) { + //right ... + //Serial.println("ABSTAND_MESSEN rechte Seite."); + servo_turn_direction = SERVO_SWEEP_TO_LEFT_STEP; + } + // trun the servo and do measuring ... remember the smallest value + do { + _servo_set_position(_servo_position + servo_turn_direction); + //Serial.print("ABSTAND_MESSEN. Servo position:"); + //Serial.println(_servo_position); + distance_cm = usonic_measure_cm(); + if (distance_cm < min_distance_cm) { + min_distance_cm = distance_cm; + } + } while ((_servo_position > H_SERVO_CENTER_LEFT) || (_servo_position < H_SERVO_CENTER_RIGHT)); + } + + Serial.print("ABSTAND_MESSEN. Der Abstand in cm ist (mindestens):"); + Serial.println(min_distance_cm); + //_min_distance_cm = min_distance_cm; + + return(min_distance_cm); + +} + +//********************************************************************************************************************** +//** Helper methods +//********************************************************************************************************************** + diff --git a/esp32_coderacer/lib/CodeRacer/CodeRacer.h b/esp32_coderacer/lib/CodeRacer/CodeRacer.h new file mode 100644 index 0000000..d006475 --- /dev/null +++ b/esp32_coderacer/lib/CodeRacer/CodeRacer.h @@ -0,0 +1,282 @@ +#include "Arduino.h" +#include // std::swap +#include // 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 // support for vectors +#include + +#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 _bt_ignoremsgs; + std::vector _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 diff --git a/esp32_coderacer/lib/CodeRacer/examples/SimpleBTCoderacer/SimpleBTCoderacer.ino b/esp32_coderacer/lib/CodeRacer/examples/SimpleBTCoderacer/SimpleBTCoderacer.ino new file mode 100644 index 0000000..bfb432e --- /dev/null +++ b/esp32_coderacer/lib/CodeRacer/examples/SimpleBTCoderacer/SimpleBTCoderacer.ino @@ -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 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); +} + + diff --git a/esp32_coderacer/lib/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino b/esp32_coderacer/lib/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino new file mode 100644 index 0000000..0ac2270 --- /dev/null +++ b/esp32_coderacer/lib/CodeRacer/examples/esp32_coderacer_beispiel/esp32_coderacer_beispiel.ino @@ -0,0 +1,82 @@ +#include + +//----- 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(); + + } + +} + + + diff --git a/esp32_coderacer/lib/CodeRacer/keywords.txt b/esp32_coderacer/lib/CodeRacer/keywords.txt new file mode 100644 index 0000000..1f6ab67 --- /dev/null +++ b/esp32_coderacer/lib/CodeRacer/keywords.txt @@ -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 \ No newline at end of file diff --git a/esp32_coderacer/lib/README b/esp32_coderacer/lib/README new file mode 100644 index 0000000..8c9c29c --- /dev/null +++ b/esp32_coderacer/lib/README @@ -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 +#include + +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 diff --git a/esp32_coderacer/platformio.ini b/esp32_coderacer/platformio.ini new file mode 100644 index 0000000..fa532b9 --- /dev/null +++ b/esp32_coderacer/platformio.ini @@ -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 + diff --git a/esp32_coderacer/src/esp32_coderacer.cpp b/esp32_coderacer/src/esp32_coderacer.cpp new file mode 100644 index 0000000..843b869 --- /dev/null +++ b/esp32_coderacer/src/esp32_coderacer.cpp @@ -0,0 +1,128 @@ +#include "CodeRacer.h" + +#include +#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; + } + +} + + + diff --git a/esp32_coderacer/test/README b/esp32_coderacer/test/README new file mode 100644 index 0000000..c3b0ed6 --- /dev/null +++ b/esp32_coderacer/test/README @@ -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