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.
Dependencies: mbed QEI_hw NVIC_set_all_priorities SoftPWM
Revision 2:e72b06f87c8b, committed 2020-07-09
- Comitter:
- exarkun
- Date:
- Thu Jul 09 08:30:19 2020 +0000
- Parent:
- 1:2fe82be93e80
- Commit message:
- driver motor with lcd control nextion nx8048t050
Changed in this revision
| main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Fri Oct 18 13:14:40 2019 +0000
+++ b/main.cpp Thu Jul 09 08:30:19 2020 +0000
@@ -11,6 +11,19 @@
#include "timer.hpp"
#include "NextionLCD.h"
+char c ;//commande moteur
+
+//declaration des leds visuelle utiliser pour mesurer le temps des taches
+DigitalOut myled1(LED1);
+DigitalOut myled3(LED3);
+
+// Define buttons
+DigitalIn input4(p19);
+DigitalIn input3(p18);
+DigitalIn input2(p17);
+//DigitalIn input1(p16);
+InterruptIn input1(p16);
+
//declaration des variables afficheur
#define BLACK 0
@@ -96,11 +109,11 @@
DigitalOut sens_rotation_moteur1(p13);
PwmOut PWM1(p21);
-
+
SPISlave spi1(p5, p6, p7, p8); // mosi, miso, sclk, ssel
AnalogIn Ain(p20);
-
+
// définition des timers.
//Timer timer1;
Timer timer2;
@@ -116,7 +129,8 @@
DigitalOut led1(LED1);
DigitalOut led3(LED3);
-char c ;
+bool home_done_tag;//tag pour savoir si la home es faite
+
int t ;
int x=0 ;
@@ -128,7 +142,10 @@
//position codeur en pulses 2000pulses/rotation
int position_actuelle;//position du codeur
int position_actuelle_n1;//position du codeur a n-1
-
+int position_home;
+int position_sortie_capteur_de_home;
+int position_initial;//position a l'alumage de la machine
+
//données mecanique & moteur
float J=3.375*1e-5;//0.005;//inertie en kg.m²
float K=0.05;//2;//constante de couple N.m/v
@@ -175,7 +192,7 @@
//variable ADC
float ADCdata;
float imax=1.8;
-
+int result;
//declaration des differantes taches
void task1_switch(void);
void task2_switch(void);
@@ -191,15 +208,11 @@
Ticker time_up2; //definition du Ticker, avec le nom “time_up2”
Ticker time_up3; //definition du Ticker, avec le nom “time_up3”
Ticker time_up4; //definition du Ticker, avec le nom “time_up4”
-Ticker time_up5; //definition du Ticker, avec le nom_up5”
-Ticker time_up6; //definition du Ticker, avec le nom_up6”
+Ticker time_up5; //definition du Ticker, avec le nom “time_up5”
+Ticker time_up6; //definition du Ticker, avec le nom “time_up6”
Ticker time_up7; //definition du Ticker, avec le nom “time_up7”
Ticker time_up8; //definition du Ticker, avec le nom “time_up8”
-//declaration des leds visuelle utiliser pour mesurer le temps des taches
-DigitalOut myled1(LED1);
-DigitalOut myled3(LED3);
-
//declaration des variables afficheur
char mRxMsg[40];
int mRxIdx;
@@ -264,8 +277,7 @@
if(mRxMsg[0] == 0x71) //sliders data return
{
- val_temp=mRxMsg[1];
-
+ val_temp=mRxMsg[1];
}
}
}
@@ -417,13 +429,13 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//FLY READY switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x19)&&(mRxMsg[3] == 0x01))
- { myled3=1;
+ {
//keyboard.printf("r");//flight ready
}//uniquement le bouton allumeras la led 1 en release ---------------SY
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//space break switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x18)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("x");//spacebreak
//wait(0.5);
while (mRxMsg[3]!=0x00)
@@ -436,14 +448,14 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//LANDING switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x17)&&(mRxMsg[3] == 0x01))
- {myled3=1;
+ {
//keyboard.printf("n");//landing mode
}//uniquement le bouton home allumeras la led 3 en release ---------------SY
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//strafe up switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x13)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf(" ");//strafe up
//wait(0.5);
while (mRxMsg[3]!=0x00)
@@ -458,7 +470,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//strafe down switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x14)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.keyCode(KEY_CTRL);//strafe down
//wait(0.5);
while (mRxMsg[3]!=0x00)
@@ -473,7 +485,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//forward switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x02)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("w");//vers l'avant
//wait(0.5);
@@ -489,7 +501,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//rearward switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x01)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("s");//vers l arriere
//wait(0.5);
@@ -505,7 +517,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//Right switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x03)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("d");//vers la droite
//wait(0.5);
@@ -521,7 +533,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//Left switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x04)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("a");//vers la gauche
//wait(0.5);
@@ -538,7 +550,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//roll left switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1a)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("e");//rouli gauche
//wait(0.5);
@@ -554,7 +566,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//roll Right switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x05)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("q");//rouli droit
//wait(0.5);
@@ -571,7 +583,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//tangage vers le bas switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1b)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("");//touche non affecté
//wait(0.5);
@@ -588,7 +600,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//tangage vers le haut switch
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1b)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("");//touche non affecté la touche non connue
//wait(0.5);
@@ -607,7 +619,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//quantum drive
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1f)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("b");//touche non affecté la touche non connue
//wait(0.5);
@@ -624,7 +636,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//Speed M
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1c)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("c");//touche non affecté la touche non connue
//wait(0.5);
@@ -641,7 +653,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//Speed M
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1c)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.printf("b");//touche non affecté la touche non connue
//wait(0.5);
@@ -658,7 +670,7 @@
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//Afterburner
if((mRxMsg[0] == 0x65)&&(mRxMsg[1] == 0x00)&&(mRxMsg[2] == 0x1c)&&(mRxMsg[3] == 0x01))//press
- {myled3=1;
+ {
//keyboard.keyCode(KEY_SHIFT);
//wait(0.5);
@@ -677,7 +689,7 @@
//ici il faut completer le code pour pouvoir detecter le bon bouton en press event et release event
//example le bouton start press event 65 01 01 01 ff ff ff et en release event 65 01 01 00 ff ff ff . rem:code touche repris par simulation avec le soft nextion
-myled3=0;
+
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -899,8 +911,9 @@
// char text[31];
// snprintf(text, 31, "%s", ppp_text);
// pc.printf(text);
-device.printf("n0.val=%d%c%c%c", (LPC_QEI->QEIPOS)/*position_actuelle*/, 0xff, 0xff, 0xff);// affiche la valeur de position sur l afficheur nextion
-
+
+//device.printf("add 1,0,%d%c%c%c", (position_actuelle/1000)+16500, 0xff, 0xff, 0xff);// pour la fonction waveform add id1,chanel0,position actu
+device.printf("add 1,0,%d%c%c%c", (position_actuelle/1000)+16500, 0xff, 0xff, 0xff);
};
////////////////////////////////////////
@@ -935,9 +948,13 @@
//device.printf("$%d;", position_actuelle); //utiliser avec logicielle serial port ploter
//pc.printf("0x%04x\n", valueFromMaster);
//pc.printf("%04x", valueFromMaster);
-device.printf("add 1,0,%d%c%c%c", (position_actuelle/500), 0xff, 0xff, 0xff);// pour la fonction waveform add id1,chanel0,position actu
-//device.printf("add 1,0,%d%c%c%c", (ADCdata)/10, 0xff, 0xff, 0xff);// pour la fonction waveform add id1,chanel0,position actu
+
+//device.printf("add 1,0,%d%c%c%c", (position_actuelle/500), 0xff, 0xff, 0xff);// pour la fonction waveform add id1,chanel0,position actu
+//pc.printf("%1.3f \n\r",ADCdata);
+pc.printf("add 1,0,%d%c%c%c", (position_actuelle/1000)+16000, 0xff, 0xff, 0xff);
+//pc.printf("n4.val=%d %c%c%c", position_actuelle, 0xff, 0xff, 0xff);
+
}
//////////////////////////////////////////////////////////////////////////////
@@ -971,39 +988,44 @@
/////////////////////////////////////////////////////////////////////////
// TASKS6 lecture de l'image courant moteur //
/////////////////////////////////////////////////////////////////////////
+int z=0;
+float result_conver_AD;
void task6_switch()
-{
- // ADCdata=Ain*3.3; //lecture de l'image du courant
+{
+ if (z!=9)
+ {
+ ADCdata=ADCdata+Ain; //sum 10 samples
+ z++ ;
+
+ }
-for (int z=0;z<=9;z++)
-{
- ADCdata=ADCdata+Ain*3.3; //sum 10 samples
-}
-//ADCdata=ADCdata/10; //divide by 10
-device.printf("n0.val=%d%c%c%c", ADCdata, 0xff, 0xff, 0xff);// affiche la valeur de position sur l afficheur nextion
-//ADCdata=Ain.read_u16();
-if(ADCdata>=imax)//si l'image du courant egale a 0.5v je coupe le moteur .
-{
- while(1){
- PWM1.write(0);//mise du signal pwm a zero.
-// pc.printf("%1.3f",ADCdata);
-// pc.printf("V\n\r");
-// pc.printf("current overload \n\r");
-
+ if (z==9)
+ {
+ ADCdata=ADCdata/10; //divide by 10
+ z=0 ;
+ }
+ //device.printf("n0.val=%d%c%c%c", ADCdata, 0xff, 0xff, 0xff);// affiche la valeur de position sur l afficheur nextion
+ //ADCdata=Ain.read_u16();
+
+ if(ADCdata>=imax)//si l'image du courant egale a 0.5v je coupe le moteur .
+ {
+ c='d';//arret moteur
+ device.printf("g0.txt=\"over i\"%c%c%c", 0xff, 0xff, 0xff);//affiche
//attendre que le manipulateur appuis sur le bouton restart a coder .
//veriffier que les plaques sont bien en position .
- //faire une home ou continuer la trajectoire .a voir !!!!
- }
-}
+ //faire une home ou continuer la trajectoire .a voir !!!!
+ }
// ici code de la tache 6
-
+//-----------------------------------------------------------------attention manque le reset de la valeur ADCdata utilise if ......
}
////////////////////////////////////////
// TASKS7 //
////////////////////////////////////////
+//lecture d'un message valide pour traitement afficheur
+
int ReadSerialMsg(char *Msg)
{
if(device.readable())
@@ -1055,7 +1077,7 @@
/*
if(device.readable())
{
- myled1=1;
+
charac = device.getc();
mRxMsg[mRxIdx] = charac;
mRxIdx++;
@@ -1084,58 +1106,79 @@
////////////////////////////////////////
// TASKS8 //
////////////////////////////////////////
+bool page_detect_ok;
void task8_switch()//detection code page
{
- if((mRxMsg[0] == 0x66))
- {
- switch ( mRxMsg[1])
- {
- case 0x00:
- page0();//ici la page0 es traité ----------- code de la page : 66 00 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
+ if(page_detect_ok!=1)
+ {
+ if((mRxMsg[0] == 0x66))
+ {
+ page_detect_ok!=1;
+ switch ( mRxMsg[1])
+ {
+ case 0x00:
+ page0();//ici la page0 es traité ----------- code de la page : 66 00 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
- case 0x01:
- page1();//ici la page0 es traité ----------- code de la page : 66 01 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
+ case 0x01:
+ page1();//ici la page0 es traité ----------- code de la page : 66 01 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
+
+ case 0x02:
+ page2();//ici la page0 es traité ----------- code de la page : 66 02 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
- case 0x02:
- page2();//ici la page0 es traité ----------- code de la page : 66 02 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
+ case 0x03:
+ page3();//ici la page0 es traité ----------- code de la page : 66 03 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
- case 0x03:
- page3();//ici la page0 es traité ----------- code de la page : 66 03 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
+ case 0x04:
+ page4();//ici la page0 es traité ----------- code de la page : 66 04 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
- case 0x04:
- page4();//ici la page0 es traité ----------- code de la page : 66 04 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
-
- case 0x05:
- page5();//ici la page0 es traité ----------- code de la page : 66 05 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
+ case 0x05:
+ page5();//ici la page0 es traité ----------- code de la page : 66 05 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
+
+ case 0x06:
+ page6();//ici la page6 es traité ----------- code de la page : 66 06 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ break;
- case 0x06:
- page6();//ici la page6 es traité ----------- code de la page : 66 06 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- break;
+ case 0x07:
+ page7();//ici la page7 es traité ----------- code de la page : 66 07 ff ff ff
+ mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
+ //memset(mRxMsg, 0, 5);
+ break;
+
+ }
+ }
+ }
+// ici code de la tache 8
+}
- case 0x07:
- page7();//ici la page7 es traité ----------- code de la page : 66 07 ff ff ff
- mRxMsg[0] = 0x00;mRxMsg[1] = 0x00;mRxMsg[2] = 0x00;mRxMsg[3] = 0x00;mRxMsg[4] = 0x00;
- //memset(mRxMsg, 0, 5);
- break;
-
- }
-
-// ici code de la tache 8
- }
+//fonction pour faire la home
+void do_the_Home()
+{
+ myled1=1;
+ c='f'; //mouvement sortie du capteur
+}
+
+void do_the_Home1()
+{
+ position_sortie_capteur_de_home=(LPC_QEI->QEIPOS);
+ myled1=0;
+ c='d';//arret moteur en 1ms
+ position_home =position_initial-position_sortie_capteur_de_home;
+ home_done_tag=1;
+ device.printf("g0.txt=\"Home done\"%c%c%c", 0xff, 0xff, 0xff);//affiche
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -1158,7 +1201,7 @@
//initialisation de la com rs232
device.baud(9600);//rs232 28800 baud
- device.printf("serial rs232 ok \n");
+ //device.printf("serial rs232 ok \n");
//calculs de tau ,Kv,Kp
tau=(J*R)/K;
@@ -1174,31 +1217,37 @@
//initialisation du spi
spi1.format(16,3); // Setup: bit data, high steady state clock, 2nd edge capture
spi1.frequency(1000000); // 1MHz
-
+
//lancement des tasks
time_up1.attach(&task1_switch, 0.0005);//"calcule de l'asservissement" initialisation du ticker a 2Khz "500us".
time_up2.attach(&task2_switch, 0.034);//"retour d'information position.
time_up3.attach(&task3_switch, 0.0005);//"generation trajectoire" initialisation du ticker a 2khz "500us".
- //time_up4.attach(&task4_switch, 0.0005);//"retour d'information position par rs232"initialisation du ticker a 100hz "10ms".
+ time_up4.attach(&task4_switch, 0.034);//"retour d'information position par rs232"initialisation du ticker a 100hz "10ms".
//time_up5.attach(&task5_switch, 0.0001);//"lecture et ecriture DATA SPI1 initialisation du ticker 10khz.
- //time_up6.attach(&task6_switch, 0.034);//retour d'information courant.
+ time_up6.attach(&task6_switch, 0.034);//retour d'information courant.
time_up7.attach(&task7_switch, 0.00005);//lecture de la com rs tous les 100us.
// time_up8.attach(&task8_switch, 0.5);//detection numero de page tous les 100 ms.
+input1.fall(&do_the_Home);//declaration d une interuption lié a input1 pour faire la home
+input1.rise(&do_the_Home1);//declaration d une interuption lié a input1 pour faire la home
+
device.printf("sendme");
count_ticks=0;
c='0';
-
+
+home_done_tag=0;
+device.printf("g0.txt=\"home?? \"%c%c%c", 0xff, 0xff, 0xff);//affiche
+wait(2);
while(1)
{
-
+ myled1 = 0;
if(buttonCmd.IsNewCommandAvailable == 1)//si y as eu un bouton appuyé et que nous somme bien en la page n°7
{
motorStep = 0;
- myled1 = 0;
+
switch(buttonCmd.cmdNb)
{
case PageCmd:
@@ -1257,39 +1306,93 @@
if((buttonCmd.IsNewCommandAvailable == 1)&&(mRxMsg[1]==0x00))//si y as eu un bouton appuyé et que nous somme bien en la page n°0
{
motorStep = 0;
- myled1 = 0;
-
+
switch(buttonCmd.buttonId)
{
case 0x02: // boutn 'A' de la page 0
- myled1 = 1;
+
c='a';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x01: // boutn 'B' de la page 0
- myled1 = 1;
+
c='b';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x03: // boutn 'R' de la page 0
- myled1 = 1;
+
c='c';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x04: // boutn 'L' de la page 0
- myled1 = 1;
+
c='d';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x05: // boutn 'R2' de la page 0
- myled1 = 1;
+
c='d';
buttonCmd.IsNewCommandAvailable = 0;
- break;
+ break;
+
+ case 32: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 7: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 13: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 14: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 15: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 35: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 11: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 8: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 10: // boutn 'R2' de la page 0
+
+ page_detect_ok=0 ;
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
}
}
@@ -1335,7 +1438,41 @@
if((buttonCmd.IsNewCommandAvailable == 1)&&(mRxMsg[1]==0x05))//si y as eu un bouton appuyé et que nous somme bien en la page n°5
{
- //page5();
+ motorStep = 0;
+
+ switch(buttonCmd.buttonId)
+ {
+ case 0x04: // boutn 'A' de la page 7
+
+ c='a';
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 0x05: // boutn 'B' de la page 7
+
+ c='b';
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 0x06: // boutn 'C' de la page 7
+
+ c='c';
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 0x07: // boutn 'D' de la page 7
+
+ c='d';
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ case 14: // boutn 'BTO' de la page 7 bouton mouvement home
+
+ c='h';
+ buttonCmd.IsNewCommandAvailable = 0;
+ break;
+
+ }
}
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -1346,7 +1483,7 @@
{
//page6();
}
-
+
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////// page7 ////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -1354,36 +1491,35 @@
if((buttonCmd.IsNewCommandAvailable == 1)&&(mRxMsg[1]==0x07))//si y as eu un bouton appuyé et que nous somme bien en la page n°7
{
motorStep = 0;
- myled1 = 1;
-
+
switch(buttonCmd.buttonId)
{
case 0x2f: // boutn 'A' de la page 7
- myled1 = 0;
+
c='a';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x30: // boutn 'B' de la page 7
- myled1 = 0;
+
c='b';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x31: // boutn 'C' de la page 7
- myled1 = 0;
+
c='c';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x32: // boutn 'D' de la page 7
- myled1 = 0;
+
c='d';
buttonCmd.IsNewCommandAvailable = 0;
break;
case 0x01: // boutn 'D' de la page 7
- myled1 = 0;
+
c='d';
buttonCmd.IsNewCommandAvailable = 0;
break;
@@ -1393,269 +1529,367 @@
//c=valueFromMaster;//valeur par la liaison spi par le master
//device.scanf("%c",&c);//capture du caract ascii
- ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////// differants mouvement ////////////////////////////////////////////////////////////
- ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+///////////////////////////////////////////// differants mouvement ///////////////////////////////////////////////////
+///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+
(LPC_QEI->QEIPOS)=0;
switch(c)//commande moteur
{
case 'a':
- //qei.Reset(0);
+ if(home_done_tag==1)
+ {
+ //qei.Reset(0);
+ switch(motorStep)
+ {
+ case 0:
+ consigne=70000-position_home ;
+ slope_time=0.25;//t =s
+ start_slope=true;
+ {
+ motorStep = 1;
+ }
+ break;
+
+ case 1:
+ if(true == Wait2(0, 550))//ms
+ {
+ motorStep = 2;
+ }
+ break;
+
+ case 2:
+ consigne=132000-position_home ;
+ slope_time=2.5;//s
+ start_slope=true;
+ {
+ motorStep = 3;
+ }
+ break;
+
+ case 3:
+ if(true == Wait2(0, 3000))//ms
+ {
+ motorStep = 4;
+ }
+ break;
+
+ case 4:
+ consigne=35000-position_home ;
+ slope_time=2.5;//s
+ start_slope=true;
+ {
+ motorStep = 5;
+ }
+ break;
+
+ case 5:
+ if(true == Wait2(0, 3000))//ms
+ {
+ motorStep = 6;
+ }
+ break;
+
+ case 6:
+ consigne=0-position_home ;
+ slope_time=2.5;//s
+ start_slope=true;
+ {
+ motorStep = 7;
+ }
+ break;
+
+ case 7:
+ if(true == Wait2(0, 3000))//ms
+ {
+ motorStep = 0;
+ }
+ break;
+ }
+ }
+ break;
+
+ case 'b':
+ if(home_done_tag==1)
+ {
+ //qei.Reset(0);
+ switch(motorStep)
+ {
+ case 0:
+ consigne=0-position_home ; //1 tour
+ slope_time=3;//s
+ start_slope=true;
+ {
+ motorStep = 1;
+ }
+ break;
+
+ case 1:
+ if(true == Wait2(0, 3500))//ms
+ {
+ motorStep = 2;
+ }
+ break;
+
+ case 2:
+ consigne=10000-position_home ;
+ slope_time=0.25;//t=s
+ start_slope=true;
+ {
+ motorStep = 3;
+ }
+ break;
+
+ case 3:
+ if(true == Wait2(0, 400))//ms
+ {
+ motorStep = 4;
+ }
+ break;
+
+ case 4:
+ consigne=20000-position_home ;
+ slope_time=0.25;//t=s
+ start_slope=true;
+ {
+ motorStep = 5;
+ }
+ break;
+
+ case 5:
+ if(true == Wait2(0, 400))//ms
+ {
+ motorStep = 6;
+ }
+ break;
+
+ case 6:
+ consigne=30000-position_home ;
+ slope_time=0.25;//t=s
+ start_slope=true;
+ {
+ motorStep = 7;
+ }
+ break;
+
+ case 7:
+ if(true == Wait2(0, 400))//ms
+ {
+ motorStep = 8;
+ }
+ break;
+
+ case 8:
+ consigne=40000-position_home ;
+ slope_time=0.25;//t=s
+ start_slope=true;
+ {
+ motorStep = 9;
+ }
+ break;
+
+ case 9:
+ if(true == Wait2(0, 400))//ms
+ {
+ motorStep = 10;
+ }
+ break;
+
+ case 10:
+ consigne=50000-position_home ;
+ slope_time=0.25;//t=s
+ start_slope=true;
+ {
+ motorStep = 11;
+ }
+ break;
+
+ case 11:
+ if(true == Wait2(0, 400))//ms
+ {
+ motorStep = 12;
+ }
+ break;
+
+ case 12:
+ consigne=60000-position_home ;
+ slope_time=0.25;//t=s
+ start_slope=true;
+ {
+ motorStep = 13;
+ }
+ break;
+
+ case 13:
+ if(true == Wait2(0, 400))//ms
+ {
+ motorStep = 14;
+ }
+ break;
+
+ case 14:
+ consigne=132000-position_home ;
+ slope_time=1;//t=s
+ start_slope=true;
+ {
+ motorStep = 15;
+ }
+ break;
+
+ case 15:
+ if(true == Wait2(0, 1200))//ms
+ {
+ motorStep = 0;
+ }
+ break;
+ }
+ }
+ break;
+
+ case 'c':
+ if(home_done_tag==1)
+ {
+ //qei.Reset(0);
+ switch(motorStep)
+ {
+ case 0:
+ consigne=132000-position_home ; //1 tour
+ slope_time=2.5;//t =s
+ start_slope=true;
+ {
+ motorStep = 1;
+ }
+ break;
+
+ case 1:
+ if(true == Wait2(0, 3000))//ms
+ {
+ motorStep = 2;
+ }
+ break;
+
+ case 2:
+ consigne=0-position_home ; //1 tour
+ slope_time=2.5;//t=ms
+ start_slope=true;
+ {
+ motorStep = 3;
+ }
+ break;
+
+ case 3:
+ if(true == Wait2(0, 3000))//ms
+ {
+ motorStep = 0;
+ }
+ break;
+ }
+ }
+ break;
+
+ case 'd'://arret a la position actuelle
+ count_slope = 0;
+ position_a_cmd_darret=(LPC_QEI->QEIPOS);//sauvegarde position d'arret
+ consigne=position_a_cmd_darret ; //arret a la position
+ slope_time=0.010;//t =10ms
+ start_slope=true;
+ Wait2(0, 10);
+
+ //qei.Reset(QEI_RESET_POS);
+ //qei.Reset(QEI_RESET_POSOnIDX);
+ //qei.Reset(QEI_RESET_VEL);
+ //qei.Reset(QEI_RESET_IDX);
+
+ break;
+
+ case 'e'://allez a la position0 apret rising edge capteur de home
+
+
+ consigne=((LPC_QEI->QEIPOS)+1000) ; //arret a la position0 +1000
+ slope_time=10;//t =10s
+ start_slope=true;
+ //Wait2(0, 5000);
+
+ //qei.Reset(QEI_RESET_POS);
+ //qei.Reset(QEI_RESET_POSOnIDX);
+ //qei.Reset(QEI_RESET_VEL);
+ //qei.Reset(QEI_RESET_IDX);
+
+ break;
+
+ case 'f'://sortie du capteur home
+
+
+ consigne=(LPC_QEI->QEIPOS)+125000 ;
+ slope_time=15;//t =2000ms
+ start_slope=true;
+ // Wait2(0, 10000);
+
+ //qei.Reset(QEI_RESET_POS);
+ //qei.Reset(QEI_RESET_POSOnIDX);
+ //qei.Reset(QEI_RESET_VEL);
+ //qei.Reset(QEI_RESET_IDX);
+
+ break;
+
+ case 'g'://arret a la position actuelle
+
+ position_a_cmd_darret=(LPC_QEI->QEIPOS);//sauvegarde position d'arret
+ consigne=position_a_cmd_darret ; //arret a la position
+ slope_time=0.25;//t =2000ms
+ start_slope=true;
+ Wait2(0, 500);
+
+ //qei.Reset(QEI_RESET_POS);
+ //qei.Reset(QEI_RESET_POSOnIDX);
+ //qei.Reset(QEI_RESET_VEL);
+ //qei.Reset(QEI_RESET_IDX);
+
+ break;
+
+ case 'h'://mouvement de la home apret un arret
switch(motorStep)
{
case 0:
- consigne=70000 ; //4 tour
- slope_time=2.5;//t =2500ms
- start_slope=true;
- {
- myled3 = 0;
- motorStep = 1;
- }
- break;
-
- case 1:
- if(true == Wait2(0, 3000))
- {
- myled3 = 1;
- motorStep = 2;
- }
- break;
-
- case 2:
- consigne=0 ; //4 tour
- slope_time=2.5;//2500ms
- start_slope=true;
- {
- motorStep = 3;
- }
- break;
-
- case 3:
- if(true == Wait2(0, 3000))
- {
- motorStep = 4;
- }
- break;
-
- case 4:
- consigne=-70000 ; //4 tour
- slope_time=2.5;//2500ms
- start_slope=true;
- {
- motorStep = 5;
- }
- break;
-
- case 5:
- if(true == Wait2(0, 3000))
- {
- motorStep = 6;
- }
- break;
-
- case 6:
- consigne=0 ; //1 tour
- slope_time=2.5;//2500ms
- start_slope=true;
- {
- motorStep = 7;
- }
- break;
-
- case 7:
- if(true == Wait2(0, 3000))
- {
- motorStep = 0;
- }
- break;
- }
- break;
-
- case 'b':
- //qei.Reset(0);
- switch(motorStep)
- {
- case 0:
- consigne=0 ; //1 tour
- slope_time=0.25;//2500ms
- start_slope=true;
+ //count_slope = 0;
+ position_a_cmd_darret=(LPC_QEI->QEIPOS);//sauvegarde position d'arret
+ consigne=position_a_cmd_darret ; //arret a la position
+ slope_time=0.1;//t =10ms
+ start_slope=true;
+ Wait2(0, 100);//ms
{
motorStep = 1;
}
break;
case 1:
- if(true == Wait2(0, 400))
+ if(true == Wait2(0, 10))//ms
{
- motorStep = 2;
+ motorStep = 2;
}
- break;
-
- case 2:
- consigne=10000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 3;
- }
+ break;
+
+ case 2:
+ count_slope = 0;
+
+ consigne=-1125000 ; //arret a la position
+ slope_time=60;//t =40s
+ start_slope=true;
+
+
break;
- case 3:
- if(true == Wait2(0, 400))
- {
- motorStep = 4;
- }
- break;
- case 4:
- consigne=20000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 5;
- }
- break;
-
- case 5:
- if(true == Wait2(0, 400))
- {
- motorStep = 6;
- }
- break;
-
- case 6:
- consigne=30000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 7;
- }
- break;
-
- case 7:
- if(true == Wait2(0, 400))
- {
- motorStep = 8;
- }
- break;
-
- case 8:
- consigne=40000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 9;
- }
- break;
-
- case 9:
- if(true == Wait2(0, 400))
- {
- motorStep = 10;
- }
- break;
-
- case 10:
- consigne=50000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 11;
- }
- break;
-
- case 11:
- if(true == Wait2(0, 400))
- {
- motorStep = 12;
- }
- break;
-
- case 12:
- consigne=60000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 13;
- }
- break;
-
- case 13:
- if(true == Wait2(0, 400))
- {
- motorStep = 14;
- }
- break;
-
- case 14:
- consigne=70000 ; //1 tour
- slope_time=0.25;//t=ms
- start_slope=true;
- {
- motorStep = 15;
- }
- break;
-
- case 15:
- if(true == Wait2(0, 400))
- {
- motorStep = 0;
- }
- break;
-
}
- break;
-
+
+ break;
+
+ }
+
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
- case 'c'://arret a la position actuelle
- //qei.Reset(0);
- switch(motorStep)
- {
- case 0:
- consigne=70000 ; //1 tour
- slope_time=0.5;//t =0.ms
- start_slope=true;
- {
- motorStep = 1;
- }
- break;
-
- case 1:
- if(true == Wait2(0, 1000))
- {
- motorStep = 2;
- }
- break;
-
- case 2:
- consigne=0 ; //1 tour
- slope_time=0.5;//t=ms
- start_slope=true;
- {
- motorStep = 3;
- }
- break;
-
- case 3:
- if(true == Wait2(0, 1000))
- {
- motorStep = 0;
- }
- break;
- }
- break;
-
- case 'd'://arret a la position actuelle
- //qei.Reset(0);
- position_a_cmd_darret=(LPC_QEI->QEIPOS);//sauvegarde position d'arret
- consigne=position_a_cmd_darret ; //arret a la position
- slope_time=0.25;//t =2000ms
- start_slope=true;
- Wait2(0, 500);
-
- break;
-
- }
/*if(device2.readable())//ici on utilise une seconde com rs avec un autre ecrant nextion
{