BRAND new version of CodeRacerMKII including asynchronous webserver

This commit is contained in:
jglueck 2020-08-21 11:21:29 +02:00
parent 3d32010ab6
commit c69acef5ef
7 changed files with 434 additions and 262 deletions

View file

@ -11,20 +11,22 @@ static volatile unsigned int left_step_counter=0;
static volatile unsigned int left_step_stopcount=0; static volatile unsigned int left_step_stopcount=0;
static volatile unsigned int right_step_counter=0; static volatile unsigned int right_step_counter=0;
static volatile unsigned int right_step_stopcount=0; static volatile unsigned int right_step_stopcount=0;
static volatile bool syncstop= 0; static volatile bool syncstop= true;
static volatile bool _drive; static volatile bool _drive;
static volatile float timebeforeleft= 0; static volatile float timebeforeleft= 0;
static volatile float timebeforeright= 0; static volatile float timebeforeright= 0;
static volatile float timeafterleft= 0; static volatile float timeafterleft= 0;
static volatile float timeafterright= 0; static volatile float timeafterright= 0;
static volatile bool obstacle_stop= false; static volatile bool obstacle_stop= true;
static volatile bool obstacle_left_side= false; static volatile bool obstacle_left_side= false;
static volatile bool obstacle_right_side= false; static volatile bool obstacle_right_side= false;
static volatile bool coderracer_activ = false; static volatile bool coderracer_activ = false;
static volatile bool right_button_pressed =false; static volatile bool right_button_pressed =false;
static volatile unsigned int right_button_count=0; static volatile unsigned int right_button_count=0;
static volatile unsigned int driven_distance= 0;
static volatile unsigned long left_button_last_pressed_at_ms = millis(); static volatile unsigned long left_button_last_pressed_at_ms = millis();
static volatile unsigned long right_button_last_pressed_at_ms = millis(); static volatile unsigned long right_button_last_pressed_at_ms = millis();
static String debug_message= "";
/** @brief CodeRace constructor without pins. All pins settings taken from the coderacer header file /** @brief CodeRace constructor without pins. All pins settings taken from the coderacer header file
@ -102,6 +104,7 @@ CodeRacerMKII::CodeRacerMKII(uint8_t button_pin_left , uint8_t button_pin_right,
_led_right_pin = led_right_pin; _led_right_pin = led_right_pin;
_led_blue_pin = led_blue_pin; _led_blue_pin = led_blue_pin;
_led_white_pin= led_white_pin; _led_white_pin= led_white_pin;
} }
/** @brief Initialisation of all attributes and settings of the coderacer. Defaults are taken from the header file. /** @brief Initialisation of all attributes and settings of the coderacer. Defaults are taken from the header file.
@ -204,7 +207,11 @@ void CodeRacerMKII::begin() {
randomSeed(analogRead(0)); randomSeed(analogRead(0));
//fun stuff //fun stuff
coderacer_fun_enabled = false; coderacer_fun_enabled = true;
servo_set_to_center();
//the Debug string for webserver
} }
//************************************** //**************************************
@ -217,7 +224,7 @@ void CodeRacerMKII::begin() {
* @{ * @{
*/ */
/** @brief Stops the racer and sets status LEDs. /** @brief Stops the racer.
* @return nothing * @return nothing
*/ */
void CodeRacerMKII::stop_driving() { void CodeRacerMKII::stop_driving() {
@ -225,7 +232,7 @@ void CodeRacerMKII::stop_driving() {
_drive = false; _drive = false;
global_stop_driving(); global_stop_driving();
//set_drives_stop_left_right(); //set_drives_stop_left_right();
//set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF); //set_leds(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
} }
/** @brief Sets the speed and the directions of both drives so that it will move forward. /** @brief Sets the speed and the directions of both drives so that it will move forward.
@ -249,10 +256,20 @@ void CodeRacerMKII::drive_forward(uint8_t left_speed, uint8_t right_speed)
{ {
set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD); set_drives_states_left_right(DRIVEFRWD, DRIVEFRWD);
set_drives_speed_left_right(left_speed, right_speed); set_drives_speed_left_right(left_speed, right_speed);
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF); wifi_printf("Driving forward...");
set_leds(LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF);
_drive = true; _drive = true;
_drive_set_at_ms = millis(); _drive_set_at_ms = millis();
} }
/** @brief tells the Coderacer to drive forward for a specified amount of time and stop afterwards
* @param time time in ms the coderacer will drive
* @return nothing
*/
void CodeRacerMKII::drive_forward_for_ms(unsigned long time ){
drive_forward();
wait_ms(time);
stop_driving();
}
/** @brief Sets the speed and the directions of both drives so that it will move backward. /** @brief Sets the speed and the directions of both drives so that it will move backward.
* *
@ -275,11 +292,22 @@ void CodeRacerMKII::drive_backward(uint8_t left_speed, uint8_t right_speed)
{ {
set_drives_states_left_right(DRIVEBACK, DRIVEBACK); set_drives_states_left_right(DRIVEBACK, DRIVEBACK);
set_drives_speed_left_right(left_speed, right_speed); set_drives_speed_left_right(left_speed, right_speed);
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF); wifi_printf("Driving Backwards...");
set_leds(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF);
_drive = true; _drive = true;
_drive_set_at_ms = millis(); _drive_set_at_ms = millis();
} }
/** @brief tells the Coderacer to drive backward for a specified amount of time and stop afterwards
* @param time time in ms the coderacer will drive
* @return nothing
*/
void CodeRacerMKII::drive_backward_for_ms(unsigned long time){
drive_backward();
wait_ms(time);
stop_driving();
}
/** @brief Will turn the racer to the left for the internally stroe time in ms and with the internally stored speed. /** @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 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.
@ -291,7 +319,7 @@ void CodeRacerMKII::turn_left()
turn_left(_turn_left_for_ms, _drive_left_speed, _drive_right_speed); 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. /** @brief Will turn the racer to the left for a 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() * 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 * @param turn_for_ms duration of time in ms to turn the racer
@ -313,17 +341,19 @@ void CodeRacerMKII::turn_left(unsigned long turn_for_ms)
void CodeRacerMKII::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed) void CodeRacerMKII::turn_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
{ {
_drive = false; _drive = false;
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen set_leds(LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
set_drives_states_left_right(DRIVEBACK, DRIVEFRWD); set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
set_drives_speed_left_right(left_speed, right_speed); set_drives_speed_left_right(left_speed, right_speed);
wifi_printf("Turning left! <p>");
// wait set delay for the timed turn // wait set delay for the timed turn
_turn_left_for_ms = turn_for_ms; _turn_left_for_ms = turn_for_ms;
delay(_turn_left_for_ms); wait_ms(_turn_left_for_ms);
// stop drives again // stop drives again
set_drives_stop_left_right(); global_stop_driving();
} }
/** @brief Will turn the racer to the right for the internally stroe time in ms and with the internally stored speed. /** @brief Will turn the racer to the right for the internally stored 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 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. * The method is delayed until the racer has turned.
@ -356,17 +386,18 @@ void CodeRacerMKII::turn_right(unsigned long turn_for_ms)
void CodeRacerMKII::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed) void CodeRacerMKII::turn_right(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed)
{ {
_drive = false; _drive = false;
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen set_leds(LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF); // LEDs setzen
set_drives_states_left_right(DRIVEFRWD, DRIVEBACK); set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
set_drives_speed_left_right(left_speed, right_speed); set_drives_speed_left_right(left_speed, right_speed);
wifi_printf("Turning right! <p>");
// wait set delay for the timed turn // wait set delay for the timed turn
_turn_right_for_ms = turn_for_ms; _turn_right_for_ms = turn_for_ms;
delay(_turn_right_for_ms); wait_ms(_turn_right_for_ms);
// stop drives again // stop drives again
set_drives_stop_left_right(); global_stop_driving();
} }
/** @brief Enables to stopp the racer if during a distance measurement the measured distance is smaller then the internally stored minimal distance. /** @brief Enables to stop 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. * 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. * If the racer was stopped can be checked with stopped_at_min_distance() - it will return true in that case.
@ -430,6 +461,22 @@ bool CodeRacerMKII::start_stop() {
return(_coderracer_activ); return(_coderracer_activ);
} }
/** @brief Returns the current message saved in debug_message. Is called every 750ms in an AJAX event on the webserver.
* @return debug_message
*/
String CodeRacerMKII::wifi_printf(){
return debug_message;
}
/** @brief Almost the same as wifi_printf(), but with a specified message to send to the webserver. can be used to send custom messages for debugging.
* @param Content the message specified by user
* @return debug_message
*/
String CodeRacerMKII::wifi_printf(String Content){
debug_message= Content;
return debug_message;
}
/** @} */ // end of group higherlevelmeths /** @} */ // end of group higherlevelmeths
/** @defgroup higherlevelgetters Getters and setters /** @defgroup higherlevelgetters Getters and setters
* @{ * @{
@ -516,8 +563,7 @@ unsigned int CodeRacerMKII::button_count() {
* @return driven_distance * @return driven_distance
*/ */
unsigned int CodeRacerMKII::show_distance_mm(){ unsigned int CodeRacerMKII::show_distance_mm(){
int driven_distance; driven_distance= ((left_step_counter*DISTANCE_PER_TICK_MM)+ (right_step_counter*DISTANCE_PER_TICK_MM))/2;
driven_distance= left_step_counter*DISTANCE_PER_TICK_MM;
return driven_distance; return driven_distance;
} }
/** @brief returns the current stepcount of the PE barrier of the left wheel /** @brief returns the current stepcount of the PE barrier of the left wheel
@ -601,25 +647,25 @@ void CodeRacerMKII::kitt()
_last_led_on = _last_led_on + _led_count; _last_led_on = _last_led_on + _led_count;
switch (_last_led_on) { switch (_last_led_on) {
case 0: case 0:
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF); set_leds(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF);
break; break;
case 1: case 1:
set_leds_left_stop_frwd_right(LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF); set_leds(LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF);
break; break;
case 2: case 2:
set_leds_left_stop_frwd_right(LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF); set_leds(LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF, LEDOFF);
break; break;
case 3: case 3:
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF); set_leds(LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF, LEDOFF);
break; break;
case 4: case 4:
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF); set_leds(LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF, LEDOFF);
break; break;
case 5: case 5:
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF); set_leds(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON, LEDOFF);
break; break;
case 6: case 6:
set_leds_left_stop_frwd_right(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON); set_leds(LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDOFF, LEDON);
} }
} }
} }
@ -848,7 +894,7 @@ uint8_t CodeRacerMKII::servo_set_position_wait(uint8_t position)
{ {
_servo_sweep = false; _servo_sweep = false;
unsigned long wait_time_ms = _servo_set_position(position); unsigned long wait_time_ms = _servo_set_position(position);
delay(wait_time_ms); wait_ms(wait_time_ms);
return(_servo_position); return(_servo_position);
} }
@ -1165,13 +1211,18 @@ void CodeRacerMKII::drives_settings(uint8_t drive_left_speed, uint8_t drive_righ
_turn_left_for_ms = turn_left_for_ms; _turn_left_for_ms = turn_left_for_ms;
_turn_right_for_ms = turn_right_for_ms; _turn_right_for_ms = turn_right_for_ms;
} }
/** @brief "Resets" the Racer. In detail, stops driving as well as setting both step counters to 0. The variable for the distance driven also gets set to 0,
/** @brief Stopps both drives * speed settings are reverted to their default (128), if a change to them has been made. Finally, the servo gets set to the center.
* @return nothing * @return nothing
*/ */
void CodeRacerMKII::set_drives_stop_left_right() { void CodeRacerMKII::Reset_Stats(){
set_drive_left_state(DRIVESTOP); global_stop_driving();
set_drive_right_state(DRIVESTOP); left_step_counter=0;
right_step_counter=0;
driven_distance=0;
speed_settings(128, 128);
servo_set_to_center();
wifi_printf("Resetted stats.");
} }
/** @brief Sets both of the drives to a specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK) /** @brief Sets both of the drives to a specified drivestate (DRIVESTOP, DRIVEFRWD, DRIVEBACK)
@ -1336,7 +1387,7 @@ void CodeRacerMKII::drive_ticks(unsigned int tickleft, unsigned int tickright){
* @return nothing * @return nothing
*/ */
void CodeRacerMKII::turn_degree(int degree){ void CodeRacerMKII::turn_degree(int degree){
// sets thhe drive states for both wheels and by that the direction the racer will turn. // sets the drive states for both wheels and by that the direction the racer will turn.
if(degree>0) if(degree>0)
{ {
set_drives_states_left_right(DRIVEFRWD, DRIVEBACK); set_drives_states_left_right(DRIVEFRWD, DRIVEBACK);
@ -1346,13 +1397,15 @@ void CodeRacerMKII::turn_degree(int degree){
set_drives_states_left_right(DRIVEBACK, DRIVEFRWD); set_drives_states_left_right(DRIVEBACK, DRIVEFRWD);
degree= abs(degree); degree= abs(degree);
} }
else set_drives_states_left_right(DRIVESTOP, DRIVESTOP); else {set_drives_states_left_right(DRIVESTOP, DRIVESTOP);}
// calculates the number of ticks for both wheels and tells the racer to drive with the internally stored driving speed // calculates the number of ticks for both wheels and tells the racer to drive with the internally stored driving speed
int Ticks= degree*TICKS_OF_ONE_DEGREE; int Ticks= degree*TICKS_OF_ONE_DEGREE;
drive_ticks_left(Ticks, false); drive_ticks_left(Ticks, false);
drive_ticks_right(Ticks, false); drive_ticks_right(Ticks, false);
set_drives_speed_left_right(_drive_left_speed, _drive_right_speed); set_drives_speed_left_right(_drive_left_speed, _drive_right_speed);
_drive= true; _drive= true;
while(true==is_driving()){}
} }
/** @brief tells the coderacer to drive a specified number of ticks for the left wheel. /** @brief tells the coderacer to drive a specified number of ticks for the left wheel.
* @param Ticks number of ticks * @param Ticks number of ticks
@ -1402,6 +1455,7 @@ void CodeRacerMKII::drive_distance_right_mm(int distance_mm){
* @return true or false if an obstacle has been identified * @return true or false if an obstacle has been identified
*/ */
bool CodeRacerMKII::obstacle_check_left_right(){ bool CodeRacerMKII::obstacle_check_left_right(){
//still needs a bit of fine tuning... currently, using digitalRead(), the infrared sensors can only "see" obstacles within 1cm in front of them.
if((true== obstacle_check_left()) || (true== obstacle_check_right())) if((true== obstacle_check_left()) || (true== obstacle_check_right()))
{ {
return true; return true;
@ -1424,7 +1478,7 @@ bool CodeRacerMKII::obstacle_check_right(){
* @return true if voltage is present, false if not * @return true if voltage is present, false if not
*/ */
bool CodeRacerMKII::obstacle_check(uint8_t sensorpin) { bool CodeRacerMKII::obstacle_check(uint8_t sensorpin) {
if (true== digitalRead(sensorpin)) { if (digitalRead(sensorpin)== HIGH) {
return true; return true;
} }
else {return false;} else {return false;}
@ -1453,7 +1507,7 @@ bool CodeRacerMKII::obstacle_check(uint8_t sensorpin) {
* @param whiteled set state of white LED * @param whiteled set state of white LED
* @return nothing * @return nothing
*/ */
void CodeRacerMKII::set_leds_left_stop_frwd_right(ledstate leftled, ledstate rightled, ledstate stopled, ledstate frwrdled, ledstate blueled, ledstate whiteled) { void CodeRacerMKII::set_leds(ledstate leftled, ledstate rightled, ledstate stopled, ledstate frwrdled, ledstate blueled, ledstate whiteled) {
digitalWrite(_led_left_pin, leftled); digitalWrite(_led_left_pin, leftled);
digitalWrite(_led_right_pin, rightled); digitalWrite(_led_right_pin, rightled);
digitalWrite(_led_stop_pin, stopled); digitalWrite(_led_stop_pin, stopled);
@ -1520,6 +1574,7 @@ static void IRAM_ATTR global_stop_driving(){
{ {
ledcWrite(DRIVE_PWM_LEFT_CHANNEL, 0); ledcWrite(DRIVE_PWM_LEFT_CHANNEL, 0);
} }
debug_message+="Stopped.";
digitalWrite(H_LED_RIGHT_PIN, LOW); digitalWrite(H_LED_RIGHT_PIN, LOW);
digitalWrite(H_LED_LEFT_PIN, LOW); digitalWrite(H_LED_LEFT_PIN, LOW);
digitalWrite(H_LED_STOP_PIN, HIGH); digitalWrite(H_LED_STOP_PIN, HIGH);
@ -1527,13 +1582,19 @@ static void IRAM_ATTR global_stop_driving(){
digitalWrite(H_LED_BLUE_PIN, LOW); digitalWrite(H_LED_BLUE_PIN, LOW);
digitalWrite(H_LED_WHITE_PIN, LOW); digitalWrite(H_LED_WHITE_PIN, LOW);
_drive= false; _drive= false;
digitalWrite(H_LED_RIGHT_PIN, LOW);
digitalWrite(H_LED_LEFT_PIN, LOW);
digitalWrite(H_LED_STOP_PIN, LOW);
digitalWrite(H_LED_FRWD_PIN, LOW);
digitalWrite(H_LED_BLUE_PIN, LOW);
digitalWrite(H_LED_WHITE_PIN, LOW);
} }
/** @brief this routine is called each time the left PE barrier changes its state. it increments (and by that counts) the ticks driven by the left wheel and is also instructed to stop the racer if the stopcount set by drive_ticks() is reached using the global_stop_driving() routine /** @brief this routine is called each time the left PE barrier changes its state. it increments (and by that counts) the ticks driven by the left wheel and is also instructed to stop the racer if the stopcount set by drive_ticks() is reached using the global_stop_driving() routine
* @return nothing * @return nothing
*/ */
static void IRAM_ATTR _count_steps_left() { static void IRAM_ATTR _count_steps_left() {
timeafterleft= millis(); //timeafterleft= millis();
timebeforeleft = timebeforeleft == 0 ? timeafterleft : timebeforeleft; //timebeforeleft = timebeforeleft == 0 ? timeafterleft : timebeforeleft;
left_step_counter++; left_step_counter++;
if (left_step_counter==left_step_stopcount) if (left_step_counter==left_step_stopcount)
{ {
@ -1541,13 +1602,15 @@ static void IRAM_ATTR _count_steps_left() {
left_step_stopcount= 0; left_step_stopcount= 0;
right_step_stopcount=0; right_step_stopcount=0;
} }
} }
/** @brief this routine is called each time the left PE barrier changes its state. it increments (and by that counts) the ticks driven by the right wheel and is also instructed to stop the racer if the stopcount set by drive_ticks() is reached using the global_stop_driving() routine /** @brief this routine is called each time the left PE barrier changes its state. it increments (and by that counts) the ticks driven by the right wheel and is also instructed to stop the racer if the stopcount set by drive_ticks() is reached using the global_stop_driving() routine
* @return nothing * @return nothing
*/ */
static void IRAM_ATTR _count_steps_right() { static void IRAM_ATTR _count_steps_right() {
timeafterright= millis();
timebeforeright = timebeforeright == 0 ? timeafterright : timebeforeright; //timeafterright= millis();
//timebeforeright = timebeforeright == 0 ? timeafterright : timebeforeright;
right_step_counter++; right_step_counter++;
if (right_step_counter==right_step_stopcount) if (right_step_counter==right_step_stopcount)
{ {
@ -1556,13 +1619,15 @@ static void IRAM_ATTR _count_steps_right() {
right_step_stopcount=0; right_step_stopcount=0;
} }
} }
/** @brief this routine is called each time the left infrared sensor changes its state. it sets the boolean variable obstacle_left_side to true/false and, if obstacle_stop is enabled, also stops the racer using global_stop_driving() /** @brief this routine is called each time the left infrared sensor changes its state. it sets the boolean variable obstacle_left_side to true/false and, if obstacle_stop is enabled, also stops the racer using global_stop_driving()
* @return nothing * @return nothing
*/ */
void IRAM_ATTR CodeRacerMKII::_stop_obstacle_left(){ void IRAM_ATTR CodeRacerMKII::_stop_obstacle_left(){
if(HIGH== digitalRead(H_INFRARED_SENSOR_LEFT)){
if(1==obstacle_stop){ if(LOW== digitalRead(H_INFRARED_SENSOR_LEFT)){
if(true==obstacle_stop){
global_stop_driving(); global_stop_driving();
} }
obstacle_left_side=true; obstacle_left_side=true;
@ -1573,6 +1638,7 @@ void IRAM_ATTR CodeRacerMKII::_stop_obstacle_left(){
* @return nothing * @return nothing
*/ */
void IRAM_ATTR CodeRacerMKII::_stop_obstacle_right(){ void IRAM_ATTR CodeRacerMKII::_stop_obstacle_right(){
if(HIGH== digitalRead(H_INFRARED_SENSOR_RIGHT)){ if(HIGH== digitalRead(H_INFRARED_SENSOR_RIGHT)){
if(1==obstacle_stop){ if(1==obstacle_stop){
global_stop_driving(); global_stop_driving();
@ -1589,8 +1655,14 @@ void IRAM_ATTR CodeRacerMKII::_stop_obstacle_right(){
//** Helper methods //** Helper methods
//********************************************************************************************************************** //**********************************************************************************************************************
/** @brief an issue with delay() is, that it stops the processor of the ESP32 completely for the waiting time and with this the interrupt routines for the stepcounters. Wait_ms() basically does the same just without the
* freezing of the prozedures. PREFER OVER DELAY()!!
* @param waittime_ms the time you want to wait- in ms
* @return nothing
*/
void wait_ms(long waittime_ms) void wait_ms(long waittime_ms)
{ {
long started_ms = millis(); long started_ms = millis();
while(millis()-started_ms < waittime_ms){} while(millis()-started_ms < waittime_ms){}
} }

View file

@ -3,6 +3,7 @@
#include <ESP32Servo.h> // Servo drive support for ESP32 #include <ESP32Servo.h> // Servo drive support for ESP32
#include "esp32-hal-ledc.h" // Part of ESP32 board files - Analog output #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 "BluetoothSerial.h" // Bluetooth enablement - part of ESP or standart Arduino lib
#include "Webserver.h"
#include <vector> // support for vectors #include <vector> // support for vectors
#include <string> #include <string>
@ -14,7 +15,7 @@
#define __CodeRacer_MKII_H__ #define __CodeRacer_MKII_H__
//----- Fun stuff --------- //----- Fun stuff ---------
#define FUN_MIN_PAUSE_MS 120000 // minimum and maximum pause between to rounds fun #define FUN_MIN_PAUSE_MS 120000 // minimum and maximum pause between two rounds fun
#define FUN_MAX_PAUSE_MS 300000 #define FUN_MAX_PAUSE_MS 300000
#define LED_SWITCH_MS 50 // speed of knight rider lights #define LED_SWITCH_MS 50 // speed of knight rider lights
//----- Button ------------ //----- Button ------------
@ -80,8 +81,11 @@
#define H_LED_BLUE_PIN 14 #define H_LED_BLUE_PIN 14
#define H_LED_WHITE_PIN 12 #define H_LED_WHITE_PIN 12
#define H_VSUPPLY 26
using namespace std; using namespace std;
// Use this method instead of delay() to avoid conflicts with the interrupt routines
void wait_ms(long waittime_ms); void wait_ms(long waittime_ms);
enum ledstate { enum ledstate {
@ -95,7 +99,7 @@ enum drivestate {
DRIVEBACK DRIVEBACK
}; };
//--- this is as preparation of the class creation //--- this is a preparation of the class creation
class CodeRacerMKII { class CodeRacerMKII {
private: private:
@ -171,6 +175,7 @@ class CodeRacerMKII {
void _analog_write(uint8_t pin, uint8_t speed); void _analog_write(uint8_t pin, uint8_t speed);
unsigned long _servo_set_position(uint8_t position); unsigned long _servo_set_position(uint8_t position);
public: public:
//properties //properties
bool coderacer_fun_enabled; bool coderacer_fun_enabled;
@ -228,8 +233,10 @@ class CodeRacerMKII {
void stop_driving(); void stop_driving();
void drive_forward(); void drive_forward();
void drive_forward(uint8_t left_speed, uint8_t right_speed); void drive_forward(uint8_t left_speed, uint8_t right_speed);
void drive_forward_for_ms(unsigned long time);
void drive_backward(); void drive_backward();
void drive_backward(uint8_t left_speed, uint8_t right_speed); void drive_backward(uint8_t left_speed, uint8_t right_speed);
void drive_backward_for_ms(unsigned long time);
void turn_left(); void turn_left();
void turn_left(unsigned long turn_for_ms); 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_left(unsigned long turn_for_ms, uint8_t left_speed, uint8_t right_speed);
@ -242,6 +249,10 @@ class CodeRacerMKII {
void stop_stop_at_min_distance(); void stop_stop_at_min_distance();
bool start_stop(); bool start_stop();
//Wifi Debug methods
String wifi_printf();
String wifi_printf(String Content);
// Bluetooth // Bluetooth
void bt_enable_stopOnLostConnection(); void bt_enable_stopOnLostConnection();
@ -256,7 +267,7 @@ class CodeRacerMKII {
void bt_removeStringFromIgnoreList(String stringtoignore); void bt_removeStringFromIgnoreList(String stringtoignore);
// LEDs // LEDs
void set_leds_left_stop_frwd_right(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled, ledstate blueled, ledstate whiteled); void set_leds(ledstate leftled, ledstate stopled, ledstate frwdled, ledstate rightled, ledstate blueled, ledstate whiteled);
void set_leds_all(ledstate alleds); void set_leds_all(ledstate alleds);
void set_leds_all_off(); void set_leds_all_off();
void set_leds_all_on(); void set_leds_all_on();
@ -264,6 +275,7 @@ class CodeRacerMKII {
// Drives // Drives
void speed_settings(uint8_t drive_left_speed, uint8_t drive_right_speed); void speed_settings(uint8_t drive_left_speed, uint8_t drive_right_speed);
void drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms); void drives_settings(uint8_t drive_left_speed, uint8_t drive_right_speed, unsigned long turn_left_ms, unsigned long turn_right_ms);
void Reset_Stats();
void set_drives_states_left_right(drivestate stateleft, drivestate stateright); void set_drives_states_left_right(drivestate stateleft, drivestate stateright);
void set_drive_left_state(drivestate state); void set_drive_left_state(drivestate state);
void set_drive_right_state(drivestate state); void set_drive_right_state(drivestate state);
@ -274,7 +286,6 @@ class CodeRacerMKII {
void set_drive_left_speed(uint8_t speed); void set_drive_left_speed(uint8_t speed);
void set_drive_right_speed(uint8_t speed); void set_drive_right_speed(uint8_t speed);
void set_drive_speed(uint8_t speed, uint8_t enablepin); void set_drive_speed(uint8_t speed, uint8_t enablepin);
void set_drives_stop_left_right();
void drive_turns(unsigned int turnsleft, unsigned int turnsright); void drive_turns(unsigned int turnsleft, unsigned int turnsright);
void drive_ticks(unsigned int tickleft, unsigned int tickright); void drive_ticks(unsigned int tickleft, unsigned int tickright);
void turn_degree(int degree); void turn_degree(int degree);
@ -316,7 +327,7 @@ class CodeRacerMKII {
}; };
extern CodeRacerMKII Coderacer;
#endif #endif

View file

@ -0,0 +1,129 @@
#include "Webserver.h"
/** @brief Constructor for the webserver
* @param ssid Network SSID
* @param password password of the network the CodeRacer is connected to
* @return nothing
*/
Codeserver::Codeserver(char *ssid, char *password){
Ssid= ssid;
Password= password;
}
/** @brief Sends an error if no valid answer to a GET request has been found
*/
void notFound(AsyncWebServerRequest *request) {
request->send(404, "text/plain", "Not found");
}
/** @brief The bread-and-butter-routine of the webserver. Connects to a Wifi network with the SSID and password defined by the constructor. Contains various routines
* telling the server what to do if a GET request comes in by the client. You can add events using server.on() here to call routines of the CodeRacer.
*/
void Codeserver::Run(){
//Connecting to Wifi network
Serial.print("Connecting to");
Serial.println(Ssid);
WiFi.begin(Ssid, Password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.println("");
Coderacer.wifi_printf("WiFi connected.");
Serial.println("IP address: ");
Serial.println(WiFi.localIP());
// Definition for events triggered by the GET request of the client
server.on("/", HTTP_GET, [] (AsyncWebServerRequest *request){
String message;
request->send(200, "text/html", String(indexHTML));
Serial.printf("Webpage sent\n");
});
server.on("/DriveForward", HTTP_GET, [] (AsyncWebServerRequest *request){
Coderacer.drive_forward();
request->send(200, "text/plain", "Hello world");
});
server.on("/DriveBackward", HTTP_GET, [] (AsyncWebServerRequest *request){
Coderacer.drive_backward();
request->send(200, "text/plain", "Hello, world");
});
server.on("/StopDriving", HTTP_GET, [] (AsyncWebServerRequest *request){
Coderacer.stop_driving();
request->send(200, "text/plain", "Hello, world");
});
server.on("/TurnLeft", HTTP_GET, [] (AsyncWebServerRequest *request){
Coderacer.turn_left();
request->send(200, "text/plain", "Hello, world");
});
server.on("/TurnRight", HTTP_GET, [] (AsyncWebServerRequest *request){
Coderacer.turn_right();
request->send(200, "text/plain", "Hello, world");
});
server.on("/ResetTable", HTTP_GET, [] (AsyncWebServerRequest *request){
Coderacer.Reset_Stats();
request->send(200, "text/plain", "Hello, world");
});
server.on("/SetSpeed", HTTP_GET, [] (AsyncWebServerRequest *request){
String Message;
if(request->hasParam("speed"))
{
Message= request->getParam("speed")->value();
Coderacer.speed_settings(Message.toInt(), Message.toInt());
Serial.printf("New Speed: %s", Message.c_str());
}
else {
request->send(200, "text/plain", "No speed sent");
}
request->send(200, "text/plain", "OK");
});
// Returns the many values contained by the table on the website via query string.
// Notice how before this routine ends, the debug_message variable on the Coderacer is resetted to avoid memory overflow.
server.on("/Values", HTTP_GET, [] (AsyncWebServerRequest *request){
String Message= "";
int leftsteps= Coderacer.show_left_stepcounter();
int leftspeed= Coderacer.drive_left_speed();
int distance= Coderacer.usonic_measure_single_shot_cm();
int drivendistancemm= Coderacer.show_distance_mm();
int rightsteps= Coderacer.show_right_stepcounter();
int rightspeed= Coderacer.drive_right_speed();
int servodegree= Coderacer.servo_position();
float drivendistancem= (float)drivendistancemm/1000.0;
String Text=Coderacer.wifi_printf();
request->send(200, "text/plain", Message+"?"+"leftstep="+leftsteps+"&leftspeed="+leftspeed+"&distance="+distance+"&DistanceMM="+drivendistancemm+"&rightstep="+rightsteps+"&rightspeed="+rightspeed+"&ServoPosition="+servodegree+"&DistanceM="+drivendistancem+"&TheMessage="+Text);
Coderacer.wifi_printf("");
});
server.on("/TurnServo", HTTP_GET, [] (AsyncWebServerRequest *request){
String message;
if(request->hasParam("degree"))
{
message= request->getParam("degree")->value();
Coderacer.servo_set_position_wait(message.toInt());
Serial.printf("New Servo Position: %s", message.c_str());
} else {
message= "No Servo message sent.";
}
request->send(200, "text/plain", "HELLO, Post"+ message);
});
// Sends an error if no valid answer has been found
server.onNotFound(notFound);
// At least, initializes the asynchronous webserver
server.begin();
}

View file

@ -0,0 +1,148 @@
// Necessary to avoid multiple includes of this header
#ifndef __CodeRacer_WEBSERVER_H__
#define __CodeRacer_WEBSERVER_H__
#include "CodeRacer_MKII.h"
#include <AsyncTCP.h>
#include <ESPAsyncWebServer.h>
// This is a char array containing the html code for the website. It is sent ONCE when the webserver first initializes.
// The script contains various routines telling what the AJAX object should do and when.
// It is strongly advised NOT to change the html text, unless you know exactly what you're doing!
const char indexHTML[] PROGMEM = R"=====(
<!DOCTYPE html>
<html>
<head>
<title>CodeRacer Webserver</title>
<meta name=viewport content="width=device-width, initial-scale=1">
<link rel="icon" type="image/x-png" href="data:image/png; base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAMAAAAoLQ9TAAAABGdBTUEAALGPC
/xhBQAAACBjSFJNAAB6JgAAgIQAAPoAAACA6AAAdTAAAOpgAAA6mAAAF3CculE8AAACglBMVEURMEwSMU0RME0QL0oSMU4SMEwTMk4TMk8SME0QL0wXOVgUNVEXOlsUNFEUM1ATM08TMU4TMU0UMk8TM1AcQmgZPV8lUnwoW4okUXwcQWQVNFIUMlAVNFAVNVMfSXMXPGMmVoQ9fbk4drIsYpgUNFQWN1YVNlUVNFMTMU8WNVIaOloeRGoqXZIza6E1c7BHjcxTm9Y+fbkyaJoaPWEaPWAaO10XOFkUNFMWNVMPMFESOV8dT4EwdLU5e7tAhsdCkthMn+JKltUtbKgUQ3IUPWUNMlgTNVoXN1kPL1BNZH1YcoxmhKNmj7uMqcWLqsd+qM54ps94pMp4mrtXc5B0hZg/WXURM1gNLk54iZmCla2JnryYrs2Vrs+ds8+cscyludSxwdGgtcqlssFrg5ymsb1pfZELMFYWO14rUoFHd7l+reWQve6Zw/GFt++AtvJen+5VmepIi9g+d7AtZJohTHciQ2UZPGAcQWYoXJ6q2vjg+/rk+frl+fvz/v3l+PzW8Pyy2v9no+s3fso9g8cnXJAZP2YXOFohT4Z0reW03/m+5fjG7PfR8/fN8ffW9ffZ9fbJ6/qGw/AzeL8vZ6MaPmISL0scRnYgUo9QiMZyrOSUyfO+5/y85vuy4fqx4PuHxPFXk8IpX5UtZZ8eRXATMEwMHjIRLlEVN2EfUIgoXpo7eLhSjslZlM5QisdHf7gqX5ckWpMsY5kiTXsVMU8PJDkMGy0KHDEPJkQTL1ARL1EWO2UWQHAYRXchUYUbRnYlV4sjUH4YOVwOIzoMHi8MGysKFiQJFiQIFyoMID0KHDQMITwKHTQJGSwZPmcaQWwZQW8SMFgNIz8KGisKGCUJFiP///+JaqBNAAAAAWJLR0TVfrw7EwAAAAd0SU1FB+QIFAoOJAEdNLQAAAETSURBVBjTY2BgRAZMzAxAARZWNkY2IMXOwsLBycDBxs7OxcrNysPFy87HL8DAICjELizCKyomLiEpICUlzcEgIMMmKyevoKikLKGiqqauwcCnqaWto6unb2BoZGxiambOYGFpZW1ja2fv4Ojk7OLq5s7g4enl7ePr5x8QGOQdHBIaxhAeERkVHRMbF5+QmJSckprGkJ6RmZWdk5uXX1BYVFxSWsZQXlFZVV1TW1ff0NjU3NLaxsDb3tHZ1d3T29c/YeKkyVOkGaZOmz5j5qzZc+bOm79g4aLFSxiWLlu+YuWq1WvWrlu/YeOmzVsYtm7bvmPnrt179u7bf+DgocNHGI4eO37i5KnTZ86eO3/h4qXLVwBVcFmCQPwHjgAAACV0RVh0ZGF0ZTpjcmVhdGUAMjAyMC0wOC0yMFQxMDoxNDozNiswMDowMGk0R6UAAAAldEVYdGRhdGU6bW9kaWZ5ADIwMjAtMDgtMjBUMTA6MTQ6MzYrMDA6MDAYaf8ZAAAAAElFTkSuQmCC"/>
<script>
var Url ="http://192.168.1.146/";
window.onload = start;
function start()
{
myAjax= new XMLHttpRequest();
myAjax.onreadystatechange= LesenAjax;
setInterval(aktualisieren,750);
aktualisieren();
}
function aktualisieren()
{
var state=myAjax.readyState;
document.getElementById('AJAXstate').innerHTML= "AJAX state: " +state;
var statustext=myAjax.statusText;
document.getElementById('AJAXstatus').innerHTML= "Status text: " +statustext;
myAjax.open("GET", Url+"Values", true);
myAjax.send();
}
function LesenAjax()
{
if(myAjax.readyState==4 && myAjax.status==200)
{
var datenstr= myAjax.responseText;
var params = new URLSearchParams(datenstr);
var leftsteps=params.get('leftstep');
var leftspeed= params.get('leftspeed');
var distance=params.get('distance');
var drivendistanceMM= params.get('DistanceMM');
var rightsteps=params.get('rightstep');
var rightspeed=params.get('rightspeed');
var servopos= params.get('ServoPosition');
var drivendistanceM= params.get('DistanceM');
var themessage= params.get('TheMessage');
document.getElementById('leftstep').innerHTML= "Left: "+leftsteps;
document.getElementById('leftspeed').innerHTML= "Left: "+leftspeed;
document.getElementById('distance').innerHTML= "Current Distance: "+distance;
document.getElementById('DistanceMM').innerHTML= "Driven Distance (MM): "+drivendistanceMM;
document.getElementById('rightstep').innerHTML= "Right: "+rightsteps;
document.getElementById('rightspeed').innerHTML= "Right: "+rightspeed;
document.getElementById('ServoPosition').innerHTML="Current Servo position: " +servopos;
document.getElementById('DistanceM').innerHTML= "Driven Distance (M): "+drivendistanceM;
addtext('textbox', themessage);
}
}
function addtext(inputid, inputtxt){
if(inputtxt!='' && inputtxt!=null)
{
var obj= document.getElementById(inputid);
obj.innerHTML += inputtxt + "<p>";
obj.scrollTop = obj.scrollHeight;
}
}
function SetValue(cmd, id)
{
action=cmd + "?" + id + "=" + document.getElementById(id).value;
myAjax.open("GET", Url+action, true);
myAjax.send();
}
function httpGet(sende)
{
myAjax.open("GET", Url+sende, true);
myAjax.send();
}
function flushTextbox(id){
document.getElementById(id).innerHTML= "";
}
</script>
<style>
html { font-family: Sylfaen; display: inline-block; margin: 0px auto; text-align: left;}
.outmsg {background-color: #FFFFFF; border: 2px solid black; color: black; padding: 5px 10px;
text-decoration: none; font-size: 20px; margin: 15px; cursor: pointer;}
div{width:650px; overflow:auto; height: 300px; border: 1px solid #000000; padding: 15px; line-height:10px;}
.button {font-family: Sylfaen; background-color: #000000; border: 2px solid black; color: white; padding: 5px 10px;
text-decoration: none; font-size: 20px; margin: 15px; cursor: pointer;}
.button3 {font-family: Sylfaen; background: #FF0000; border: 2px solid black; color: white; padding: 5px 10px;
text-decoration: none; font-size: 20px; margin: 10px 0px; cursor: pointer;}
</style>
</head>
<body>
<h1>Welcome to the CodeRacer Webserver!</h1>
<p><button class="button" onclick="httpGet('DriveForward')">Drive Forward</button>
<button class="button" onclick="httpGet('DriveBackward')">Drive Backward</button>
<button class="button" onclick="httpGet('StopDriving')">Stop Driving</button>
<button class="button" onclick="httpGet('TurnLeft')">Turn Left</button>
<button class="button" onclick="httpGet('TurnRight')">Turn Right</button>
<p>
<label for="speed">Set new Speed</label>
<input id="speed" type="text" placeholder="Enter value (0-255)" />
<input type="button" onclick="SetValue('SetSpeed', 'speed')" />
</p>
<p>
<label for="b">Turn Servo</label>
<input id="degree" type="text" placeholder="Enter Degree (10-170)" />
<input type="button" onclick="SetValue('TurnServo', 'degree')" />
</p>
<p><table border="1">
<tr><th>Step Counters</th><th>Speed of Drives</th><th>Servo- Information</th><th>Driven Distance</th><th>AJAX Information<th></tr>
<tr><td id="leftstep">0</td><td id="leftspeed">0</td><td id="distance">0</td><td id="DistanceMM">0</td><td id="AJAXstate">0</td></tr>
<tr><td id="rightstep">0</td><td id="rightspeed">0</td><td id="ServoPosition">0</td><td id="DistanceM">0</td><td id="AJAXstatus">0</td></tr>
</table>
<button class="button3" onclick="httpGet('ResetTable')">Reset Dashboard</button></p>
<div id="textbox"></div>
<button class="button3" onclick="flushTextbox('textbox')">Reset Debugging Window</button>
</body>
</html>
)=====";
// The class declaration of the webserver
class Codeserver {
private:
public:
Codeserver(char *ssid, char *password);
const char* Ssid;
const char* Password;
void Run();
};
extern AsyncWebServer server;
#endif

View file

@ -1,4 +1,4 @@
#include <CodeRacer.h> #include "CodeRacer_MKII.h"
//----- settings for the ultrasonic sensor ----- //----- settings for the ultrasonic sensor -----
#define US_STOP_ABSTAND_CM 20 // if distance goes below that - stop the racer #define US_STOP_ABSTAND_CM 20 // if distance goes below that - stop the racer
@ -7,10 +7,10 @@
unsigned long distance_cm = 0; unsigned long distance_cm = 0;
//---- construct the coderacer object //---- construct the coderacer object
CodeRacer coderacer; CodeRacerMKII coderacer;
//---- set up code - executed ones //---- set up code - executed ones
void setup() { void setup1() {
// start serial monitor // start serial monitor
Serial.begin(115200); Serial.begin(115200);
// initialize the coderacer // initialize the coderacer
@ -27,7 +27,7 @@ void setup() {
} }
//---- 'endless' loop //---- 'endless' loop
void loop() { void loop1() {
// check if the racer was started (button was toggled to coderacer active state // check if the racer was started (button was toggled to coderacer active state
if(true == coderacer.start_stop()){ if(true == coderacer.start_stop()){

View file

@ -1,215 +1,21 @@
// Example Code of a CodeRacer sketch with implementation of a webserver
#include "CodeRacer_MKII.h" #include "CodeRacer_MKII.h"
#include <ESP32Servo.h> #include "Webserver.h"
#include "esp32-hal-ledc.h"
#include <WiFi.h>
// Replace with your network credentials
const char* ssid = "WLAN-318091";
const char* password = "peter4004";
// Set web server port number to 80
WiFiServer server(80);
// Variable to store the HTTP request
String header;
// Auxiliar variables to store the current output state
String output32State= "off";
String output33State="off";
String output25State = "off";
String output27State = "off";
String output14State= "off";
String output12State= "off";
// Assign output variables to GPIO pins
const int output25 = 25;
const int output27 = 27;
const int output32=32;
const int output33= 33;
const int output14= 14;
const int output12= 12;
CodeRacerMKII Coderacer; CodeRacerMKII Coderacer;
unsigned long Distance; // IMPORTANT definition of the server port
AsyncWebServer server(80);
// Definition of the webserver. enter your network's SSID and password here
Codeserver Test((char*)"coderacer_ap", (char*)"007coderacer");
void setup() { void setup() {
Coderacer.begin(); Coderacer.begin();
Serial.begin(115200); Serial.begin(115200);
// Initialize the output variables as outputs // Calls the Run() routine, which manages everything the webserver needs to work
pinMode(output25, OUTPUT); Test.Run();
pinMode(output27, OUTPUT);
pinMode(output32, OUTPUT);
pinMode(output33, OUTPUT);
pinMode(output14, OUTPUT);
pinMode(output12, OUTPUT);
// Set outputs to LOW
digitalWrite(output25, LOW);
digitalWrite(output27, LOW);
digitalWrite(output32, LOW);
digitalWrite(output33, LOW);
digitalWrite(output14, LOW);
digitalWrite(output12, LOW);
// Connect to Wi-Fi network with SSID and password
Serial.print("Connecting to ");
Serial.println(ssid);
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
// Print local IP address and start web server
Serial.println("");
Serial.println("WiFi connected.");
Serial.println("IP address: ");
Serial.println(WiFi.localIP());
server.begin();
} }
void loop(){ void loop()
WiFiClient client = server.available(); // Listen for incoming clients {
if (client) { // If a new client connects, //Coderacer.speed_settings(255, 250);
Serial.println("New Client detected."); // print a message out in the serial port
String currentLine = ""; // make a String to hold incoming data from the client
while (client.connected()) { // loop while the client's connected
if (client.available()) { // if there's bytes to read from the client,
char c = client.read(); // read a byte, then
Serial.write(c); // print it out the serial monitor
header += c;
if (c == '\n') { // if the byte is a newline character
// if the current line is blank, you got two newline characters in a row.
// that's the end of the client HTTP request, so send a response:
if (currentLine.length() == 0) {
// HTTP headers always start with a response code (e.g. HTTP/1.1 200 OK)
// and a content-type so the client knows what's coming, then a blank line:
client.println("HTTP/1.1 200 OK");
client.println("Content-type:text/html");
client.println("Connection: close");
client.println();
// turns the GPIOs on and off
if (header.indexOf("GET /25/on") >= 0) {
Serial.println("GPIO 25 on");
output25State = "on";
digitalWrite(output25, HIGH);
} else if (header.indexOf("GET /25/off") >= 0) {
Serial.println("GPIO 25 off");
output25State = "off";
digitalWrite(output25, LOW);
} else if (header.indexOf("GET /27/on") >= 0) {
Serial.println("GPIO 27 on");
output27State = "on";
digitalWrite(output27, HIGH);
} else if (header.indexOf("GET /27/off") >= 0) {
Serial.println("GPIO 27 off");
output27State = "off";
digitalWrite(output27, LOW);
} else if(header.indexOf("GET /32/off") >=0) {
Serial.println("GPIO 32 off");
output32State= "off";
digitalWrite(output32, LOW);
} else if(header.indexOf("GET /32/on") >=0) {
Serial.println("GPIO 32 on");
output32State= "on";
digitalWrite(output32, HIGH);
} else if (header.indexOf("GET /33/on") >= 0) {
Serial.println("GPIO 33 on");
output33State = "on";
digitalWrite(output33, HIGH);
} else if (header.indexOf("GET /33/off") >= 0) {
Serial.println("GPIO 33 off");
output33State = "off";
digitalWrite(output33, LOW);
} else if (header.indexOf("GET /MeasureDistance") >=0) {
Distance= Coderacer.usonic_measure_cm();
} else if (header.indexOf("GET /DriveForward") >=0) {
Serial.printf("header: '%s'\n", header.c_str());
if(header.indexOf("=") >=0) {int Position= header.indexOf("=");
String Substring= header.substring(Position+1);
int iSpeed= Substring.toInt();
Coderacer.speed_settings(iSpeed, iSpeed);
Coderacer.servo_set_position_wait(iSpeed);
}
//Coderacer.drive_forward();
} else if(header.indexOf("GET /DriveBackward") >=0) {
Coderacer.drive_backward();
}
// Display the HTML web page
client.println("<!DOCTYPE html><html>");
client.println("<head><meta name=\"viewport\" content=\"width=device-width, initial-scale=1\">");
client.println("<link rel=\"icon\" href=\"data:,\">");
// CSS to style the on/off buttons
// Feel free to change the background-color and font-size attributes to fit your preferences
client.println("<style>html { font-family: Impact; display: inline-block; margin: 0px auto; text-align: left;}");
client.println(".outmsg {background-color: #FFFFFF; border: 2px solid black; color: black; padding: 10px 10px;");
client.println("text-decoration: none; font-size: 30px; margin: 15px; cursor: pointer;}");
client.println(".button {background-color: #4CAF50; border: none; color: white; padding: 10px 10px;");
client.println("text-decoration: none; font-size: 30px; margin: 15px; cursor: pointer;}");
client.println(".button2 {background-color: #555555;}</style></head>");
// Web Page Heading
client.println("<body><h1>ESP32 Web Server</h1>");
client.println("<p>GPIO 32 - State " + output32State );
// If the output27State is off, it displays the ON button
if (output32State=="off") {
client.println("<a href=\"/32/on\"><button class=\"button\">OFF</button></a>");
} else {
client.println("<a href=\"/32/off\"><button class=\"button button2\">ON</button></a>");
}
client.println("GPIO 33 - State " + output33State );
// If the output27State is off, it displays the ON button
if (output33State=="off") {
client.println("<a href=\"/33/on\"><button class=\"button\">OFF</button></a></p>");
} else {
client.println("<a href=\"/33/off\"><button class=\"button button2\">ON</button></a></p>");
}
// Display current state, and ON/OFF buttons for GPIO 26
client.println("<p>GPIO 25 - State " + output25State );
// If the output26State is off, it displays the ON button
if (output25State=="off") {
client.println("<a href=\"/25/on\"><button class=\"button\">OFF</button></a>");
} else {
client.println("<a href=\"/25/off\"><button class=\"button button2\">ON</button></a>");
}
// Display current state, and ON/OFF buttons for GPIO 27
client.println("GPIO 27 - State " + output27State );
// If the output27State is off, it displays the ON button
if (output27State=="off") {
client.println("<a href=\"/27/on\"><button class=\"button\">OFF</button></a></p>");
} else {
client.println("<a href=\"/27/off\"><button class=\"button button2\">ON</button></a></p>");
}
client.println("<p><a href=\"/MeasureDistance\"><button class=\"button\">Measure Distance</button></a>");
client.printf("<button class=\"outmsg\">%li</button></p>", Distance);
client.println("<p><a href=\"/DriveForward\"><button class=\"button\">Drive Forward</button></a>");
client.println("<a href=\"/DriveBackward\"><button class=\"button\">Drive Backward</button></a>");
client.println("<form action=\"http://192.168.2.107/DriveForward/\">");
client.println("<p><label for=\"q\">Set Speed</label>");
client.println("<input id=\"q\" name=\"Speed\" aria-label=\"Set Speed\" placeholder=\"Enter value\">");
client.println("<button >Submit</button>");
client.println("</body></html>");
// The HTTP response ends with another blank line
client.println();
// Break out of the while loop
break;
} else { // if you got a newline, then clear currentLine
currentLine = "";
}
} else if (c != '\r') { // if you got anything else but a carriage return character,
currentLine += c; // add it to the end of the currentLine
}
}
}
// Clear the header variable
header = "";
// Close the connection
client.stop();
Serial.println("Client disconnected.");
Serial.println("");
}
} }

View file

@ -37,7 +37,7 @@ const bool RIGHT = false;
const unsigned int IN_MAX = 255; const unsigned int IN_MAX = 255;
//---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ---- //---- Hier startet der Code zum Einstellen aller wichtigen Dinge. Setup() wird einmal ausgeführt. ----
void setup1() { void setup2() {
// Monitor // Monitor
Serial.begin(9600); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen. Serial.begin(9600); // Serial Monitor aktivieren. Mit dem Monitor kann man sich Werte und Meldungen anzeigen lassen.
@ -58,8 +58,10 @@ void setup1() {
} }
//---- 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 //---- 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 loop1() void loop2()
{ {
coderacer.drive_distance_mm(1000, 1000);
bool started = false; bool started = false;
while(coderacer.start_stop()== 1) while(coderacer.start_stop()== 1)
{ {
@ -69,6 +71,10 @@ void loop1()
wait_ms(1000); wait_ms(1000);
} }
// below - mitteln // below - mitteln
coderacer.stop_driving(); coderacer.stop_driving();
unsigned int in_min_left = get_inmin(true); unsigned int in_min_left = get_inmin(true);