Descargar código en formato 7z: brazorobotico.7z
#include "pantalla.h" #include "teclado.h" #include "dht.h" #include "mando2.h" #include "var.h" #include "brazo.h" void setup() { Serial.begin(9600); Serial3.begin(9600); Serial.println("INICIO"); iniciarPines(); //iniciarPantalla(); iniciarTeclado(); //iniciarDHT(); //iniciarMandoRemoto(); iniciarBrazo(); // interrupcion attachInterrupt(0, pararBrazo, FALLING); } void loop() { /* Serial.print("motor="); Serial.println(motor); Serial.print("motorpp="); Serial.println(motorpp); */ // leer teclado leerTeclado(); // leer mando remoto //leerMandoRemoto(); // leer sensor DHT 22 ////leerDHT(); // leo los pulsadores para ver cual se ha pulsado leerPulsadores(); // almaceno en pulsador el resultado // Si he pulsado un pulsador distinto reinicio variables // estado inicial del programa, antes de pulsar reiniciarVariables(); // Segun el bucle elegido haremos una funcion u otra ejecutarSecuencias(); //pantalla(dibujar2); int estado = 'g'; if (Serial3.available() > 0) { // lee el bluetooth y almacena en estado estado = Serial3.read(); } if (estado == 'a') { // Boton desplazar al Frente pulsador = 0; } if (estado == 'b') { // Boton IZQ pulsador = 1; } if (estado == 'c') { // Boton Parar pulsador = 2; } if (estado == 'd') { // Boton DER pulsador = 3; } if (estado == 'e') { // Boton Reversa } if (estado == 'f') { // Boton ON se mueve sensando distancia } if (estado == 'g') { // Boton OFF, detiene los motores no hace nada } moverMotor(); } void pararBrazo() { motor = -1; motorpp = 10; pararMotor(M1); pararMotor(M2); pararMotor(M3); pararMotor(M4); }
boolean grabar = false; int motorGrabacion[30]; int contadorGrabacion[30]; int pasoGrabacion = 0; int pasosGrabados = 0; int cont = 0; int teclaGrabar = -1; int motorpp = -1; int motor = -1; int motorppAnterior = -1; int contadorM1 = 1000; int contadorMaxM1 = 626; int contadorM2 = 1000; int contadorMaxM2 = 355; int contadorM3 = 1000; int contadorMaxM3 = 530; int contadorM4 = 0; int contadorMaxM4 = 500; int finalCarrera1 = 7; int finalCarrera2 = 6; int finalCarrera3 = 5; int finalCarrera4 = 4; int pinMotores[4][4] = { {22, 24, 26, 28}, {30, 32, 34, 36}, {38, 40, 42, 44}, {39, 41, 43, 45} }; int M1 = 1; int M2 = 2; int M3 = 3; int M4 = 4; // Secuencia de pasos (par máximo) int paso [8][4] = { {1, 0, 0, 0}, {1, 1, 0, 0}, {0, 1, 0, 0}, {0, 1, 1, 0}, {0, 0, 1, 0}, {0, 0, 1, 1}, {0, 0, 0, 1}, {1, 0, 0, 1} };
void giroIzquierda(int numeroMotor, int ret) { for (int i = 0; i < 8; i++) { for (int j = 0; j < 4; j++) { digitalWrite(pinMotores[numeroMotor - 1][j], paso[i][j]); } delay(ret); } } void giroDerecha(int numeroMotor, int ret) { for (int i = 0; i < 8; i++) { for (int j = 0; j < 4; j++) { digitalWrite(pinMotores[numeroMotor - 1][j], paso[i][3 - j]); } delay(ret); } } void pararMotor(int numeroMotor) { for (int i = 0; i < 4; i++) { digitalWrite(pinMotores[numeroMotor - 1][i], LOW); } } // parar los motores excepto el que le pasemos como parametro void pararMotores(int numeroMotor) { for (int i = 1; i < 5; i++) { if (i != numeroMotor) { pararMotor(i); } } } void moverMotor() { //Serial.print(grabar); //Serial.print(" "); digitalWrite(13, grabar); if (grabar) { if ((motorpp != motorppAnterior) && (motorpp != 11)) { motorppAnterior = motorpp; Serial.print("mover motor = "); Serial.println(motorpp); motorGrabacion[pasoGrabacion] = motorpp; if (pasoGrabacion != 0) { contadorGrabacion[pasoGrabacion - 1] = cont; } pasoGrabacion++; cont = 0; } } pararMotores(motor); switch (motorpp) { case 1: if (contadorM1 != 0) { giroIzquierda(M1, 2); contadorM1--; cont++; //Serial.println(cont); } else { pararMotor(M1); } break; case 2: if (contadorM1 < contadorMaxM1) { giroDerecha(M1, 2); contadorM1++; cont++; //Serial.println(cont); } else { pararMotor(M1); } break; case 3: giroDerecha(M1, 2); //giroDerecha(M11, M12, M13, M14, 2); break; case 4: if (contadorM2 != 0) { giroDerecha(M2, 1); contadorM2--; cont++; //Serial.println(cont); //Serial.print("contadorM2="); //Serial.println(contadorM2); } else { pararMotor(M2); } break; case 5: if (contadorM2 < contadorMaxM2) { giroIzquierda(M2, 1); contadorM2++; cont++; //Serial.println(cont); Serial.print("contadorM2="); Serial.println(contadorM2); } else { pararMotor(M2); } break; case 6: giroIzquierda(M2, 1); break; case 7: if (contadorM3 != 0) { giroIzquierda(M3, 1); contadorM3--; cont++; //Serial.println(cont); //Serial.print("contadorM3="); //Serial.println(contadorM3); } else { pararMotor(M3); } break; case 8: if (contadorM3 < contadorMaxM3) { giroDerecha(M3, 1); contadorM3++; cont++; //Serial.println(cont); //Serial.print("contadorM3="); //Serial.println(contadorM3); } else { pararMotor(M3); } break; case 9: giroIzquierda(M3, 3); //giroIzquierda(M31, M32, M33, M34, 3); contadorM3 = 0; break; case 14: if (contadorM4 != 0) { giroDerecha(M4, 1); contadorM4--; cont++; //Serial.println(cont); // Serial.print("contadorM4="); // Serial.println(contadorM4); } else { pararMotor(M4); } break; case 0: if (contadorM4 < contadorMaxM4) { giroIzquierda(M4, 1); contadorM4++; cont++; ///Serial.print("contadorM4="); //Serial.println(contadorM4); } else { pararMotor(M4); } break; case 10: //Serial.println("A"); pararMotor(M1); pararMotor(M2); pararMotor(M3); pararMotor(M4); break; case 11: // Tecla B break; case 12: reproducirSecuencia(); break; case 13: // Tecla D Serial.println("D"); secuenciaProgramada(); } } void secuenciaProgramada() { moverDerecha(500, M1, 2); moverIzquierda(200, M2, 1); moverDerecha(400, M3, 1); moverIzquierda(400, M3, 1); moverDerecha(200, M2, 1); moverIzquierda(500, M1, 2); } void moverIzquierda(int pasos, int numeroMotor, int retardo) { for (int i = 0; i < pasos; i++) { giroIzquierda(numeroMotor, retardo); } pararMotor(numeroMotor); } void moverDerecha(int pasos, int numeroMotor, int retardo) { for (int i = 0; i < pasos; i++) { giroDerecha(numeroMotor, retardo); } pararMotor(numeroMotor); } void moverMotorAutomatico() { } void reproducirSecuencia() { for (int i = pasosGrabados - 1; i >= 0; i--) { switch (motorGrabacion[i]) { case 2: moverIzquierda(contadorGrabacion[i], M1, 2); break; case 1: moverDerecha(contadorGrabacion[i], M1, 2); break; case 5: moverDerecha(contadorGrabacion[i], M2, 1); break; case 4: moverIzquierda(contadorGrabacion[i], M2, 1); break; case 8: moverIzquierda(contadorGrabacion[i], M3, 1); break; case 7: moverDerecha(contadorGrabacion[i], M3, 1); break; } } for (int i = 0; i < pasosGrabados; i++) { switch (motorGrabacion[i]) { case 1: moverIzquierda(contadorGrabacion[i], M1, 2); break; case 2: moverDerecha(contadorGrabacion[i], M1, 2); break; case 4: moverDerecha(contadorGrabacion[i], M2, 1); break; case 5: moverIzquierda(contadorGrabacion[i], M2, 1); break; case 7: moverIzquierda(contadorGrabacion[i], M3, 1); break; case 8: moverDerecha(contadorGrabacion[i], M3, 1); break; } } } void verSecuencia() { Serial.print("grabacion: "); for (int i = 0; i < 30; i++) { Serial.print(motorGrabacion[i]); Serial.print(" "); Serial.print(contadorGrabacion[i]); Serial.print(" | "); } Serial.println(); }
void iniciarMotor(int numeroMotor) { for (int i = 0; i < 4; i++) { pinMode (pinMotores[numeroMotor - 1][i], OUTPUT); } } void iniciarBrazo() { pinMode(finalCarrera1, INPUT); pinMode(finalCarrera2, INPUT); pinMode(finalCarrera3, INPUT); pinMode(finalCarrera4, INPUT); Serial.println("M1"); iniciarMotor(M1); Serial.println("M2"); iniciarMotor(M2); Serial.println("M3"); iniciarMotor(M3); Serial.println("M4"); iniciarMotor(M4); //depurarBrazo1(); posicionInicialBrazo(); //depurarBrazo1(); Serial.println("grabacion"); for (int i = 0; i < 30; i++) { Serial.print(motorGrabacion[i]); Serial.print(" "); } Serial.println(); } void posicionInicialBrazo() { Serial.print("finalCarrera2="); Serial.println(!digitalRead(finalCarrera2)); while (contadorM2 > 0) { Serial.println("VAMOS 2"); if (!digitalRead(finalCarrera2)) { contadorM2 = 0; //Serial.println("contadorM2"); } else { giroDerecha(M2, 1); } } pararMotor(M2); delay(50); Serial.print("finalCarrera3="); Serial.println(!digitalRead(finalCarrera3)); while (contadorM3 > 0) { //Serial.println("VAMOS 3"); if (!digitalRead(finalCarrera3)) { contadorM3 = 0; //Serial.println("contadorM3"); } else { giroIzquierda(M3, 1); } } pararMotor(M3); delay(50); Serial.print("finalCarrera1="); Serial.println(digitalRead(finalCarrera1)); while (contadorM1 > 0) { //Serial.println("VAMOS 1"); if (digitalRead(finalCarrera1)) { contadorM1 = 0; //Serial.println("contadorM1"); } else { giroIzquierda(M1, 2); } } pararMotor(M1); delay(50); // dejar pinza cerrada for (int i = 0; i < contadorMaxM4; i++) { giroDerecha(M4, 1); } contadorM4 = 0; } void depurarBrazo1() { Serial.print(contadorM1); Serial.print(" =M1= "); Serial.print(digitalRead(finalCarrera1)); Serial.print(" "); Serial.print(contadorM2); Serial.print(" =M2= "); Serial.print(!digitalRead(finalCarrera2)); Serial.print(" "); Serial.print(contadorM3); Serial.print(" =M3= "); Serial.print(!digitalRead(finalCarrera3)); Serial.println(" "); } /* delay(500); for (int i = 0; i < 100; i++) { giroDerecha(M11, M12, M13, M14, 2); Serial.println("M1 derecha"); } delay(2500); for (int i = 0; i < 100; i++) { giroIzquierda(M21, M22, M23, M24, 2); Serial.println("M2 izquierda"); } delay(2500); for (int i = 0; i < 100; i++) { giroDerecha(M31, M32, M33, M34, 2); Serial.println("M3 derecha"); } delay(2500); */
#include <DHT.h> #define DHTPIN 41 //#define DHTTYPE DHT11 // DHT 11 #define DHTTYPE DHT22 // DHT 22 (AM2302), AM2321 //#define DHTTYPE DHT21 // DHT 21 (AM2301) DHT dht(DHTPIN, DHTTYPE); float temperatura; float humedad;
void iniciarDHT(){ dht.begin(); } void leerDHT(){ humedad = dht.readHumidity(); temperatura = dht.readTemperature(); // Chequea el sensor. if (isnan(humedad) || isnan(temperatura)) { Serial.println("Ha fallado la lectura del sensor DHT!"); return; } }
#include <IRremote.h> int RECV_PIN = 43; // Usamos el pin 43 para el receptor IR IRrecv irrecv(RECV_PIN); decode_results results; int teclaMandoPulsada; boolean mandoPulsado = false; /* * Extraigo los codigos del mando y los anoto aqui */ /* 0 FF6897 FF9867 1 FF30CF FFA25D 2 FF18E7 FF629D 3 FF7A85 FFE21D 4 FF10EF FF22DD 5 FF38C7 FF02FD 6 FF5AA5 FFC23D 7 FF42BD FFE01F 8 FF4AB5 FFA857 9 FF52AD FF906F CH- Apagado FFA25D CH MODE FF629D CH+ ALTAVOZ FFE21D Retroceso FF22DD Avance FF02FD Pausa FFC23D - FFE01F + FFA857 EQ FF906F 100+ FF9867 200+ Retorno FFB04F * FF6897 # FFB04F Flecha Arriba FF18E7 Flecha Abajo FF4AB5 Flecha Derecha FF5AA5 Flecha Izquierda FF10EF OK FF38C7 */
#define DEPURAR_MANDO_ /* Llamar a esta función en el setup() */ void iniciarMandoRemoto() { irrecv.enableIRIn(); // Inicio el receptor } /* Al pulsar una tecla del mando guardamos un valor numerico en teclaMandoPulsada */ void leerMandoRemoto() { if (irrecv.decode(&results)) { mandoPulsado = true; switch (results.value) { case 0xFF9867: _Depurar("Tecla 0"); teclaMandoPulsada = 0; break; case 0xFFA25D: _Depurar("Tecla 1"); teclaMandoPulsada = 1; break; case 0xFF629D: _Depurar("Tecla 2"); teclaMandoPulsada = 2; break; case 0xFFE21D: _Depurar("Tecla 3"); teclaMandoPulsada = 3; break; case 0xFF22DD: _Depurar("Tecla 4"); teclaMandoPulsada = 4; break; case 0xFF02FD: _Depurar("Tecla 5"); teclaMandoPulsada = 5; break; case 0xFFC23D: _Depurar("Tecla 6"); teclaMandoPulsada = 6; break; case 0xFFE01F: _Depurar("Tecla 7"); teclaMandoPulsada = 7; break; case 0xFFA857: _Depurar("Tecla 8"); teclaMandoPulsada = 8; break; case 0xFF906F: _Depurar("Tecla 9"); teclaMandoPulsada = 9; break; case 0xFF6897: _Depurar("Tecla 10 *"); teclaMandoPulsada = 10; break; case 0xFFB04F: _Depurar("Tecla 11 #"); teclaMandoPulsada = 11; break; case 0xFF18E7: _Depurar("Tecla 12 Flecha Arriba"); teclaMandoPulsada = 12; break; case 0xFF4AB5: _Depurar("Tecla 13 Flecha Abajo"); teclaMandoPulsada = 13; break; case 0xFF5AA5: _Depurar("Tecla 14 Flecha Derecha"); teclaMandoPulsada = 14; break; case 0xFF10EF: _Depurar("Tecla 15 Flecha Izquierda"); teclaMandoPulsada = 15; break; case 0xFF38C7: _Depurar("Tecla 16 OK"); teclaMandoPulsada = 16; break; case 0xFFFFFFFF: break; default: Serial.print("Tecla "); Serial.print(results.value, HEX); Serial.println(" no implementada"); } accionMando(); irrecv.resume(); // Recibir el proximo valor } } void _Depurar(String msg) { #if defined(DEPURAR_MANDO) Serial.println(msg); #endif } void accionMando() { switch (teclaMandoPulsada) { case 1: pulsador = 0; break; case 2: pulsador = 1; break; case 3: pulsador = 2; break; case 4: pulsador = 3; break; } }
#include <U8glib.h> // Para pantalla seria 12864ZW U8GLIB_ST7920_128X64_4X u8g(53, 51, 50);
/* Llamar en el setup() */ void iniciarPantalla() { u8g.setRot180(); u8g.setFont(u8g_font_unifont); u8g.firstPage(); do { u8g.drawStr(0, 10, "Bienvenido"); } while (u8g.nextPage()); } void pantalla(void dibujar()) { u8g.firstPage(); do { dibujar(); } while (u8g.nextPage()); } void dibujar() { u8g.drawStr(20, 30, "Pulsador "); u8g.setPrintPos(40, 50); u8g.print(String(pulsador)); } void dibujar2() { u8g.setPrintPos(5, 10); u8g.print("Tempera: "); u8g.print(String(temperatura)); u8g.print("ºC"); u8g.setPrintPos(5, 30); u8g.print("Humedad: "); u8g.print(String(humedad)); u8g.print("%"); u8g.setPrintPos(5, 50); u8g.print("Pulsador "); u8g.print(String(pulsador)); //u8g.drawStr(20,40,"Pulsador "); //u8g.setPrintPos(50,50); //u8g.print(String(pulsador)); }
void leerPulsadores(){ for (i=0; i<npulsadores;i++){ if (digitalRead(pulsadores[i])){ pulsador = i; } } }
void reiniciarVariables(){ if (pulsador != pulsadorAnterior) { apagarTodos(); contador = 0; tiempo = millis(); pulsadorAnterior = pulsador; } }
void ejecutarSecuencias(){ switch (pulsador) { case 0: encenderTodos(); break; case 1: apagarTodos(); break; case 2: secuencia2(150); break; case 3: secuencia3(150); break; default: pulsador = 10; } } void encenderTodos() { for (i = 0; i < nleds; i++) { digitalWrite(leds[i], HIGH); } } void apagarTodos() { for (i = 0; i < nleds; i++) { digitalWrite(leds[i], LOW); } } void secuencia2(long retardo) { if ((millis() - tiempo) > retardo) { digitalWrite(leds[contador], HIGH); tiempo = millis(); contador++; } if (contador > nleds) { contador = 0; tiempo = millis(); apagarTodos(); } } void secuencia3(long retardo) { if ((millis() - tiempo) > retardo) { if (contador == 0) { digitalWrite(leds[nleds - 1], LOW); } else { digitalWrite(leds[contador - 1], LOW); } digitalWrite(leds[contador], HIGH); tiempo = millis(); contador++; } if (contador > nleds) { tiempo = millis(); contador = 0; apagarTodos(); } }
#include <Keypad.h> const byte filas = 4; // cuatro filas const byte columnas = 4; // cuatro columnas char teclas[filas][columnas] = { { '1', '2', '3', 'A' } , { '4', '5', '6', 'B' } , { '7', '8', '9', 'C' } , { '*', '0', '#', 'D' } }; byte pinesFilas[filas] = { 23, 25, 27, 29 }; // conecta a los pines de salida de la fila del teclado byte pinesColumnas[columnas] = { 31, 33, 35, 37 }; //conecta a los pines de salida de la columna del teclado // Inicializo una instancia de la clase keypad. Keypad keypad = Keypad( makeKeymap(teclas), pinesFilas, pinesColumnas, filas, columnas); String teclaTecladoPulsada; #define DEPURAR_TECLADO void _depurarTeclado(String msg) { #if defined(DEPURAR_TECLADO) Serial.println(msg); #endif }
/* Poner en el setup */ void iniciarTeclado() { keypad.addEventListener(keypadEvent); //añadir un evento al teclado } /* Poner en el loop o dentro de una funcion a usar en el loop */ void leerTeclado() { char key = keypad.getKey(); } /* evento para cuando pulsamos un tecla */ void keypadEvent(KeypadEvent key) { switch (keypad.getState()) { case RELEASED: // se ejecuta al soltar la tecla switch (key) { case '1': _depurarTeclado("Tecla 1"); teclaTecladoPulsada = "1"; pulsador = 0; motorpp = 1; motor = 1; teclaGrabar = 1; break; case '2': _depurarTeclado("Tecla 2"); teclaTecladoPulsada = "2"; pulsador = 1; motorpp = 2; motor = 1; teclaGrabar = 2; break; case '3': _depurarTeclado("Tecla 3"); teclaTecladoPulsada = "3"; pulsador = 2; motorpp = 3; motor = 1; break; case '4': _depurarTeclado("Tecla 4"); teclaTecladoPulsada = "4"; pulsador = 3; motorpp = 4; motor = 2; teclaGrabar = 4; break; case '5': _depurarTeclado("Tecla 5"); teclaTecladoPulsada = "5"; motorpp = 5; motor = 2; teclaGrabar = 5; break; case '6': _depurarTeclado("Tecla 6"); teclaTecladoPulsada = "6"; motorpp = 6; motor = 2; break; case '7': _depurarTeclado("Tecla 7"); teclaTecladoPulsada = "7"; motorpp = 7; motor =3; teclaGrabar = 7; break; case '8': _depurarTeclado("Tecla 8"); teclaTecladoPulsada = "8"; motorpp = 8; motor = 3; teclaGrabar = 8; break; case '9': _depurarTeclado("Tecla 9"); teclaTecladoPulsada = "9"; motorpp = 9; motor =3; //teclaGrabar = 9; break; case '*': _depurarTeclado("Tecla *"); teclaTecladoPulsada = "*"; motorpp = 14; motor = 4; teclaGrabar = 14; break; case '0': _depurarTeclado("Tecla 0"); teclaTecladoPulsada = "0"; motorpp = 0; motor = 4; teclaGrabar = 0; break; case '#': _depurarTeclado("Tecla #"); teclaTecladoPulsada = "#"; motorpp = 15; break; case 'A': _depurarTeclado("Tecla A"); teclaTecladoPulsada = "A"; motorpp = 10; break; case 'B': _depurarTeclado("Tecla B"); teclaTecladoPulsada = "B"; motorpp = 11; grabar = !grabar; pasosGrabados = pasoGrabacion; Serial.print("pasosGrabados="); Serial.println(pasosGrabados); pasoGrabacion = 0; break; case 'C': _depurarTeclado("Tecla C"); teclaTecladoPulsada = "C"; motorpp = 12; verSecuencia(); break; case 'D': _depurarTeclado("Tecla D"); teclaTecladoPulsada = "D"; posicionInicialBrazo(); motorpp = 13; break; default: _depurarTeclado("Tecla " + String(key) + " no implementada"); break; } break; } }
// salidas int leds[] = {13, 12, 11, 10, 9, 8, 7, 6, 5}; int nleds = 9; // entradas int pulsadores[] = {28, 26, 24, 22}; int npulsadores = 4; // variables a usar int pulsador = 10; int pulsadorAnterior = 10; int i; int contador = 0; long tiempo = 0;
void iniciarPines(){ // (leds) Inicializo los pines de salida for (i = 0; i < nleds; i++) { pinMode(leds[i], OUTPUT); } // (pulsadores) Inicializo los pines de entrada for (i = 0; i < npulsadores; i++) { pinMode(pulsadores[i], INPUT); } }