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.
main.cpp
- Committer:
- Darstack
- Date:
- 2019-04-23
- Revision:
- 5:d165935ba818
- Parent:
- 4:7a06dce3de99
- Child:
- 6:35c069133c9a
File content as of revision 5:d165935ba818:
#include "mbed.h"
#include "scolor_TCS3200.h"
/* *****************************************************************************
Programa que solicita telemetria al sistema embebido, por medio del comando 0xFe
para preguntar por el color que detecta el sensor TCS3200
el sistema embebido recibe el inicio de trama FE y el número de comado: 01
| INITELE | CMD |
| 0xfe | 0x01 |
para enviar los comandos usar el programa Coolterm http://freeware.the-meiers.org/
@fabeltranm 2019
fbeltranm@ecci.edu.co
********************************************************************************
datasheet https://www.mouser.com/catalog/specsheets/TCS3200-E11.pdf
S0 Frequency scaling
S1 Frequency scaling
S2 Photo diode selection
S3 Photo diode selection
OutFreq Frequency
-----------------------------------
| ____________ ____________ |
----> | | | | | | ___ ___
Light | | Photodiode | | Current |--|---OUTPUT_FREQ | |___| |___
----> | | Array |---| to | |
| | | | Frequency | |
| |____________| |____________| |
| ^ ^ ^ ^ |
-------|--|-------------|--|-------
| | | |
S2 S3 S0 S1
SO | S1 | OUTPUT FREQUENCY SCALING | | S2 | S3 | PHOTODIODE TYPE |
0 | 0 | power down | | 0 | 0 | Red |
0 | 1 | 2% | | 0 | 1 | Blue |
1 | 0 | 20% | | 1 | 0 | Clear (no filter) |
1 | 1 | 100% | | 1 | 1 | Green |
******************************************************************************/
#define INITCMD 0xFF
#define DO 2000
#define RE 2500
#define MI 3000
#define FA 3500
/* ||Definicion de Puertos || */
Serial command(USBTX, USBRX);
// S0, S1, S2, S3, OUT
scolor_TCS3200 scolor( PA_9, PC_7, PB_6, PA_7, PA_6 ) ;
DigitalOut stepper_step ( PB_4 ) ;
DigitalOut steppeer_dir ( PB_5 ) ;
DigitalOut stepper_step2 ( PB_10 ) ;
DigitalOut steppeer_dir2 ( PA_8 ) ;
AnalogIn analog_value0 ( A0 ) ;
AnalogIn analog_value1 ( A1 ) ;
PwmOut mybuzzer( PB_9 ) ;
/* ||Definicion de Puertos || */
uint32_t VELOCITY = 400 ; // Tiempo en micro segundos
int16_t Lectura [ 2 ] = {} ;
double In [ 1 ] = {} ;
// definición de las funciones
void setup_uart ();
void leer_datos ();
void leer_color ();
void funcionesrobot ( uint8_t _Parametro, uint8_t _Comando );
int main() {
setup_uart();
while(1){
leer_datos();
funcionesrobot ( Lectura [ 1 ], Lectura [ 0 ] );
}
}
void setup_uart(){
command.baud(115200);
}
void leer_datos(){
while(command.getc()!= INITCMD) ;
uint8_t i ;
for ( i = 0 ; i < 2 ; i++){
Lectura [ i ] = command.getc();
//printf ( " %4d ", Lectura [ i ]);
}
}
void leer_color(){
mybuzzer.write(0);
long red = scolor.ReadRed();
long green = scolor.ReadGreen();
long blue = scolor.ReadBlue();
long clear = scolor.ReadClear();
long frqred;
long frqgreen;
long frqblue;
long frqclear;
int8_t sel_color = 0;
printf("RED: %5d GREEN: %5d BLUE: %5d CLEAR: %5d \n ", red, green, blue, clear);
frqred = ( ( 1.0/red )* 1000.0 );
frqgreen = ( ( 1.0/green ) * 1000.0);
frqblue = ( (1.0/blue) *1000.0 );
frqclear = ( (1.0/clear) *1000.0 );
printf("RED: %5d GREEN: %5d BLUE: %5d CLEAR: %5d \n ", frqred, frqgreen, frqblue,frqclear);
///////////////////////////////////////////////////////////////////////////////
/*||||||||||||||||Seleccionando los diferentes colores.||||||||||||||||||||||*/
/*||||||||||||||||||||||||||||||Color rojo|||||||||||||||||||||||||||||||||||*/
///////////////////////////////////////////////////////////////////////////////
if ( frqred >= 30.0 and frqred <= 500.0) {
if( frqgreen >= 0.0 and frqgreen <= 20.0 ) {
if ( frqblue >= 5.0 and frqblue <= 29.0 ) {
printf ( "tiende a rojo \n" );
mybuzzer.period_us(DO);
mybuzzer.write(0.8);
wait(5);
mybuzzer.write(0);
sel_color = 1;
}
}
}
////////////////////////////////////////////////////////////////////////////////
/*°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°Color verde°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°*/
////////////////////////////////////////////////////////////////////////////////
if ( frqgreen >= 11.0 and frqgreen <= 21.0) {
if( frqred >= 8.0 and frqred <= 20.0 ) {
if ( frqblue >= 10.0 and frqblue <= 26.0 ) {
printf ( "tiende a verde \n" );
mybuzzer.period_us(RE);
mybuzzer.write(0.5);
wait(5);
mybuzzer.write(0);
sel_color = 2;
}
}
}
////////////////////////////////////////////////////////////////////////////////
/*°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°Color azul°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°*/
///////////////////////////////////////////////////////////////////////////////
if ( frqblue >= 10.0 and frqblue <= 70.0) {
if( frqgreen >= 5.0 and frqgreen <= 26.0 ) {
if ( frqred >= 5.0 and frqred <= 20.0 ) {
printf ( "tiende a azul \n" );
mybuzzer.period_us(MI);
mybuzzer.write(1);
wait(5);
mybuzzer.write(0);
sel_color = 3;
}
}
}
/////////////////////////////////////////////////////////////////////////////////
/*°°°°°°°°°°°°°°°°°°°°°°°°°°°°°Color amarillo°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°*/
////////////////////////////////////////////////////////////////////////////////
if ( frqblue >= 0.0 and frqblue <= 30.0 ) {
if( frqgreen >= 20.0 and frqgreen <= 40.0) {
if ( frqred >= 20.0 and frqred <= 50.0 ) {
printf ( "tiende a amarillo \n" );
mybuzzer.period_us(FA);
mybuzzer.write(0.6);
wait(5);
mybuzzer.write(0);
sel_color = 4;
}
}
}
/////////////////////////////////////////////////////////////////////////////////
/*°°°°°°°°°°°°°°°°°°°°°°°°°°°°°Color no found°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°°*/
////////////////////////////////////////////////////////////////////////////////
switch ( sel_color ) {
case 0:
//int32_t enviar5 = RESPUESTA5 ;
//char txt5 [6] ;
//printf ( txt5 , "%02X" , enviar5 );
printf ( " FF00 \n " );
break;
case 1:
//int32_t enviar1 = RESPUESTA1 ;
//char txt1 [6] ;
printf ( "FE01 \n" );
sel_color = 0;
break;
case 2:
//int32_t enviar2 = RESPUESTA2 ;
//char txt2 [6] ;
printf ( "FE02 \n" ) ;
sel_color = 0;
break;
case 3:
//int32_t enviar3 = RESPUESTA3;
//char txt3 [6] ;
printf ( "FE03 \n" );
sel_color = 0;
break;
case 4:
//int32_t enviar4 = RESPUESTA4;
//char txt4 [6] ;
printf ( "FE04 \n" );
sel_color = 0;
break;
}
}
void funcionesrobot ( uint8_t _Parametro, uint8_t _Comando ){
/* °°Declaración de contadores°° */
uint8_t i ;
uint8_t j ;
switch ( _Comando ){
// Acciones que ejerce el robot
case 0 :
leer_color() ;
break ;
case 1 :
printf ( "Frecuencia: 2000 Tiempo: %d s \n" , _Parametro ) ;
mybuzzer.period_us ( DO ) ;
mybuzzer.write ( 0.8 ) ;
wait( _Parametro ) ;
mybuzzer.write ( 0 ) ;
break ;
case 2 :
printf ( "Frecuencia: 2500 Tiempo: %d s \n" , _Parametro ) ;
mybuzzer.period_us ( RE ) ;
mybuzzer.write ( 0.8 ) ;
wait ( _Parametro ) ;
mybuzzer.write ( 0 ) ;
break ;
case 3 :
printf ( " Frecuencia: 3000 " ); printf ( " Tiempo: %d s \n " , _Parametro ) ;
mybuzzer.period_us ( MI ) ;
mybuzzer.write ( 0.8 ) ;
wait( _Parametro ) ;
mybuzzer.write ( 0 ) ;
break ;
case 4:
printf ( "Frecuencia: 3500 Tiempo: %d s \n" , _Parametro ) ;
mybuzzer.period_us ( FA );
mybuzzer.write ( 0.8 );
wait ( 5 );
mybuzzer.write ( 0 );
break ;
case 5 :
steppeer_dir = 1 ;
steppeer_dir2 = 0 ;
wait_us ( 1 );
for ( j = 1 ; j <= _Parametro ; j++){
for ( i= 0 ; i <= 200 ; i++ ){
stepper_step = 1 ;
stepper_step2 = 1;
wait_us( VELOCITY );
stepper_step = 0;
stepper_step2 = 0;
wait_us ( VELOCITY );
}
}
break;
case 6 :
steppeer_dir = 0;
steppeer_dir2 = 1;
wait_us ( 1 );
for ( j = 1 ; j <= _Parametro ; j++){
for ( i= 0 ; i <= 200 ; i++ ){
stepper_step = 1 ;
stepper_step2 = 1 ;
wait_us( VELOCITY ) ;
stepper_step = 0 ;
stepper_step2 = 0 ;
wait_us ( VELOCITY ) ;
}
}
break;
case 7:
steppeer_dir = 0;
wait_us ( 1 );
for ( j = 1 ; j <= _Parametro ; j++){
for ( i= 0 ; i <= 50 ; i++ ){
stepper_step = 1 ;
//stepper_step2 = 1 ;
wait_us(VELOCITY) ;
stepper_step = 0 ;
//stepper_step2 = 0 ;
wait_us(VELOCITY) ;
}
}
break;
case 8 :
steppeer_dir2 = 1;
wait_us ( 1 );
for ( j = 1 ; j <= _Parametro ; j++){
for ( i= 0 ; i <= 50 ; i++ ){
//stepper_step = 1 ;
stepper_step2 = 1 ;
wait_us( VELOCITY ) ;
//stepper_step = 0 ;
stepper_step2 = 0 ;
wait_us ( VELOCITY ) ;
}
}
break;
case 9 :
switch ( _Parametro ){
case 1:
VELOCITY = 400 ;
break;
case 2:
VELOCITY = 2500 ;
break;
case 3:
VELOCITY = 5000 ;
break;
}
break;
case 10:
int8_t Exit = 0 ;
if ( _Parametro == 1){
while ( !Exit ){
In [ 0 ] = analog_value0.read(); // Converts and read the analog input value (value from 0.0 to 1.0)
//printf(" X = %.04f \n", In[0]);
In [ 1 ] = analog_value1.read(); // Converts and read the analog input value (value from 0.0 to 1.0)
//printf(" X = %.04f \n", In[0]);
if ( In [ 0 ] > 0.5 ){
steppeer_dir = 1;
wait_us( 1 );
for ( i= 0 ; i <= 50 ; i++ ){
stepper_step = 1 ;
//stepper_step2 = 1 ;
wait_us( VELOCITY ) ;
stepper_step = 0 ;
//stepper_step2 = 0 ;
wait_us( VELOCITY ) ;
}
}
if ( In[ 0 ] < 0.5 ){
steppeer_dir2 = 1;
wait_us( 1 );
for ( i= 0 ; i <= 50 ; i++ ){
//stepper_step = 1 ;
stepper_step2 = 1 ;
wait_us( VELOCITY ) ;
//stepper_step = 0 ;
stepper_step2 = 0 ;
wait_us( VELOCITY ) ;
}
}
if (In [ 1 ] > 0.5 ){
steppeer_dir = 1 ;
steppeer_dir2 = 0 ;
wait_us( 1 );
for ( i= 0 ; i <= 50 ; i++ ){
stepper_step = 1 ;
stepper_step2 = 1 ;
wait_us( VELOCITY ) ;
stepper_step = 0 ;
stepper_step2 = 0 ;
wait_us( VELOCITY ) ;
}
}
if ( In [ 1 ] < 0.5 ){
steppeer_dir = 0 ;
steppeer_dir2 = 1 ;
wait_us( 1 );
for ( i= 0 ; i <= 50 ; i++ ){
stepper_step = 1 ;
stepper_step2 = 1 ;
wait_us( VELOCITY ) ;
stepper_step = 0 ;
stepper_step2 = 0 ;
wait_us ( VELOCITY ) ;
}
}
wait ( 1 );
if ( command.readable () == 1 ){
leer_datos();
if ( Lectura [ 1 ] == 02 ){
Exit = 1 ;
}
}
}
}
break;
}
}