// Codice per il monitoraggio da remoto della temperatura e umidità
// con NodeRED su http://NODEREDCLIENT_IPADDRESS/8080/ui
// con webserver ESP_IPADDRESS
//GIRA SU ARDUINOIDE e il PWM girava originariamente su un altro progetto
//Secondo me qualcuna delle seguenti librerie crea un conflitto. Bisogna richiamare
//direttamente qualche libreria qui di seguito (poetamy)
//https://wokwi.com/projects/395293277134876673
#include "Adafruit_Sensor.h"
#include <DHT.h>
#include <WiFi.h>
#include <PubSubClient.h>
#include <AsyncTCP.h>
#include <ESPAsyncWebSrv.h>
//#include <ArduinoJson.h>
#include <AnalogWrite_ESP32.h>
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
// Wokwi Virtual WiFi
const char* ssid = "Wokwi-GUEST";
const char* password = "";
const char* mqtt_server = "test.mosquitto.org";// MQTT Broker address
int mqtt_broker_port = 1883;
char* mqttTopic_DHT_temp = "esp32/iot1/dht/temp"; // MQTT topic2: sensor-temerature
char* mqttTopic_DHT_hum = "esp32/iot1/dht/hum"; // MQTT topic3: sensor-humidity
WiFiClient wifiClient;
PubSubClient pubSubClient(wifiClient);
// Create AsyncWebServer object on port 80
AsyncWebServer server(80);
AsyncWebSocket ws("/ws");
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//Constants
#define DHTPIN 4 // pin DATI sul GPIO
#define DHTTYPE DHT11 // Sensore DHT11 (AM2302)
//#define DHTTYPE DHT22 // DHT 11 (AM2302)
DHT dht(DHTPIN, DHTTYPE); // Inizializza il sensore
float temp; // valori sensore temperatura
float humidity; // valori sensore umidità
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
// Funzioni comandi F,R,B,L
// Ognuno di questi comandi ha uno stato vero o falso
// Si definiscono 2 valori di tensione per cui i motori si movimentano "bene" e "meglio"
float VH = 3.3; //V
float VM = 2.7; //V
float VL = 0.0; //V
// Se tutti i comandi sono falsi in input, allora il rovere si ferma
// Se F>0 va avanti
// se F>0 AND R>0 allora M== (gira verso destra)
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
int PIN_M1Rr = 5; //GPIO pin Motore 1 destro
int PIN_M1Rb = 4; //GPIO pin Motore 1 destro
int PIN_M2Rr = 2; //...GPIO pin Motore 2 destro
int PIN_M2Rb = 15; //...GPIO pin Motore 2 destro
int PIN_M1Lr = 27; //GPIO pin Motore 1 sinistro
int PIN_M1Lb = 14; //GPIO pin Motore 1 sinistro
int PIN_M2Lr = 12; //...GPIO pin Motore 2 sinistro
int PIN_M2Lb = 13; //...GPIO pin Motore 2 sinistro
// Definizione dei parametri PWM
const int PWM_FREQ = 5000; // Hz, Arduino Uno is ~490 Hz. Official ESP32 example uses 5kHz
const int PWM_RES = 8; // Risoluzione PWM a 8 bit, PWM resolution (1 - 16 bits)
const int MAX_DUTY_CYCLE = (0x01 << PWM_RES) - 1;
//const int dutyCycleMax = 255; // 3.3V
const int dutyCycleMax = MAX_DUTY_CYCLE; // 3.3V
//const int dutyCycleMild = 209; // 2.7V calcolato come (2.7/3.3) * 255
const int dutyCycleMild = (int)(MAX_DUTY_CYCLE * (VM / VH));; //(int)(255.0 * (2.7 / 3.3)); // Converti 2.7V in duty cycle
const int PWM_DELAY_MS = 10; //5; //80; // delay between increments in ms
// Canali LEDC per ESP32
const int channelRightRed = 0; // 16 canali, da 0 a 15
const int channelRightBlack = 1; // 16 canali, da 0 a 15
const int channelLeftRed = 2; // 16 canali, da 0 a 15
const int channelLeftBlack = 3; // 16 canali, da 0 a 15
void moveRobot(bool varF, bool varR, bool varB, bool varL) {
// Escludiamo combinazioni opposte
if (varF && varB) varF = varB = false;
if (varR && varL) varR = varL = false;
int pwmRightRed = 0, pwmRightBlack = 0;
int pwmLeftRed = 0, pwmLeftBlack = 0;
if (varF && varR) {
pwmRightRed = dutyCycleMild;
pwmRightBlack = 0;
pwmLeftRed = dutyCycleMax;
pwmLeftBlack = 0;
} else if (varF && varL) {
pwmRightRed = dutyCycleMax;
pwmRightBlack = 0;
pwmLeftRed = dutyCycleMild;
pwmLeftBlack = 0;
} else if (varB && varR) {
pwmRightRed = dutyCycleMild;
pwmRightBlack = 0;
pwmLeftRed = 0;
pwmLeftBlack = dutyCycleMax;
} else if (varB && varL) {
pwmRightRed = 0;
pwmRightBlack = dutyCycleMax;
pwmLeftRed = dutyCycleMild;
pwmLeftBlack = 0;
} else if (varF) { //stato singolo
pwmRightRed = dutyCycleMax;
pwmRightBlack = 0;
pwmLeftRed = dutyCycleMax;
pwmLeftBlack = 0;
} else if (varB) { //stato singolo
pwmRightRed = 0;
pwmRightBlack = dutyCycleMax;
pwmLeftRed = 0;
pwmLeftBlack = dutyCycleMax;
} else if (varR) { //stato singolo
pwmRightRed = 0;
pwmRightBlack = dutyCycleMild;
pwmLeftRed = dutyCycleMild;
pwmLeftBlack = 0;
} else if (varL) { //stato singolo
pwmRightRed = dutyCycleMild;
pwmRightBlack = 0;
pwmLeftRed = 0;
pwmLeftBlack = dutyCycleMild;
}
// Scrittura dei valori PWM
ledcWrite(channelRightRed, pwmRightRed);
ledcWrite(channelRightBlack, pwmRightBlack);
ledcWrite(channelLeftRed, pwmLeftRed);
ledcWrite(channelLeftBlack, pwmLeftBlack);
//Introdurre il bloccaggio dei motori con tenendoli in stallo !
delay(PWM_DELAY_MS);
}
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
const int LEDPIN1 = 23; // pin controllato dal WebServer
bool sLEDPIN1 = 0; //Stato pin contrallato dal WebServer
const int LEDPIN2 = 26; // pin controllato dal WebServer
bool sLEDPIN2 = 0; //Stato pin contrallato dal WebServer
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
const char index_html[] PROGMEM = R"rawliteral(
<!DOCTYPE HTML><html>
<head>
<title>ESP Web Server</title>
<meta name="viewport" content="width=device-width, initial-scale=1">
<style>
html { font-family: Arial, Helvetica, sans-serif; text-align: center; background-color: #f4f4f4; }
h1 { color: #143642; }
.container { margin-top: 20px; }
.button {
width: 80px; height: 80px; font-size: 2rem; margin: 10px;
background-color: #0f8b8d; color: white; border: none; border-radius: 10px;
display: inline-block; cursor: pointer; outline: none;
}
.button:active { background-color: #0a6163; }
.grid { display: grid; grid-template-columns: repeat(3, 1fr); gap: 10px; justify-content: center; }
.center { display: flex; justify-content: center; }
</style>
</head>
<body>
<h1>ESP32 Robot Control</h1>
<div class="container">
<div class="grid">
<div></div>
<button class="button" id="btnF">▲</button>
<div></div>
<button class="button" id="btnL">◀</button>
<div></div>
<button class="button" id="btnR">▶</button>
<div></div>
<button class="button" id="btnB">▼</button>
<div></div>
</div>
</div>
<script>
var gateway = `ws://${window.location.hostname}/ws`;
var websocket;
window.addEventListener('load', onLoad);
function onLoad() {
initWebSocket();
initButtons();
}
function initWebSocket() {
console.log('Connecting to WebSocket...');
websocket = new WebSocket(gateway);
websocket.onopen = () => console.log('WebSocket Connected');
websocket.onclose = () => setTimeout(initWebSocket, 2000);
}
function sendCommand(command, state) {
websocket.send(JSON.stringify({ command: command, state: state }));
}
function initButtons() {
document.getElementById('btnF').addEventListener('mousedown', () => sendCommand('F', true));
document.getElementById('btnF').addEventListener('mouseup', () => sendCommand('F', false));
document.getElementById('btnB').addEventListener('mousedown', () => sendCommand('B', true));
document.getElementById('btnB').addEventListener('mouseup', () => sendCommand('B', false));
document.getElementById('btnR').addEventListener('mousedown', () => sendCommand('R', true));
document.getElementById('btnR').addEventListener('mouseup', () => sendCommand('R', false));
document.getElementById('btnL').addEventListener('mousedown', () => sendCommand('L', true));
document.getElementById('btnL').addEventListener('mouseup', () => sendCommand('L', false));
}
</script>
</body>
</html>
)rawliteral";
bool varF = false, varB = false, varR = false, varL = false;
void notifyClientsArrows() {
String message = String(varF) + "," + String(varB) + "," + String(varR) + "," + String(varL);
ws.textAll(message);
}
void notifyClientsButton1() {
ws.textAll(String(sLEDPIN1));
}
/*
void handleWebSocketMessage(void *arg, uint8_t *data, size_t len) {
AwsFrameInfo *info = (AwsFrameInfo*)arg;
if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT) {
data[len] = 0;
//Button1
if (strcmp((char*)data, "toggle") == 0) { //Stato pulsante precedente
sLEDPIN1 = !sLEDPIN1;
notifyClientsButton1();
}
//Frecce
String msg = String((char*)data);
DynamicJsonDocument doc(256);
deserializeJson(doc, msg);
String command = doc["command"];
bool state = doc["state"];
if (command == "F") varF = state;
else if (command == "B") varB = state;
else if (command == "R") varR = state;
else if (command == "L") varL = state;
notifyClientsArrows();
}
}
*/
void handleWebSocketMessage(void *arg, uint8_t *data, size_t len) {
AwsFrameInfo *info = (AwsFrameInfo*)arg;
if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT) {
data[len] = 0; // Assicura che la stringa sia terminata correttamente
String msg = String((char*)data);
// Controllo del pulsante toggle
if (msg == "toggle") {
sLEDPIN1 = !sLEDPIN1;
notifyClientsButton1();
return;
}
// Controllo dei comandi delle frecce (F, B, R, L)
char command = msg.charAt(0); // Il primo carattere è il comando
bool state = (msg.charAt(1) == '1'); // Il secondo carattere è lo stato (1=TRUE, 0=FALSE)
switch (command) {
case 'F': varF = state; break;
case 'B': varB = state; break;
case 'R': varR = state; break;
case 'L': varL = state; break;
}
notifyClientsArrows();
}
}
void onEvent(AsyncWebSocket *server, AsyncWebSocketClient *client, AwsEventType type,
void *arg, uint8_t *data, size_t len) {
switch (type) {
case WS_EVT_CONNECT:
Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str());
break;
case WS_EVT_DISCONNECT:
Serial.printf("WebSocket client #%u disconnected\n", client->id());
break;
case WS_EVT_DATA:
handleWebSocketMessage(arg, data, len);
break;
case WS_EVT_PONG:
case WS_EVT_ERROR:
break;
}
}
void initWebSocket() {
ws.onEvent(onEvent);
server.addHandler(&ws);
}
String processorButton1(const String& var){
Serial.println(var);
if(var == "STATE"){
if (sLEDPIN1){
return "ON";
}
else{
return "OFF";
}
}
return String();
}
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
//----------------------------------------------------------------------------------------------
void setup_wifi() { // Connessione al WiFi
WiFi.mode(WIFI_STA); // default, se non lo si dichiara non serve
//delay(10);
Serial.println();
Serial.print("Connecting to ");
Serial.println(ssid);
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(100);
Serial.print(".");
}
Serial.println("");
Serial.println("WiFi connected");
Serial.println("IP address: ");
Serial.println(WiFi.localIP()); // Indirizzo IP associato all'ESP32 una volta connesso
}
// Process incoming MQTT message and control the servo motor
//void callback(char* topic, byte* payload, unsigned int length) {
//if (topic = mqttTopic_DHT_temp){
//}
//}
void setup() {
Serial.begin(115200); // Inizializzazione del monitor seriale (solo per il debugging!)
//myservo.attach(5); // Evetuale servo sul GPIO 5
setup_wifi();
pubSubClient.setServer(mqtt_server, mqtt_broker_port); // Server e porta MQTT del broker al quale puntare
//pubSubClient.setCallback(callback); // Funzione di callback per i messaggi in ingresso
dht.begin();
pinMode(LEDPIN1, OUTPUT);
digitalWrite(LEDPIN1, LOW);
pinMode(LEDPIN2, OUTPUT);
digitalWrite(LEDPIN2, LOW);
//ledcSetup(channelRightRed, PWM_FREQ, PWM_RES);
//ledcAttachPin(PIN_M1Rr, channelRightRed);
ledcAttach(PIN_M1Rr, channelRightRed);
//ledcSetup(channelRightBlack, PWM_FREQ, PWM_RES);
//ledcAttachPin(PIN_M1Rb, channelRightBlack);
ledcAttach(PIN_M1Rb, channelRightBlack);
//ledcSetup(channelLeftRed, PWM_FREQ, PWM_RES);
//ledcAttachPin(PIN_M1Lr, channelLeftRed);
ledcAttach(PIN_M1Lr, channelLeftRed);
//ledcSetup(channelLeftBlack, PWM_FREQ, PWM_RES);
//ledcAttachPin(PIN_M1Lb, channelLeftBlack);
ledcAttach(PIN_M1Lb, channelLeftBlack);
//const int MAX_DUTY_CYCLE = power(2,PWM_RES)-1;
//const int MAX_DUTY_CYCLE = (0x01 << PWM_RES) - 1;
Serial.print("Max duty cycle value : ");
Serial.println(MAX_DUTY_CYCLE);
initWebSocket();
// Route root webpage : /
server.on("/", HTTP_GET, [](AsyncWebServerRequest *request){
request->send_P(200, "text/html", index_html, processorButton1);
});
server.begin(); // Start Web Server
delay(2000);
}
void mqttReconnect() { // Riconnessione al broker MQTT
while (!pubSubClient.connected()) {
Serial.print("Attempting MQTT connection...");
if (pubSubClient.connect("ESPClient")) {
Serial.println("connected");
pubSubClient.subscribe(mqttTopic_DHT_temp);
pubSubClient.subscribe(mqttTopic_DHT_hum);
} else {
Serial.print("failed, rc=");
Serial.print(pubSubClient.state());
Serial.println(" try again in 5 seconds");
delay(5000);
}
}
}
void loop() {
if (!pubSubClient.connected()) { // Verifica lo stato della connessione MQTT
digitalWrite(LEDPIN1, LOW);
mqttReconnect();
} else {
digitalWrite(LEDPIN1, HIGH);
}
pubSubClient.loop();
delay(100); // ritardo per gestire il canale loop
temp = dht.readTemperature();
humidity = dht.readHumidity();
Serial.print("Temp : ");
Serial.print(temp);
Serial.println(" C ");
Serial.print("Humidity : ");
Serial.print(humidity);
Serial.println(" % ");
String messaget = String(temp); // Formato di scambio stringhe con pubsubclient
String messageh = String(humidity); // Formato di scambio stringhe con pubsubclient
pubSubClient.publish(mqttTopic_DHT_temp, messaget.c_str());
pubSubClient.publish(mqttTopic_DHT_hum, messageh.c_str());
ws.cleanupClients();
digitalWrite(LEDPIN1, sLEDPIN1);
// Simulazione lettura dei pulsanti (da sostituire con digitalRead dai pulsanti reali)
bool varF = false, varR = false, varB = false, varL = false;
moveRobot(varF, varR, varB, varL); // Chiamata della funzione di controllo motori
delay(1000);
varF = true, varR = false, varB = false, varL = false;
moveRobot(varF, varR, varB, varL);
delay(4000);
varF = true, varR = true, varB = false, varL = false;
moveRobot(varF, varR, varB, varL);
delay(4000);
varF = true, varR = true, varB = true, varL = false;
moveRobot(varF, varR, varB, varL);
delay(4000);
varF = true, varR = true, varB = true, varL = true;
moveRobot(varF, varR, varB, varL);
delay(4000);
delay(200);
}
/*
Vedere anche per servo drive in c++
https://wokwi.com/projects/395027653294405633
*/
Loading
esp32-s3-devkitc-1
esp32-s3-devkitc-1