Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
cuadrupedo2018
Aquí encontrarás todo lo correspondiente al proyecto de embebidos de 7 semestre- Ingeniería Mecatrónica
Para iniciar entramos a la pagina de mbed y nos disponemos a crear un perfil de usuario en la pestaña de sing in
Se abre una ventana como la siguiente y se ingresan los datos correspondientes
Después de crear el perfil nos dirigimos a este link: https://os.mbed.com/users/andrescas/code/Entrega/wiki/cuadrupedo2018 En el cual nos abrirá la wiki y el código de programa a usar en el proyecto
TARJETA DE CONTROL¶
Para la segunda entrega de la materia embebidos se busca realizar el movimiento de un cuadrúpedo el cual tendrá forma de araña, el dispositivo de control sera la tarjeta STM32F446. La programación esta hecha mediante el lenguaje C++ el cual es ampliamente utilizado en proyectos de sistemas embebidos debido a su gran versatilidad y compatibilidad con estos sistemas.
ENTORNO DE PROGRAMACION¶
El entorno de programación utilizado para el proyecto es Mbed, es una plataforma y sistemaoperativo para dispositivos conectados a Internet basados en microcontroladores ARM Cortex-Mde 32 bits. Dichos dispositivos también se conocen como dispositivos de Internet de las Cosas. El proyecto es desarrollado colaborativamente por Arm y sus socios tecnológicos.
ACTUADORES¶
El conjunto de actudores utilizado para este proyecto son los servomotores SG90 los cuales Servo2
poseen un troque de 1.8 Kg/cm. Esto representa un baja inversión y es mas que suficiente para realizar el movimiento de las 8 articulaciones del cuadrúpedo.
Aquí podrás encontrar su Datasheet con sus características y conexiones : http://akizukidenshi.com/download/ds/towerpro/SG90.pdf
SENSOR¶
En este apartado encontramos el sensor de color TCS3200 con el cual detectaremos distintos colores mediante una conversión de frecuencias las cuales nos darán unos rangos adecuados para cada color detectado y con esto haremos distintos movimiento programados anteriormente en el código. Aquí podrás encontrar su Datasheet con sus características y conexiones : https://www.mouser.com/catalog/specsheets/TCS3200-E11.pdf
CONTROL ANALOGO¶
equipado con un modulo joystick con el cual se controlara el avance y retroceso de la araña. este funciona mediante una señal analoga segun la pocision en la que se este direccionando la palanca, esta señal en la tarjeta de control se vuelve digital y de este modo se define un proceso. en el siguiente link se encuentran sus caracteristicas y especificaciones: http://www.energiazero.org/arduino_sensori/joystick_module.pdf
despues de conocer los componentes nos disponemos a realizar las conecciones: iniciaremos conectando todos los servomotores
como se ve en la imagen todos los servomotores se conectan los vcc y gnd a 5v y las señales se conectaran a estos puerto de nuestra tarjeta nucleo f446. PwmOut myServo1(PB_5); PwmOut myServo2(PB_3); PwmOut myServo3(PA_5); PwmOut myServo4(PA_6); PwmOut myServo5(PA_7); PwmOut myServo6(PA_8); PwmOut myServo7(PA_9); PwmOut myServo8(PA_10);
de una vez se inicializan como salidas de pwm nota: si se quiere cambiar de puerto hay que verificar que el periferico tenga como opcion salida de PWM
Despues proseguimos a conectar el sensor de color:
como se observan los pines del sensor nos disponemos a conectar el vcc y gnd a 5v, los pines s0,s1,s2,s3, se conectan a la tarjeta por estos perifericos: DigitalOut S0(PA_13); DigitalOut S1(PA_14); DigitalOut S2(PC_14); DigitalOut S3(PC_8); y se inicializan como salidas digitales, estos pines son los que manejan que color queremos leer y el porcentaje de lectura de nuestro sensor, el otro pin a conectar es el pin OUT se conecta a la tarjeta en el periferico: DigitalIn leer(PC_9); y si inicializa como entrada digital, este pin es el que nos envia la frecuencia de lectura del sensor dependiendo del color varia la frecuencia
para finalizar se conecta el joystick:
se conectan los vcc y gnd a 3.3v, y las entradas a estos perifericos: AnalogIn analog_value(A0); AnalogIn analog_value(A1); se inicializan como entradas analogas las cuales son las que leera el programa y el llevara acabo las funciones de movimiento.
despues de conectar todo nos dirigimos a la pestaña de home:
y buscamos en la parte superior derecha el boton de import into compiler y hacemos click
ahi lo nombramos como se desee y le damos continuar
se abre la pestaña de main.cpp
se compila el programa y despues se busca en la carpeta donde se descargo el codigo BIN se le da click derecho-enviar a- y se busca node 446
COOLTERM¶
Por medio de este programa se enviaran los comandos hexadecimales de cinco caracteres
Primer carácter es la entrada del comando: FF Segundo carácter es el numero de comando: 01 Tercer carácter es el numero del servomotor: (Del 1 al 8) Cuarto carácter es el numero del grado al cual se va a mover el servomotor: 0 a 180 Quinto carácter es el final del comando: FD
Despues en el programa las lecturas que obtenemos del sensor o del jostick las imprimimos en la pantalla principal
CODIGO¶
En esta parte del programa se encuntran las declaraciones de los pines de entrada y salida, aqui se encuentran los pines usados para el funcionamiento de los servomotores, entradas analogas para el funcionamiento del Joyestick y el sensor de color. Ademas encontramos las declaraciones de las funciones en las cuales esta dividido el funcinamiento general del programa.
include the mbed library with this snippet
#include "mbed.h" Serial pc(USBTX, USBRX); // leer comnunicacion serial Serial pcBT(D8, D2); // tx, rx AnalogIn analog_value(A0); // definimos puerto para leer analogamente el joystick PwmOut myServo1(PC_7); // definir puertos de los servos PwmOut myServo2(PB_4); PwmOut myServo3(PB_5); PwmOut myServo4(PB_8); PwmOut myServo5(PA_6); PwmOut myServo6(PB_9); PwmOut myServo7(PA_8); PwmOut myServo8(PA_7); DigitalOut led(LED1,0); //led indicador de interrupcion DigitalOut S0(PA_13); //definimos los puertos del sensor DigitalOut S1(PA_14); DigitalOut S2(PA_15); DigitalOut S3(PC_8); DigitalIn leer(PC_9); // puerto donde leemos la frecuencia que envia el sensor Timer tiempo; // timer para uso del sensor Timeout timeout; //creamos el objeto timeout unsigned int lectura(); //respuesta de lectura de sensor unsigned int inicio=0, final=0, resultado=0, rojo=0,verde=0,azul=0;// variables que se usan en los procesos float meas_r; //variables del joystick float meas_v; void moving(); void grupomover(); void mover_ser(uint8_t nmotor, uint8_t pos); void timer_interrupt(); void read_command(); // definimos los 4 numeros hexadecimales enviados void read_commandbt(); // definimos los 4 numeros hexadecimales enviados void adelante(); void atras(); void init_servo(); char init_c; int read_cc; uint32_t grados; uint32_t nmotor; int endc;
En el siguiente apartado encontramos la funcion principal del programa, que es la encargada del funcionamiento del cuadrupedo. Si se observa detalladamente se puede ver que es muy corta, lo anterior debido a que el programa esta hecho en su mayoria por funciones que permiten sintetizar el funcionamiento del mismo.
include the mbed library with this snippet
int main() { pc.baud(9600); // leer en el monitor serial pc.printf("inicio\n"); timeout.attach(&timer_interrupt,0.5); // llamamos la interrupcion del timeout cada 0.5 segundos pc.attach(&read_command, Serial::RxIrq); //llamamos la interrupcion serialmente pcBT.attach(&read_commandbt, Serial::RxIrq);//llamamos la interrupcion serialmente S0=1,S1=0; //calibracion de lectura del sensor S2=0,S3=0; init_servo(); while(1) { wait(1); pc.printf("modo joystick\n"); meas_r = analog_value.read(); // se lee la entrada analoga del joystick meas_v = meas_r * 3300; // se convierte la variable a 3.3v pc.printf("medida = %f = %.0f mV\n", meas_r, meas_v); //muestra en el monitor lectura del joystick if (meas_v < 1000) { pc.printf("adelante\n"); adelante(); } if (meas_v > 3000) { pc.printf("atras\n"); atras(); } } }
Funcion encargada de leer el color mediante el sensor, aqui se hace la operacion para restar los flancos y de esta manera se obtiene el valor en frecuencia que es necesaria para saber el color de la lectura.
include the mbed library with this snippet
unsigned int lectura() // lectura del sensor { tiempo.start(); while(leer) {} while(!leer) {} // inicia desde el inicio de cambio de flanco //pc.printf("sale"); while(leer) {} tiempo.reset(); inicio=tiempo.read_us(); while(!leer) {} final=tiempo.read_us(); resultado=(final-inicio); return resultado; }
En este apartado se da inicio a los servomotores ademas se inicia la comunicacion con el coolterm de manera que si los comandos enviados no cumplen los parametros, este devuelva un error para su correspondiente correcion. Ademas se hace la connversion de lalectura de manra que los servos se puedan mover en los grados correspondientes a la misma.
include the mbed library with this snippet
void init_servo() //inicializamos servomotores { myServo1.period_ms(20); // periodo de cada servo myServo2.period_ms(20); myServo3.period_ms(20); myServo4.period_ms(20); myServo5.period_ms(20); myServo6.period_ms(20); myServo7.period_ms(20); myServo8.period_ms(20); } int coord2us(float coord) { if(0 <= coord <= 180) return int(750+coord*1750/180);// cambiar de numero de entrada serial a grados return 750; } void read_command() { init_c=pc.getc(); if( init_c==0xFF) { read_cc=pc.getc(); nmotor=pc.getc(); grados=pc.getc(); endc=pc.getc(); if(endc==0xFD) { switch (read_cc) { case 0x01: moving(); break; case 0x02: grupomover(); break; default: pc.printf("error \nSe espera 0xFEF0 o 0xFFF0 \n"); break ; } } else pc.printf("Error de codigo de cierre \n"); } else pc.printf("Error de codigo de inicio. \n"); }
Funcion encargada de mover los servomotores mostrando el proceso en pantalla mediante CoolTerm.
include the mbed library with this snippet
void moving() { pc.printf("mueve\n"); mover_ser(nmotor,grados); // llama el void para mover servo con grados pc.printf("fin mueve\n"); }
Se definen los 8 servomotores y a cada uno se le asigna una variable. Se establecen los casos para el movimiento de cada servo.
include the mbed library with this snippet
void mover_ser(uint8_t nmotor, uint8_t grados) // definimos que leen los 8 servos y le asiganamos a cada variable un servo { int pulsea = coord2us(grados); switch (nmotor) { case 0x01: myServo1.pulsewidth_us(pulsea); break; // caso para cada servo case 0x02: myServo2.pulsewidth_us(pulsea); break; case 0x03: myServo3.pulsewidth_us(pulsea); break; case 0x04: myServo4.pulsewidth_us(pulsea); break; case 0x05: myServo5.pulsewidth_us(pulsea); break; case 0x06: myServo6.pulsewidth_us(pulsea); break; case 0x07: myServo7.pulsewidth_us(pulsea); break; case 0x08: myServo8.pulsewidth_us(pulsea); break; default: pc.printf("no hay mas motores error de comando\n"); break ; } }
Se hace el llamado a la interrupcion externa mediante el Timer y se establecen los movimientos para cada lectura de color mediante el sensor.
include the mbed library with this snippet
void timer_interrupt() //la respuesta de cada interrupcion externamente por timer { led = !led; S2=0,S3=0; rojo=lectura(); //pc.printf("rojo --%d\n",rojo); S2=1,S3=1; verde=lectura(); //pc.printf("verde --%d\n",verde); S2=0,S3=1; azul=lectura(); //pc.printf("azul --%d\n",azul); if (rojo>=100 and rojo <=400) { // lee el rojo------------ if (verde>=450 and verde <=700) { if (azul>=300 and azul <=600) { //POSICION ORIGINAL pc.printf("POSICION ORIGINAL --%d\n",rojo); myServo1.pulsewidth_us(1025); wait (0.5); myServo2.pulsewidth_us(1711); wait (0.5); myServo1.pulsewidth_us(1412); wait (0.5); myServo7.pulsewidth_us(1025); wait (0.5); myServo8.pulsewidth_us(1319); wait (0.5); myServo7.pulsewidth_us(1417); wait (0.5); myServo2.pulsewidth_us(1515); myServo8.pulsewidth_us(1515); wait (0.5); myServo3.pulsewidth_us(1221); wait (0.5); /* myServo2.pulsewidth_us(1800); wait(0.5); myServo8.pulsewidth_us(1600); wait(0.5); myServo4.pulsewidth_us(1400); wait(0.5); myServo6.pulsewidth_us(1600); wait(0.5); myServo1.pulsewidth_us(1200); wait(0.5); myServo3.pulsewidth_us(1200); wait(0.5); myServo5.pulsewidth_us(1200); wait(0.5); myServo7.pulsewidth_us(1200); wait(1);*/ pc.printf("rojo --%d\n",rojo); } } } if (rojo>=200 and rojo <=450) { // lee el verde -------------------------------------- if (verde>=200 and verde <=450) { if (azul>=200 and azul <=450) { // GIRO A LA DERECHA pc.printf("GIRO A LA DERECHA --%d\n",verde); myServo1.pulsewidth_us(1200); myServo3.pulsewidth_us(1200); myServo5.pulsewidth_us(1200); myServo7.pulsewidth_us(1200); wait(0.5); myServo1.pulsewidth_us(2000); wait(0.5); myServo2.pulsewidth_us(1000); wait(0.5); myServo1.pulsewidth_us(1200); wait(0.5); myServo7.pulsewidth_us(2000); wait(0.5); myServo8.pulsewidth_us(1000); wait(0.5); myServo7.pulsewidth_us(1200); wait(0.5); myServo5.pulsewidth_us(2000); wait(0.5); myServo6.pulsewidth_us(1000); wait(0.5); myServo5.pulsewidth_us(1200); wait(0.5); myServo3.pulsewidth_us(2000); wait(0.5); myServo4.pulsewidth_us(1000); wait(0.5); myServo3.pulsewidth_us(1200); wait(0.5); myServo2.pulsewidth_us(2200); myServo6.pulsewidth_us(2200); wait(0.5); myServo4.pulsewidth_us(2200); myServo8.pulsewidth_us(2200); wait(1); pc.printf("verde --%d\n",verde); } } } if (rojo>=400 and rojo <=800) { // lee el azul------------------------------------ if (verde>=200 and verde <=500) { if (azul>=1 and azul <=400) { // GIRO A LA IZQUIERDA pc.printf("GIRO A LA IZQUIERDA --%d\n",azul); myServo1.pulsewidth_us(1200); myServo3.pulsewidth_us(1200); myServo5.pulsewidth_us(1200); myServo7.pulsewidth_us(1200); wait(1); myServo1.pulsewidth_us(2000); wait(0.5); myServo2.pulsewidth_us(2200); wait(0.5); myServo1.pulsewidth_us(1200); wait(0.5); myServo7.pulsewidth_us(2000); wait(0.5); myServo8.pulsewidth_us(2200); wait(0.5); myServo7.pulsewidth_us(1200); wait(0.5); myServo5.pulsewidth_us(2000); wait(0.5); myServo6.pulsewidth_us(2200); wait(0.5); myServo5.pulsewidth_us(1200); wait(0.5); myServo3.pulsewidth_us(2000); wait(0.5); myServo4.pulsewidth_us(2200); wait(0.5); myServo3.pulsewidth_us(1200); wait(0.5); myServo2.pulsewidth_us(1200); myServo6.pulsewidth_us(1200); wait(0.5); myServo4.pulsewidth_us(1200); myServo8.pulsewidth_us(1200); wait(1); pc.printf("azul --%d\n",azul); } } } timeout.attach(&timer_interrupt, 0.5); // reiniciamos el timeout para la siguiente lectura }
Esta funcion se encarga de mover los servomotores por grupos "patas" dependiendo de cada caso.
include the mbed library with this snippet
void grupomover() { pc.printf("mueve grupo \n"); switch (nmotor) { case 0x01: { myServo1.pulsewidth_us(550); myServo2.pulsewidth_us(1800); pc.printf("primer caso\n"); break; } case 0x02: { myServo3.pulsewidth_us(550); myServo4.pulsewidth_us(1800); pc.printf("segundo caso \n"); break ; } case 0x03: { myServo5.pulsewidth_us(550); myServo6.pulsewidth_us(1800); pc.printf("tercer caso \n"); break; } case 0x04: { myServo7.pulsewidth_us(500); myServo8.pulsewidth_us(1800); pc.printf("cuarto caso \n"); break; default: pc.printf("solo 4 casos error en comando\n"); break ; } } pc.printf("fin mueve grupo\n"); }
Finalmente encontramos las dos funciones que permiten el moviemiento hacia adelante y atras respctivamente, como se puede observar esta configurada de manara que se logre dar sincronia entre los pasos para un moviemiento coordinado.
include the mbed library with this snippet
void adelante() { // PASO DERECHA-DELANTERA myServo8.pulsewidth_us(1000); wait(0.5); myServo7.pulsewidth_us(2000); wait(0.5); myServo8.pulsewidth_us(2000); wait(0.5); myServo7.pulsewidth_us(1200); wait(0.5); myServo8.pulsewidth_us(1000); wait(0.5); // PASO IZQUIERDA-TRASERA myServo4.pulsewidth_us(1600); wait(0.5); myServo3.pulsewidth_us(2000); wait(0.5); myServo4.pulsewidth_us(800); wait(0.5); myServo3.pulsewidth_us(1200); wait(0.5); myServo4.pulsewidth_us(1600); wait(0.5); // PASO IZQUIERDA-DELANTERA myServo2.pulsewidth_us(2400); wait(0.5); myServo1.pulsewidth_us(2000); wait(0.5); myServo2.pulsewidth_us(1200); wait(0.5); myServo1.pulsewidth_us(1200); wait(0.5); myServo2.pulsewidth_us(2400); wait(0.5); // PASO DERECHA-TRASERA myServo6.pulsewidth_us(1500); wait(0.5); myServo5.pulsewidth_us(2000); wait(0.5); myServo6.pulsewidth_us(2300); wait(0.5); myServo5.pulsewidth_us(1200); wait(0.5); myServo6.pulsewidth_us(1500); wait(0.5); } void atras() { // PASO DERECHA-DELANTERA myServo8.pulsewidth_us(1000); wait(0.5); myServo7.pulsewidth_us(1200); wait(0.5); myServo8.pulsewidth_us(2000); wait(0.5); myServo7.pulsewidth_us(2000); wait(0.5); myServo8.pulsewidth_us(1000); wait(0.5); myServo7.pulsewidth_us(1200); wait(0.5); // PASO IZQUIERDA-TRASERA myServo4.pulsewidth_us(1600); wait(0.5); myServo3.pulsewidth_us(1200); wait(0.5); myServo4.pulsewidth_us(800); wait(0.5); myServo3.pulsewidth_us(2000); wait(0.5); myServo4.pulsewidth_us(1600); wait(0.5); myServo3.pulsewidth_us(1200); wait(0.5); // PASO IZQUIERDA-DELANTERA myServo2.pulsewidth_us(2400); wait(0.5); myServo1.pulsewidth_us(1200); wait(0.5); myServo2.pulsewidth_us(1200); wait(0.5); myServo1.pulsewidth_us(2000); wait(0.5); myServo2.pulsewidth_us(2400); wait(0.5); myServo1.pulsewidth_us(1200); wait(0.5); // PASO DERECHA-TRASERA myServo6.pulsewidth_us(1500); wait(0.5); myServo5.pulsewidth_us(1200); wait(0.5); myServo6.pulsewidth_us(2300); wait(0.5); myServo5.pulsewidth_us(2000); wait(0.5); myServo6.pulsewidth_us(1500); wait(0.5); myServo5.pulsewidth_us(1200); wait(0.5); }
<<yestoc>>