Robot

Dependencies:   Servo mbed wav_header wave_player TextLCD RemoteIR

main.cpp

Committer:
dan_cuspi
Date:
2014-06-27
Revision:
0:39f6dbb94f99

File content as of revision 0:39f6dbb94f99:

#include "mbed.h"
#include "Servo.h"
#include  "Speaker.h"
#include "ReceiverIR.h"
#define TEST_LOOP_BACK  0
#define DEBOUNCEDELAY 500
//pines libres p15,p16,p17,p19,p30, "p26 socket IF-r" 
Serial Bt(p9,p10);
Serial Wf(p28,p27);
Serial Pc(USBTX, USBRX);
ReceiverIR IR_Receiver(p15);
PwmOut IR_Transmitter(p26); 
DigitalOut Lights(p19);
DigitalOut Motor2A(p7);
DigitalOut Motor2B(p6);
DigitalOut Motor4A(p13);
DigitalOut Motor4B(p14);
DigitalOut Motor3A(p8);
DigitalOut Motor3B(p5);
DigitalOut Motor1A(p12);
DigitalOut Motor1B(p11);
Servo myservo1(p21);
Servo myservo2(p22);
Servo myservo3(p23);
Servo myservo4(p24);
Speaker mySpeaker(p18);
char K,F;
int u,l=0;
float max = 0.0006;
float min = -0.0005;
float position1 = 0.0,position2 = 0.0;
    int receive(RemoteIR::Format *format, uint8_t *buf, int bufsiz, int timeout = 100)
 {
    int cnt = 0;
    while (IR_Receiver.getState() != ReceiverIR::Received) {cnt++;if (timeout < cnt) {return -1;}}
    return IR_Receiver.getData(format, buf, bufsiz * 8);
 }
/////////IR Transmitter
short Power_On_Off[] = {  2460, 543, 1290, 514, 692, 507, 1289, 514, 692, 507, 1290, 514,  691, 507, 690, 508, 1289, 516, 717, 481,690, 508, 689,  508, 692, 25634,};

short Volume_Up[] =    {  2500,440,700,480,1280,460,680,480,700,460,1300,460,700,460,700,460,1280,460,700,480,700,460,680,480,700,25620,}; //Volume Up

short Volume_Down[]=   {  2480,480, 1260,500, 1260,480, 680,500, 660,500, 1240,500, 680,480, 680,460, 1280,500, 660,500, 680,480, 680,480, 680,25040,}; 

short One_B[]=         {  2480,460,700,460,700,460,720,440,720,460,700,460,700,460,720,440,1320,440,700,460,700,460,700,460,700,26800,};
                
short Two_B[]=         {  2500,440,1300,460,680,480,680,480,680,480,680,480,680,480,700,480,1280,460,680,480,680,480,700,460,700,26220,};
               
short Three_B[]=       {  2500,440,680,480,1300,440,700,480,680,480,680,480,680,480,680,500,1280,460,680,480,680,480,680,480,680,26240,};
                 
short Four_B[]=        {  2520,420,1300,460,1300,440,700,480,680,480,680,480,680,480,680,480,1300,460,680,480,680,480,680,480,680,25640,};
                
short Five_B[]=        {  2500,460,680,480,680,480,1300,440,680,500,680,480,680,480,680,480,1300,440,700,480,680,480,680,480,680,26220,};
                                          
void PowerOff()
{
    IR_Transmitter.period_us( 26 );int iCountHighLow = sizeof( Power_On_Off ) / sizeof( Power_On_Off[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) ); wait_us( Power_On_Off[iIndexHighLow] );}   
}
void VolumeUp()
{
    IR_Transmitter.period_us( 26 );int iCountHighLow = sizeof( Volume_Up ) / sizeof( Volume_Up[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( Volume_Up[iIndexHighLow] );}
}
void VolumeDown()
{
    IR_Transmitter.period_us( 26 );int iCountHighLow = sizeof( Volume_Down ) / sizeof( Volume_Down[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( Volume_Down[iIndexHighLow] );}
}
void One()
{
     IR_Transmitter.period_us( 26 ); int iCountHighLow = sizeof( One_B ) / sizeof( One_B[0] );
     for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( One_B[iIndexHighLow] );}
    
}
void Two()
{
    IR_Transmitter.period_us( 26 ); int iCountHighLow = sizeof( Two_B ) / sizeof( Two_B[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( Two_B[iIndexHighLow] );}
}
void Three()
{
    IR_Transmitter.period_us( 26 );int iCountHighLow = sizeof( Three_B ) / sizeof( Three_B[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( Three_B[iIndexHighLow] );}
}
void Four()
{
    IR_Transmitter.period_us( 26 );int iCountHighLow = sizeof( Four_B ) / sizeof( Four_B[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( Four_B[iIndexHighLow] );}
}  
void Five()
{
    IR_Transmitter.period_us( 26 );int iCountHighLow = sizeof( Five_B ) / sizeof( Five_B[0] );
    for( int iIndexHighLow = 0; iIndexHighLow < iCountHighLow; iIndexHighLow++ ) {IR_Transmitter.write( 0.5 * (1 - (iIndexHighLow % 2)) );wait_us( Five_B[iIndexHighLow] );}
}

int main() {
 Timer timer;
 timer.start();
 int D1A,D1B,D2A,D2B,D3A,D3B,D4A,D4B,x4,y4,x2,y2;
 int iMilliSec_prev = timer.read_ms();
     myservo1.calibrate_max(max, 90); myservo1.calibrate_min(min, 0);
     myservo2.calibrate_max(max, 90); myservo2.calibrate_min(min, 0);
     myservo3.calibrate_max(max, 90); myservo3.calibrate_min(min, 0);
     myservo4.calibrate_max(max, 90); myservo4.calibrate_min(min, 0);
     myservo1 =0.95;myservo2 = 0.0; myservo3= 0.90; myservo4 =0.0;D1A=1,D1B=0,D2A=1,D2B=0,D3A=1,D3B=0,D4A=1,D4B=0 ;x2=D2A; y2=D2B; x4=D4A; y4=D4B;
  while(1) {
    Motor1A=0; Motor1B=0; Motor2A=0; Motor2B=0;  Motor3A=0; Motor3B=0; Motor4A=0; Motor4B=0; // Motor Stop
    if (Bt.readable()){K=Bt.getc();}
    if (Wf.readable()){K=Wf.getc();}
    if (Pc.readable()){K=Pc.getc();}
///////////   Infrared Transmitter   //////////////    
    if (K=='1'){ One();        IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='2'){ Two();        IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='3'){ Three();      IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='4'){ Four();       IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='5'){ Five();       IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='p'){ PowerOff();   IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='u'){ VolumeUp();   IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
    if (K=='d'){ VolumeDown(); IR_Transmitter=0;IR_Transmitter.period(0.020);K=0;}
///////////   Servo   //////////////     
    if (K=='7'){ myservo1 =0.0;  myservo2 = .90;  myservo3= 0.0; myservo4 =.90; D1A=1,D1B=0,D2A=0,D2B=1,D3A=1,D3B=0,D4A=0,D4B=1; x2=D2B; y2=D2A; x4=D4B; y4=D4A;}
    if (K=='8'){ myservo1 =0.5;  myservo2 = 0.5 ; myservo3= 0.5; myservo4 =0.5;}
    if (K=='9'){ myservo1 =.90;  myservo2 = 0.0;  myservo3= .90; myservo4 =0; D1A=1,D1B=0,D2A=1,D2B=0,D3A=1,D3B=0,D4A=1,D4B=0 ;x2=D2A; y2=D2B; x4=D4A; y4=D4B;}
    if (K=='6'){ myservo1 =0; myservo2 = 0; myservo3= 0; myservo4 =0;K=0;}
///////////   Lights  //////////////     
    if (K=='l'){ if(l==1){Lights=0;l=0;K=0;}else {Lights=1;l=1;K=0;}}
///////////   Wifly Config   //////////////     
    if (K=='c'){ while(1){while(Bt.readable())Wf.putc(Bt.getc());while(Wf.readable())Bt.putc(Wf.getc());}}
///////////   Claxon   ////////////// 
    if (K=='k'){  mySpeaker.PlayNote(969.0, 0.5, 1.0);mySpeaker.PlayNote(800.0, 0.5, 1.0);K=0;}
///////////   Motores   ////////////// 
    if (K==0x41||K=='t'){Motor1A=D1A; Motor1B=D1B; Motor2A=D2A; Motor2B=D2B;  Motor3A=D3A; Motor3B=D3B; Motor4A=D4A; Motor4B=D4B; wait(0.1); K=0;} //forward
    if (K==0x42||K=='g'){Motor1A=D1B; Motor1B=D1A; Motor2A=D2B; Motor2B=D2A;  Motor3A=D3B; Motor3B=D3A; Motor4A=D4B; Motor4B=D4A; wait(0.1); K=0;} //backward
    if (K==0x43||K=='h'){Motor1A=D1B; Motor1B=D1A; Motor3A=D3A; Motor3B=D3B; Motor2A=x2; Motor2B=y2;   Motor4A=y4; Motor4B=x4; wait(0.016);  K=0;} //right
    if (K==0x44||K=='f'){Motor1A=D1A; Motor1B=D1B; Motor3A=D3B; Motor3B=D3A; Motor2A=y2; Motor2B=x2;   Motor4A=x4; Motor4B=y4; wait(0.016);  K=0;} //left
   
    Wf.printf("\n\r");
   Pc.printf("%c",K);
///////////   Infrared Receiver   ////////////// 
     uint8_t buf1[32];
     int bitlength1; 
     RemoteIR::Format format;memset(buf1, 0x00, sizeof(buf1));bitlength1 = receive(&format, buf1, sizeof(buf1));
     if (bitlength1 < 0) {continue;}
     for (int i = 0; i <4; i++) 
     {for (int i = 0; i <1; i++) 
             { u=buf1[i];
               if(u==244){K=0x41;} // Forward
               if(u==245){K=0x42;}// Backward
               if(u==179){K=0x43;}// Right
               if(u==180){K=0x44;}//Left
               if(u==229){K=0x0D;}//Horn
               if(u==133){K='6';}// Servos Position 0 movement
               if(u==134){K='7';}// Servos left movement
               if(u==135){K='8';}// Servos Star movement
               if(u==136){K='9';}// Servos Right movement
               if(u==149){K='o';}// Robot on
               if(u==224){K='l';}// Lights
               if(u==139){K='p';}// Tv on/off
             }
      }
       Bt.printf("%i",u); Bt.printf("\n\r");
    }
}