Robot's source code

Dependencies:   mbed

main.cpp

Committer:
Jagang
Date:
2015-03-16
Revision:
39:09c04fd42c94
Parent:
38:28f476eacde4
Child:
40:83ce8d1072ef

File content as of revision 39:09c04fd42c94:

#include "mbed.h"

#include "defines.h"

#include "QEI.h"
#include "Map.h"
#include "AX12.h"

#include "Asserv.h"
#include "Motor.h"
/*----------------------------------------------------------------------------------------------*/
/*Serial*/    
Serial logger(OUT_TX, OUT_RX); // tx, rx
/*----------------------------------------------------------------------------------------------*/

/* --- Initialisation de la liste des obstable --- */
int Obstacle::lastId = 0;

int main()
{
    logger.printf("Initialisation...\r\n");
    //mbed
    /*
    PwmOut pw1(p22);
    DigitalOut dir1(p21);
    PwmOut pw2(p24);
    DigitalOut dir2(p23);
    */
    
    //mbuino
    /*
    PwmOut pw1(P0_17);
    DigitalOut dir1(P0_18);
    PwmOut pw2(P0_23);
    DigitalOut dir2(P0_19);
    */
    /*
    //nucleo
    PwmOut pw1(PB_8);
    DigitalOut dir1(D12);
    PwmOut pw2(PB_9);
    DigitalOut dir2(D13);
    */
    //nucleo
    
    PwmOut pw1(PB_13);
    DigitalOut dir1(PC_9);
    PwmOut pw2(PB_14);
    DigitalOut dir2(PB_8);
    
        
    Motor motorR(&pw1,&dir1);
    Motor motorL(&pw2,&dir2);    
    logger.printf("mise a jour des pwm.\r\n");
    Timer t;
    
    AX12 test(PA_9,NC,0x05,250000);
    AnalogIn ain0(PA_0);
    AnalogIn ain1(PA_1);
    AnalogIn ain2(PA_4);
    AnalogIn ain3(PB_0);
    AnalogIn ain4(PC_1);
    
    /*----------------------------------------------------------------------------------------------*/
    /*Odometry*/
    QEI qei_left(PB_3,PA_10,NC,1024*4,QEI::X4_ENCODING);
    QEI qei_right(PB_4,PB_5,NC,1024*4,QEI::X4_ENCODING);
    Odometry odometry(&qei_left,&qei_right,63/2.,63/2.,280);
    DigitalOut led(LED1);
    
    test.SetMode(0); // Position
    
    char dataOff[] = {0};
    char dataOn[] = {1};
    /*while(1)
    {
        logger.printf("0: %f\r\n",ain0);
        logger.printf("1: %f\r\n",ain1);
        logger.printf("2: %f\r\n",ain2);
        logger.printf("3: %f\r\n",ain3);
        logger.printf("4: %f\r\n\r\n",ain4);
        led = !led;
        wait(0.5);
        test.write(0x05,0x19,1,dataOff);
        wait(0.5);
        test.write(0x05,0x19,1,dataOn);
    }*/
    bool testOdo = true;
    
    
    Asserv<float> instanceAsserv(&odometry);
    
    /*----------------------------------------------------------------------------------------------*/
    instanceAsserv.setGoal( (float)10,(float)0, (float)PI/2);
    
    while(1)
    {       
        //Asservissement :
        t.start();         
        instanceAsserv.update((float)t.read());
                        
        Mat<float> X( instanceAsserv.getX() );
        float phi_r = instanceAsserv.getPhiR();
        float phi_l = instanceAsserv.getPhiL();
        float phi_max = instanceAsserv.getPhiMax();
        logger.printf(" x : %f ;\t y : %f ;\t theta : %f ;\t phiD = %f ;\t phiG = %f \n\r",X.get(1,1),X.get(2,1),X.get(3,1), X.get(4,1), X.get(5,1) );
        //pcs.printf("%f : %f : %f\n", (double)odometry.getX()*100,(double)odometry.getY()*100,(double)odometry.getTheta()*180/3.14);                                            
        //blue.printf("State : \n\r");
        //(instanceAsserv.getX()).afficherMblue();
        //blue.printf("Odometry : \n\r");
        //z.afficherMblue();       
                                 
        //Mise a jour des moteurs :
        if(!testOdo)
        {
            motorR.update((float)phi_r/phi_max);        
            motorL.update((float)phi_l/phi_max);
        }            
        logger.printf("\n\n----------------- Commandes moteurs : mises a jour. ------------------ \n");
                
        //Timer Handling :
        t.stop();
        logger.printf("%f s ecoulee.\n\r", t.read());
        t.reset();
        t.start();                
    }
        
    
    while(1)
    {
        //setPWM(&pw1,0.0);
        //setPWM(&pw2,0.0);
        pw1.write(0.0);
        pw2.write(0.0);
        led = !led;
        wait(1);
    }
}