tasks
This commit is contained in:
12
firmwareCarroEsp32/.vscode/extensions.json
vendored
12
firmwareCarroEsp32/.vscode/extensions.json
vendored
@@ -1,7 +1,7 @@
|
|||||||
{
|
{
|
||||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||||
// for the documentation about the extensions.json format
|
// for the documentation about the extensions.json format
|
||||||
"recommendations": [
|
"recommendations": [
|
||||||
"platformio.platformio-ide"
|
"platformio.platformio-ide"
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
|
|||||||
222
firmwareCarroEsp32/data/index.html
Normal file
222
firmwareCarroEsp32/data/index.html
Normal file
@@ -0,0 +1,222 @@
|
|||||||
|
<!doctype html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset=utf-8>
|
||||||
|
<meta name='viewport' content='width=device-width, height=device-height, initial-scale=1.0, maximum-scale=1.0'/>
|
||||||
|
<title>ESP32 CARRO</title>
|
||||||
|
|
||||||
|
<style>
|
||||||
|
*{-webkit-touch-callout: none;
|
||||||
|
-webkit-text-size-adjust: none;
|
||||||
|
-webkit-tap-highlight-color: #FFFFFF;
|
||||||
|
-webkit-user-select: none;
|
||||||
|
-webkit-tap-highlight-color: #FFFFFF;}
|
||||||
|
|
||||||
|
body {margin: 0px;}
|
||||||
|
canvas {display:block; position:absolute}
|
||||||
|
.containerButtons {width: auto; display: flex; justify-content: space-around;}
|
||||||
|
.buttons {border: none; color: white; padding: 4px 4px; text-align: center; text-decoration: none; display: inline-block; font-size: 4.0vmin; font-weight: bold; margin: 4px 2px;
|
||||||
|
-webkit-transition-duration: 0.4s; transition-duration: 0.4s; cursor: pointer; width: 25%; border-radius: 2px;}
|
||||||
|
.btn1 {background-color: #808080; color: #FFFFFF; border: 3px solid #808080;} .btn1:hover {background-color: #F2F2F2; color: #000000; border: 3px solid #FF0000;}
|
||||||
|
.btn2 {background-color: #1E90FF; color: #FFFFFF; border: 3px solid #1E90FF;} .btn2:hover {background-color: #F2F2F2; color: #000000; border: 3px solid #FF0000;}
|
||||||
|
.data {padding: 2px 4px; background-color: #F2F2F2; color: #000000; font-size: 3.5vmin; border: 2px solid #000000;}
|
||||||
|
.containerCanvas {width: auto;}
|
||||||
|
</style>
|
||||||
|
|
||||||
|
<body id='body'>
|
||||||
|
<div class='containerButtons'>
|
||||||
|
<button class='buttons btn1' onclick='onStatic()' autofocus>Estático</button>
|
||||||
|
<button class='buttons btn2' onclick='onDynamic()'>Dinámico</button>
|
||||||
|
<p id='txt1_id' class='buttons data'></p>
|
||||||
|
<p id='txt2_id' class='buttons data'></p>
|
||||||
|
<p id='distancia' class='buttons data'></p>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<script>
|
||||||
|
|
||||||
|
///////VARIABLES GLOBALES Y OPERACIONES CON VECTORES ///////
|
||||||
|
var canvas, c , containerCanvas, ratioWindow, ladoMenor;
|
||||||
|
var estatico = true, touchStart = false, mouseDown = false;
|
||||||
|
var angRad, angGrd, vectorHypot, speed;
|
||||||
|
var vector2 = function (x,y) {this.x= x || 0; this.y = y || 0;};
|
||||||
|
let distancia =0;
|
||||||
|
var distancia_label = document.getElementById('distancia');
|
||||||
|
vector2.prototype = {
|
||||||
|
reset: function ( x, y ) {this.x = x; this.y = y; return this;},
|
||||||
|
copyFrom : function (v) {this.x = v.x; this.y = v.y; return this;},
|
||||||
|
minusEq : function (v) {this.x-= v.x; this.y-= v.y; return this;},
|
||||||
|
};
|
||||||
|
var pos = new vector2(0,0), startPos = new vector2(0,0), vector = new vector2(0,0), posMax = new vector2(0,0);
|
||||||
|
|
||||||
|
var connection = new WebSocket('ws://'+location.hostname+':81/', ['arduino']);
|
||||||
|
connection.onopen = function () {connection.send('Connect ' + new Date()); };
|
||||||
|
connection.onerror = function (error) {console.log('WebSocket Error ', error);};
|
||||||
|
connection.onmessage = function (event) {
|
||||||
|
|
||||||
|
if(!isNaN(event.data))
|
||||||
|
|
||||||
|
distancia = parseInt(event.data,10)
|
||||||
|
distancia_label.innerHTML = 'Distancia<br/>'+distancia +" cm";
|
||||||
|
console.log('Server: ', distancia);
|
||||||
|
};
|
||||||
|
|
||||||
|
///////CANVAS///////
|
||||||
|
setupCanvas();
|
||||||
|
function setupCanvas() {
|
||||||
|
canvas = document.createElement('canvas');
|
||||||
|
c = canvas.getContext('2d');
|
||||||
|
resetAll();
|
||||||
|
containerCanvas = document.createElement('div');
|
||||||
|
containerCanvas.className = "containerCanvas";
|
||||||
|
document.body.appendChild(containerCanvas);
|
||||||
|
containerCanvas.appendChild(canvas);
|
||||||
|
}
|
||||||
|
function resetAll () {
|
||||||
|
var buttonsHeight = Math.min(window.innerWidth, window.innerHeight)*0.04+44;
|
||||||
|
canvas.width = window.innerWidth; canvas.height = window.innerHeight-buttonsHeight;
|
||||||
|
ratioWindow = canvas.width/canvas.height; ladoMenor=Math.min(canvas.width, canvas.height);
|
||||||
|
window.scrollTo(0,0);
|
||||||
|
c.font = Math.round(ladoMenor*0.03) + 'px sans-serif';
|
||||||
|
c.fillStyle = "white";
|
||||||
|
c.textAlign="center";
|
||||||
|
estatico? onStatic() : onDynamic();
|
||||||
|
}
|
||||||
|
function resetByOrientationchange () {
|
||||||
|
document.body.removeChild(containerCanvas);
|
||||||
|
setTimeout(function(){
|
||||||
|
setupCanvas();
|
||||||
|
startEventListener();
|
||||||
|
}, 450);
|
||||||
|
}
|
||||||
|
|
||||||
|
///////DETECCIÓN DE EVENTOS Y DETERMINACIÓN DEL TIPO DE DISPOSITIVO SEÑALADOR (TÁCTIL O RATÓN)///////
|
||||||
|
var touchable = 'createTouch' in document;
|
||||||
|
startEventListener();
|
||||||
|
function startEventListener(){
|
||||||
|
window.onresize = resetAll;
|
||||||
|
if(touchable) {
|
||||||
|
canvas.addEventListener( 'touchstart', onTouchStart, false);
|
||||||
|
canvas.addEventListener( 'touchmove', onTouchMove, false);
|
||||||
|
canvas.addEventListener( 'touchend', onTouchEnd, false);
|
||||||
|
window.onorientationchange = resetByOrientationchange;
|
||||||
|
} else {
|
||||||
|
canvas.addEventListener( 'mousedown', onMouseDown, false);
|
||||||
|
canvas.addEventListener( 'mousemove', onMouseMove, false);
|
||||||
|
['mouseup', 'mouseout'].forEach(function(event){canvas.addEventListener(event,onMouseEnd,false);});
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
///////ESTÁTICO / DINÁMICO///////
|
||||||
|
function onStatic() {
|
||||||
|
estatico = true;
|
||||||
|
document.getElementById('body').style.background= '#CECECE';
|
||||||
|
c.strokeStyle = '#808080';
|
||||||
|
drawOnCanvasStartOrMoveEnd();
|
||||||
|
}
|
||||||
|
function onDynamic() {
|
||||||
|
estatico = false;
|
||||||
|
document.getElementById('body').style.background= '#ADD8E6';
|
||||||
|
c.strokeStyle = '#1E90FF';
|
||||||
|
drawOnCanvasStartOrMoveEnd();
|
||||||
|
}
|
||||||
|
|
||||||
|
///////GESTIÓN DE DISPOSITIVO TÁCTIL///////
|
||||||
|
function onTouchStart(event) {
|
||||||
|
touchStart = true;
|
||||||
|
if (estatico){
|
||||||
|
pos.reset(event.touches[0].clientX-canvas.getBoundingClientRect().left, event.touches[0].clientY-canvas.getBoundingClientRect().top);
|
||||||
|
vector.copyFrom(pos);
|
||||||
|
vector.minusEq(startPos);
|
||||||
|
} else {
|
||||||
|
startPos.reset(event.touches[0].clientX-canvas.getBoundingClientRect().left, event.touches[0].clientY-canvas.getBoundingClientRect().top);
|
||||||
|
pos.copyFrom(startPos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
function onTouchMove(event) {
|
||||||
|
if (touchStart){
|
||||||
|
event.preventDefault();
|
||||||
|
pos.reset(event.touches[0].clientX-canvas.getBoundingClientRect().left, event.touches[0].clientY-canvas.getBoundingClientRect().top);
|
||||||
|
vector.copyFrom(pos);
|
||||||
|
vector.minusEq(startPos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
function onTouchEnd(event) {
|
||||||
|
touchStart = false;
|
||||||
|
drawOnCanvasStartOrMoveEnd();
|
||||||
|
sendData ();
|
||||||
|
}
|
||||||
|
|
||||||
|
///////GESTIÓN DEL RATÓN///////
|
||||||
|
function onMouseDown(event) {
|
||||||
|
event.preventDefault();
|
||||||
|
mouseDown = true;
|
||||||
|
if (estatico){
|
||||||
|
pos.reset(event.offsetX, event.offsetY);
|
||||||
|
vector.copyFrom(pos);
|
||||||
|
vector.minusEq(startPos);
|
||||||
|
} else {
|
||||||
|
startPos.reset(event.offsetX, event.offsetY);
|
||||||
|
pos.copyFrom(startPos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
function onMouseMove(event) {
|
||||||
|
if(mouseDown){
|
||||||
|
pos.reset(event.offsetX, event.offsetY);
|
||||||
|
vector.copyFrom(pos);
|
||||||
|
vector.minusEq(startPos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
function onMouseEnd(event) {
|
||||||
|
mouseDown = false;
|
||||||
|
drawOnCanvasStartOrMoveEnd();
|
||||||
|
sendData ();
|
||||||
|
}
|
||||||
|
|
||||||
|
///////DIBUJO DE LA BASE Y STICK///////
|
||||||
|
setInterval(drawOnMove, 1000/50);
|
||||||
|
function drawOnMove() {
|
||||||
|
if(touchStart || mouseDown) {
|
||||||
|
c.clearRect(0,0,canvas.width, canvas.height);
|
||||||
|
drawBase (startPos.x, startPos.y);
|
||||||
|
newValues ();
|
||||||
|
drawStick ();
|
||||||
|
drawText ();
|
||||||
|
sendData ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
function drawOnCanvasStartOrMoveEnd(){
|
||||||
|
c.clearRect(0,0,canvas.width, canvas.height);
|
||||||
|
startPos.reset(canvas.width/2,canvas.height/2);
|
||||||
|
vector.reset(0,0);
|
||||||
|
estatico? drawBase() : c.fillText('TOCA LA PANTALLA PARA COMENZAR',canvas.width/2,canvas.height/2);
|
||||||
|
newValues ();
|
||||||
|
drawText ();
|
||||||
|
}
|
||||||
|
function newValues(){
|
||||||
|
angRad = Math.atan2(-vector.y,vector.x).toFixed(2);
|
||||||
|
angGrd = Math.round(angRad*180/Math.PI);
|
||||||
|
vectorHypot = Math.hypot(vector.x,vector.y);
|
||||||
|
posMax.reset(startPos.x+Math.min(vectorHypot, ladoMenor*0.25)*Math.cos(angRad), startPos.y-Math.min(vectorHypot, ladoMenor*0.25)*Math.sin(angRad));
|
||||||
|
speed = Math.round((Math.min(vectorHypot,ladoMenor*0.25)/(ladoMenor*0.25)*100));
|
||||||
|
}
|
||||||
|
function drawBase(){
|
||||||
|
c.beginPath(); c.lineWidth = 6; c.arc(startPos.x, startPos.y, ladoMenor*0.10 ,0,Math.PI*2,true); c.stroke();
|
||||||
|
c.beginPath(); c.lineWidth = 2; c.arc(startPos.x, startPos.y, ladoMenor*0.35 ,0,Math.PI*2,true); c.stroke();
|
||||||
|
}
|
||||||
|
function drawStick(){
|
||||||
|
c.beginPath(); c.arc(posMax.x, posMax.y, ladoMenor*0.10, 0,Math.PI*2, true); c.stroke();
|
||||||
|
}
|
||||||
|
|
||||||
|
function drawText(){
|
||||||
|
document.getElementById('txt2_id').innerHTML = 'Ángulo<br/>'+angGrd+'º';
|
||||||
|
document.getElementById('txt1_id').innerHTML = 'Velocidad<br/>'+speed+'%';
|
||||||
|
|
||||||
|
}
|
||||||
|
function sendData(){
|
||||||
|
var dir = 'Velocidad:'+speed+' Angulo:'+angRad;
|
||||||
|
console.log(dir);
|
||||||
|
connection.send(dir);
|
||||||
|
}
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
@@ -13,4 +13,9 @@ platform = espressif32
|
|||||||
board = mhetesp32devkit
|
board = mhetesp32devkit
|
||||||
framework = arduino
|
framework = arduino
|
||||||
|
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
|
upload_protocol = espota
|
||||||
|
upload_port = 192.168.1.109
|
||||||
|
upload_flags =
|
||||||
|
--port=3232
|
||||||
|
--auth=un260874
|
||||||
@@ -1,10 +1,6 @@
|
|||||||
# include "Arduino.h"
|
# include "Arduino.h"
|
||||||
# include "OpenTB6612FNG.h"
|
# include "OpenTB6612FNG.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
OpenTB6612FNG::OpenTB6612FNG(int TP) {
|
OpenTB6612FNG::OpenTB6612FNG(int TP) {
|
||||||
|
|
||||||
pinMode(AIN1, OUTPUT);
|
pinMode(AIN1, OUTPUT);
|
||||||
@@ -13,47 +9,16 @@ OpenTB6612FNG::OpenTB6612FNG(int TP) {
|
|||||||
pinMode(BIN1, OUTPUT);
|
pinMode(BIN1, OUTPUT);
|
||||||
pinMode(BIN2, OUTPUT);
|
pinMode(BIN2, OUTPUT);
|
||||||
pinMode(PWMB, OUTPUT);
|
pinMode(PWMB, OUTPUT);
|
||||||
analogWriteFreq(20000);
|
analogWriteResolution(10);
|
||||||
analogWriteRange(255);
|
analogWriteFrequency(10000);
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void OpenTB6612FNG::MotorIz(int value) {
|
void OpenTB6612FNG::MotorIz(int value) {
|
||||||
/* if (value >= 0) {
|
|
||||||
// si valor positivo vamos hacia adelante
|
|
||||||
|
|
||||||
digitalWrite(AIN1, HIGH);
|
|
||||||
digitalWrite(AIN2, LOW);
|
|
||||||
} else {
|
|
||||||
// si valor negativo vamos hacia atras
|
|
||||||
|
|
||||||
digitalWrite(AIN1, LOW);
|
|
||||||
digitalWrite(AIN2, HIGH);
|
|
||||||
value *= -1;
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
// Setea Velocidad
|
|
||||||
|
|
||||||
analogWrite(MOTOR_IZQ, value);
|
analogWrite(MOTOR_IZQ, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
void OpenTB6612FNG::MotorDe(int value) {
|
void OpenTB6612FNG::MotorDe(int value) {
|
||||||
/* if (value >= 0) {
|
|
||||||
// si valor positivo vamos hacia adelante
|
|
||||||
|
|
||||||
digitalWrite(BIN1, HIGH);
|
|
||||||
digitalWrite(BIN2, LOW);
|
|
||||||
} else {
|
|
||||||
// si valor negativo vamos hacia atras
|
|
||||||
|
|
||||||
digitalWrite(BIN1, LOW);
|
|
||||||
digitalWrite(BIN2, HIGH);
|
|
||||||
value *= -1;
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
// Setea Velocidad
|
|
||||||
|
|
||||||
analogWrite(MOTOR_DER, value);
|
analogWrite(MOTOR_DER, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -78,9 +43,6 @@ void OpenTB6612FNG::Backward()
|
|||||||
digitalWrite(BIN2, HIGH);
|
digitalWrite(BIN2, HIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void OpenTB6612FNG::Stop()
|
void OpenTB6612FNG::Stop()
|
||||||
{
|
{
|
||||||
digitalWrite(AIN1, LOW);
|
digitalWrite(AIN1, LOW);
|
||||||
|
|||||||
@@ -1,12 +1,13 @@
|
|||||||
#ifndef OpenTB6612FNG_h
|
#ifndef OpenTB6612FNG_h
|
||||||
#define OpenTB6612FNG_h
|
#define OpenTB6612FNG_h
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#define PWMA D1
|
#include <analogWrite.h>
|
||||||
#define AIN1 D2
|
#define PWMA 33
|
||||||
#define AIN2 D3
|
#define AIN1 26
|
||||||
#define BIN1 D4
|
#define AIN2 25
|
||||||
#define BIN2 D5
|
#define BIN1 27
|
||||||
#define PWMB D6
|
#define BIN2 14
|
||||||
|
#define PWMB 13
|
||||||
#define MOTOR_IZQ PWMB
|
#define MOTOR_IZQ PWMB
|
||||||
#define MOTOR_DER PWMA
|
#define MOTOR_DER PWMA
|
||||||
|
|
||||||
@@ -14,7 +15,7 @@
|
|||||||
class OpenTB6612FNG{
|
class OpenTB6612FNG{
|
||||||
public:
|
public:
|
||||||
OpenTB6612FNG(int TP);
|
OpenTB6612FNG(int TP);
|
||||||
|
|
||||||
void MotorIz(int value);
|
void MotorIz(int value);
|
||||||
void MotorDe(int value);
|
void MotorDe(int value);
|
||||||
void Motores(int left, int righ);
|
void Motores(int left, int righ);
|
||||||
|
|||||||
@@ -1,10 +1,10 @@
|
|||||||
#ifndef CARROESP32_h
|
#ifndef CARROESP32_h
|
||||||
#define CARROESP32_h
|
#define CARROESP32_h
|
||||||
#define OUT1 A13
|
#define OUT1 36
|
||||||
#define OUT2 A16
|
#define OUT2 39
|
||||||
#define OUT3 A15
|
#define OUT3 34
|
||||||
#define OUT4 A10
|
#define OUT4 35
|
||||||
#define OUT5 A14
|
#define OUT5 32
|
||||||
|
|
||||||
int sensores[5] = {0, 0, 0, 0, 0};
|
int sensores[5] = {0, 0, 0, 0, 0};
|
||||||
|
|
||||||
@@ -15,6 +15,7 @@ void readSensors()
|
|||||||
sensores[2] = analogRead(OUT3);
|
sensores[2] = analogRead(OUT3);
|
||||||
sensores[3] = analogRead(OUT4);
|
sensores[3] = analogRead(OUT4);
|
||||||
sensores[4] = analogRead(OUT5);
|
sensores[4] = analogRead(OUT5);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void printSensores()
|
void printSensores()
|
||||||
@@ -35,8 +36,27 @@ void init_sensores(){
|
|||||||
pinMode(OUT5, INPUT);
|
pinMode(OUT5, INPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int readSensors(int chanel)
|
||||||
|
{
|
||||||
|
|
||||||
|
switch (chanel)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
return analogRead(OUT1);
|
||||||
|
case 1:
|
||||||
|
return analogRead(OUT2);
|
||||||
|
case 2:
|
||||||
|
return analogRead(OUT3);
|
||||||
|
case 3:
|
||||||
|
return analogRead(OUT4);
|
||||||
|
case 4:
|
||||||
|
return analogRead(OUT5);
|
||||||
|
|
||||||
|
|
||||||
|
default:
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
9
firmwareCarroEsp32/src/config_ota.hpp
Normal file
9
firmwareCarroEsp32/src/config_ota.hpp
Normal file
@@ -0,0 +1,9 @@
|
|||||||
|
|
||||||
|
void ota_init()
|
||||||
|
{
|
||||||
|
ArduinoOTA.setHostname("OtaEsp32");
|
||||||
|
ArduinoOTA.setPassword((const char *)"un260874");
|
||||||
|
ArduinoOTA.setPort(3232);
|
||||||
|
ArduinoOTA.begin();
|
||||||
|
}
|
||||||
|
|
||||||
@@ -1,30 +1,72 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "BluetoothSerial.h"
|
|
||||||
#include "carroEsp32.h"
|
#include "carroEsp32.h"
|
||||||
#include "OpenTB6612FNG/OpenTB6612FNG.h"
|
#include "OpenTB6612FNG/OpenTB6612FNG.h"
|
||||||
|
#include "wifi_config.hpp"
|
||||||
|
#include "SPIFFS.h"
|
||||||
|
#include <ArduinoOTA.h>
|
||||||
|
#include "config_ota.hpp"
|
||||||
|
TaskHandle_t TareaProcesador1;
|
||||||
|
TaskHandle_t TareaProcesador2;
|
||||||
|
void loop1(void *pvParameters);
|
||||||
|
void loop2(void *pvParameters);
|
||||||
|
int anterior = millis();
|
||||||
|
char sensorCadena[16];
|
||||||
|
|
||||||
|
|
||||||
OpenTB6612FNG misMotores(0);
|
OpenTB6612FNG misMotores(0);
|
||||||
BluetoothSerial ESP_BT; //Object for Bluetooth
|
|
||||||
|
|
||||||
|
#include "managerServer.hpp"
|
||||||
|
|
||||||
void setup() {
|
void setup()
|
||||||
init_sensores();
|
{
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
wifi();
|
||||||
|
ota_init();
|
||||||
|
SPIFFS.begin();
|
||||||
|
init_sensores();
|
||||||
|
|
||||||
|
webSocket.begin();
|
||||||
|
webSocket.onEvent(webSocketEvent);
|
||||||
|
server.begin();
|
||||||
|
xTaskCreatePinnedToCore(loop1, "Tarea1", 10000, NULL, 1, &TareaProcesador1, 0);
|
||||||
|
xTaskCreatePinnedToCore(loop2, "Tarea2", 10000, NULL, 1, &TareaProcesador2, 1);
|
||||||
|
delay(200);
|
||||||
|
|
||||||
Serial.println("Carro Esp32");
|
Serial.println("Carro Esp32");
|
||||||
ESP_BT.begin("CARRO ESP32"); //Name of your Bluetooth Signal
|
|
||||||
|
// handle index
|
||||||
|
server.on("/", []() {
|
||||||
|
File index = SPIFFS.open("/index.html", "r");
|
||||||
|
server.streamFile(index, "text/html");
|
||||||
|
index.close();
|
||||||
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop()
|
||||||
misMotores.Forward();
|
{
|
||||||
misMotores.Motores(255,255);
|
}
|
||||||
if (ESP_BT.available()) //Check if we receive anything from Bluetooth
|
void loop1(void *pvParameters)
|
||||||
|
{
|
||||||
|
for (;;)
|
||||||
{
|
{
|
||||||
//incoming = ESP_BT.read(); //Read what we recevive
|
webSocket.loop();
|
||||||
Serial.print("Received:"); Serial.println(ESP_BT.read());
|
ArduinoOTA.handle();
|
||||||
|
server.handleClient();
|
||||||
|
delay(10);
|
||||||
}
|
}
|
||||||
//readSensors();
|
|
||||||
//printSensores();
|
|
||||||
//delay(500);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void loop2(void *pvParameters)
|
||||||
|
{
|
||||||
|
for (;;)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (((millis() - anterior) > 100) && (nCliente > -1))
|
||||||
|
{
|
||||||
|
anterior = millis();
|
||||||
|
|
||||||
|
sprintf(sensorCadena, "%d",readSensors(0));
|
||||||
|
webSocket.sendTXT(nCliente, sensorCadena);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
63
firmwareCarroEsp32/src/managerServer.hpp
Normal file
63
firmwareCarroEsp32/src/managerServer.hpp
Normal file
@@ -0,0 +1,63 @@
|
|||||||
|
int nCliente = -1;
|
||||||
|
WebServer server (80);
|
||||||
|
WebSocketsServer webSocket = WebSocketsServer(81);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) {
|
||||||
|
|
||||||
|
switch (type) {
|
||||||
|
case WStype_DISCONNECTED:
|
||||||
|
Serial.printf("[%u] Disconnected!\n", num);
|
||||||
|
misMotores.Stop();
|
||||||
|
nCliente =-1;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case WStype_CONNECTED: {
|
||||||
|
IPAddress ip = webSocket.remoteIP(num);
|
||||||
|
Serial.printf("[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload);
|
||||||
|
webSocket.sendTXT(num, "Connected");
|
||||||
|
nCliente = num; // send message to client
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case WStype_TEXT:
|
||||||
|
//Serial.printf("Número de conexión: %u - Texto recibido: %s\n", num, payload);
|
||||||
|
if (num == 0) { //Únicamente va a reconocer la primera conexión (softAP).
|
||||||
|
String str = (char*)payload; //Ejemplo de texto recibido: Velocidad:100 Angulo:-1.88
|
||||||
|
int velocidad = str.substring(str.indexOf(':', str.indexOf("Velocidad:")) + 1, str.indexOf(' ', str.indexOf("Velocidad:"))).toInt();
|
||||||
|
float angulo = str.substring(str.indexOf(':', str.indexOf("Angulo:")) + 1).toFloat();
|
||||||
|
|
||||||
|
//uint8_t velocidadMax = velocidad*255/100; //La velocidad se envía con valores entre 0 y 100. Se debe mapear a 0-255
|
||||||
|
uint8_t velocidadMax = 85 + velocidad * 170 / 100; //Se corrige el mapeo porque el motor entre los valores 0-84 no se mueve, se mueve ente los valores 85-255
|
||||||
|
|
||||||
|
uint8_t velocidadSin = abs(velocidadMax * sin(angulo)); //Giro coche rápido
|
||||||
|
//uint8_t velocidadSin = abs(velocidadMax*sin(abs(2*angulo/3)+PI/6)); //Giro coche intermedio
|
||||||
|
//uint8_t velocidadSin = abs(velocidadMax*sin(abs(angulo/2)+PI/4)); //Giro coche lento
|
||||||
|
float anguloCos = cos(angulo);
|
||||||
|
|
||||||
|
//Sentido de giro de los motores
|
||||||
|
if (angulo > 0) { //Primer y segundo cuadrante
|
||||||
|
misMotores.Forward();
|
||||||
|
} else if (angulo < 0) { //Tercer y cuarto cuadrante
|
||||||
|
misMotores.Backward();
|
||||||
|
} else { //Parado
|
||||||
|
misMotores.Stop();
|
||||||
|
}
|
||||||
|
//Velocidad de los motores
|
||||||
|
uint8_t izq, der;
|
||||||
|
if (anguloCos > 0) { //Primer y cuarto cuadrante
|
||||||
|
izq = velocidadMax;
|
||||||
|
der = velocidadSin;
|
||||||
|
} else { //Segundo y tercer cuadrante
|
||||||
|
izq = velocidadSin;
|
||||||
|
der = velocidadMax;
|
||||||
|
}
|
||||||
|
misMotores.Motores(izq,der);
|
||||||
|
|
||||||
|
Serial.print(anguloCos); Serial.print(" "); Serial.print(izq); Serial.print(" "); Serial.println(der);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
28
firmwareCarroEsp32/src/wifi_config.hpp
Normal file
28
firmwareCarroEsp32/src/wifi_config.hpp
Normal file
@@ -0,0 +1,28 @@
|
|||||||
|
#include <Arduino.h>
|
||||||
|
#include <WiFi.h>
|
||||||
|
#include <WebServer.h>
|
||||||
|
#include <WebSocketsServer.h>
|
||||||
|
|
||||||
|
const char* ssid = "mdchaparror";
|
||||||
|
const char* password = "un260874";
|
||||||
|
int contconexion = 0;
|
||||||
|
void wifi(){
|
||||||
|
//setup wifi
|
||||||
|
WiFi.mode(WIFI_STA); //para que no inicie el SoftAP en el modo normal
|
||||||
|
WiFi.begin(ssid, password);
|
||||||
|
while (WiFi.status() != WL_CONNECTED and contconexion < 50) { //Cuenta hasta 50 si no se puede conectar lo cancela
|
||||||
|
++contconexion;
|
||||||
|
delay(500);
|
||||||
|
Serial.print(".");
|
||||||
|
}
|
||||||
|
if (contconexion < 50) {
|
||||||
|
|
||||||
|
Serial.println("");
|
||||||
|
Serial.println("WiFi conectado");
|
||||||
|
Serial.println(WiFi.localIP());
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
Serial.println("");
|
||||||
|
Serial.println("Error de conexion");
|
||||||
|
}
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user