carte esclave pompe 2020 V1
Dependencies: mbed ident_crac
main.cpp@16:5e00af31ae8a, 2019-05-23 (annotated)
- Committer:
- marwanesaich
- Date:
- Thu May 23 10:36:35 2019 +0000
- Revision:
- 16:5e00af31ae8a
- Parent:
- 13:178eaf022d60
- Child:
- 17:fcfdd7de9039
reglage delay et seuil release atome
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
kyxstark | 12:2491a5b0f90b | 1 | |
marwanesaich | 4:82c90657da4a | 2 | #include "extern.h" |
kyxstark | 8:a25a9c22ba91 | 3 | #define SIZE_FIFO 50 |
marwanesaich | 1:8a55f1d5cb26 | 4 | |
kyxstark | 8:a25a9c22ba91 | 5 | |
marwanesaich | 0:84a8c24e29ae | 6 | |
kyxstark | 8:a25a9c22ba91 | 7 | |
marwanesaich | 0:84a8c24e29ae | 8 | |
marwanesaich | 0:84a8c24e29ae | 9 | CANMessage msgRxBuffer[SIZE_FIFO]; |
marwanesaich | 0:84a8c24e29ae | 10 | unsigned char FIFO_ecriture=0; //Position du fifo pour la reception CAN |
marwanesaich | 0:84a8c24e29ae | 11 | signed char FIFO_lecture=0;//Position du fifo de lecture des messages CAN |
kyxstark | 8:a25a9c22ba91 | 12 | char end_game = 0; |
marwanesaich | 0:84a8c24e29ae | 13 | |
kyxstark | 8:a25a9c22ba91 | 14 | Ventouse* ventouse[NB_VENTOUSES]; |
kyxstark | 8:a25a9c22ba91 | 15 | |
kyxstark | 8:a25a9c22ba91 | 16 | #ifdef ROBOT_SMALL |
kyxstark | 8:a25a9c22ba91 | 17 | |
kyxstark | 8:a25a9c22ba91 | 18 | #endif |
kyxstark | 8:a25a9c22ba91 | 19 | |
kyxstark | 8:a25a9c22ba91 | 20 | #ifdef ROBOT_BIG |
kyxstark | 8:a25a9c22ba91 | 21 | PwmOut ascenseur[8] = {PC_9, PA_8, PA_9, PA_10, PC_7, PC_8, PB_10 ,PB_2}; |
kyxstark | 8:a25a9c22ba91 | 22 | PwmOut* ascenseur_D; |
kyxstark | 8:a25a9c22ba91 | 23 | PwmOut* ascenseur_G; |
kyxstark | 8:a25a9c22ba91 | 24 | |
kyxstark | 8:a25a9c22ba91 | 25 | #define VIT_G 0.7 |
kyxstark | 8:a25a9c22ba91 | 26 | #define VIT_D 0.65 |
kyxstark | 8:a25a9c22ba91 | 27 | |
kyxstark | 8:a25a9c22ba91 | 28 | void set_ascensseur(int allume); |
kyxstark | 8:a25a9c22ba91 | 29 | #endif |
kyxstark | 8:a25a9c22ba91 | 30 | |
marwanesaich | 0:84a8c24e29ae | 31 | |
marwanesaich | 0:84a8c24e29ae | 32 | |
marwanesaich | 0:84a8c24e29ae | 33 | void get_etat_ventouses(); |
marwanesaich | 0:84a8c24e29ae | 34 | |
kyxstark | 8:a25a9c22ba91 | 35 | |
marwanesaich | 2:4cc8fa2f64be | 36 | CAN can(PB_8,PB_9,1000000); |
marwanesaich | 2:4cc8fa2f64be | 37 | Serial pc(USBTX,USBRX); |
marwanesaich | 0:84a8c24e29ae | 38 | |
marwanesaich | 0:84a8c24e29ae | 39 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 40 | /* FUNCTION NAME: canRx_ISR */ |
marwanesaich | 0:84a8c24e29ae | 41 | /* DESCRIPTION : lit les messages sur le can et les stocke dans la FIFO */ |
marwanesaich | 0:84a8c24e29ae | 42 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 43 | void canRx_ISR (void) |
marwanesaich | 0:84a8c24e29ae | 44 | { |
marwanesaich | 0:84a8c24e29ae | 45 | if (can.read(msgRxBuffer[FIFO_ecriture])) |
marwanesaich | 0:84a8c24e29ae | 46 | FIFO_ecriture=(FIFO_ecriture+1)%SIZE_FIFO; |
marwanesaich | 0:84a8c24e29ae | 47 | } |
marwanesaich | 0:84a8c24e29ae | 48 | |
marwanesaich | 0:84a8c24e29ae | 49 | |
marwanesaich | 0:84a8c24e29ae | 50 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 51 | /* FUNCTION NAME: canProcessRx */ |
marwanesaich | 0:84a8c24e29ae | 52 | /* DESCRIPTION : Fonction de traitement des messages CAN */ |
marwanesaich | 0:84a8c24e29ae | 53 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 54 | void canProcessRx(void){ |
marwanesaich | 0:84a8c24e29ae | 55 | static signed char FIFO_occupation=0,FIFO_max_occupation=0; |
marwanesaich | 0:84a8c24e29ae | 56 | CANMessage msgTx=CANMessage(); |
marwanesaich | 0:84a8c24e29ae | 57 | FIFO_occupation=FIFO_ecriture-FIFO_lecture; |
marwanesaich | 0:84a8c24e29ae | 58 | if(FIFO_occupation<0) |
marwanesaich | 0:84a8c24e29ae | 59 | FIFO_occupation=FIFO_occupation+SIZE_FIFO; |
marwanesaich | 0:84a8c24e29ae | 60 | if(FIFO_max_occupation<FIFO_occupation) |
marwanesaich | 0:84a8c24e29ae | 61 | FIFO_max_occupation=FIFO_occupation; |
marwanesaich | 0:84a8c24e29ae | 62 | if(FIFO_occupation!=0) { |
marwanesaich | 0:84a8c24e29ae | 63 | int identifiant=msgRxBuffer[FIFO_lecture].id; |
marwanesaich | 1:8a55f1d5cb26 | 64 | char BRAS = 0; |
marwanesaich | 1:8a55f1d5cb26 | 65 | |
marwanesaich | 0:84a8c24e29ae | 66 | switch(identifiant){ |
marwanesaich | 0:84a8c24e29ae | 67 | |
marwanesaich | 0:84a8c24e29ae | 68 | case HACHEUR_GET_ATOM: |
marwanesaich | 1:8a55f1d5cb26 | 69 | BRAS = msgRxBuffer[FIFO_lecture].data[0]; |
marwanesaich | 2:4cc8fa2f64be | 70 | ventouse[BRAS]->action(1); |
marwanesaich | 0:84a8c24e29ae | 71 | break; |
kyxstark | 8:a25a9c22ba91 | 72 | |
marwanesaich | 0:84a8c24e29ae | 73 | case HACHEUR_RELEASE_ATOM: |
marwanesaich | 1:8a55f1d5cb26 | 74 | BRAS = msgRxBuffer[FIFO_lecture].data[0]; |
marwanesaich | 2:4cc8fa2f64be | 75 | ventouse[BRAS]->action(0); |
kyxstark | 8:a25a9c22ba91 | 76 | break; |
kyxstark | 8:a25a9c22ba91 | 77 | |
kyxstark | 8:a25a9c22ba91 | 78 | case HACHEUR_STATUT_VENTOUSES: |
kyxstark | 8:a25a9c22ba91 | 79 | get_etat_ventouses(); |
kyxstark | 8:a25a9c22ba91 | 80 | break; |
kyxstark | 8:a25a9c22ba91 | 81 | |
kyxstark | 8:a25a9c22ba91 | 82 | case GLOBAL_GAME_END: |
kyxstark | 8:a25a9c22ba91 | 83 | end_game = 1; |
kyxstark | 8:a25a9c22ba91 | 84 | break; |
kyxstark | 8:a25a9c22ba91 | 85 | |
kyxstark | 8:a25a9c22ba91 | 86 | #ifdef ROBOT_SMALL |
kyxstark | 8:a25a9c22ba91 | 87 | |
marwanesaich | 0:84a8c24e29ae | 88 | |
marwanesaich | 4:82c90657da4a | 89 | case HACHEUR_GET_PRESENTOIR_AR: |
marwanesaich | 5:176e7353ba1c | 90 | ventouse[AR_GAUCHE]->action(1); |
marwanesaich | 5:176e7353ba1c | 91 | ventouse[AR_CENTRE]->action(1); |
marwanesaich | 5:176e7353ba1c | 92 | ventouse[AR_DROIT]->action(1); |
marwanesaich | 0:84a8c24e29ae | 93 | break; |
marwanesaich | 0:84a8c24e29ae | 94 | |
marwanesaich | 5:176e7353ba1c | 95 | case HACHEUR_RELEASE_AR: |
marwanesaich | 5:176e7353ba1c | 96 | ventouse[AR_GAUCHE]->action(0); |
marwanesaich | 5:176e7353ba1c | 97 | ventouse[AR_CENTRE]->action(0); |
marwanesaich | 5:176e7353ba1c | 98 | ventouse[AR_DROIT]->action(0); |
marwanesaich | 5:176e7353ba1c | 99 | break; |
marwanesaich | 5:176e7353ba1c | 100 | |
marwanesaich | 1:8a55f1d5cb26 | 101 | case HACHEUR_GET_PRESENTOIR_AV : |
marwanesaich | 5:176e7353ba1c | 102 | ventouse[AV_GAUCHE]->action(1); |
marwanesaich | 5:176e7353ba1c | 103 | ventouse[AV_CENTRE]->action(1); |
marwanesaich | 5:176e7353ba1c | 104 | ventouse[AV_DROIT]->action(1); |
marwanesaich | 0:84a8c24e29ae | 105 | break; |
marwanesaich | 0:84a8c24e29ae | 106 | |
marwanesaich | 5:176e7353ba1c | 107 | case HACHEUR_RELEASE_AV : |
marwanesaich | 5:176e7353ba1c | 108 | ventouse[AV_GAUCHE]->action(0); |
marwanesaich | 5:176e7353ba1c | 109 | ventouse[AV_CENTRE]->action(0); |
marwanesaich | 5:176e7353ba1c | 110 | ventouse[AV_DROIT]->action(0); |
marwanesaich | 5:176e7353ba1c | 111 | break; |
marwanesaich | 5:176e7353ba1c | 112 | |
kyxstark | 8:a25a9c22ba91 | 113 | |
kyxstark | 8:a25a9c22ba91 | 114 | |
kyxstark | 8:a25a9c22ba91 | 115 | |
kyxstark | 8:a25a9c22ba91 | 116 | #endif |
kyxstark | 8:a25a9c22ba91 | 117 | |
kyxstark | 8:a25a9c22ba91 | 118 | #ifdef ROBOT_BIG |
kyxstark | 8:a25a9c22ba91 | 119 | |
kyxstark | 8:a25a9c22ba91 | 120 | case HACHEUR_GET_PRESENTOIR_AV : |
kyxstark | 13:178eaf022d60 | 121 | ventouse[AV_GAUCHE]->action(1); |
kyxstark | 13:178eaf022d60 | 122 | ventouse[AV_CENTRE]->action(1); |
kyxstark | 13:178eaf022d60 | 123 | ventouse[AV_DROIT]->action(1); |
marwanesaich | 0:84a8c24e29ae | 124 | break; |
marwanesaich | 0:84a8c24e29ae | 125 | |
kyxstark | 8:a25a9c22ba91 | 126 | case HACHEUR_RELEASE_AV : |
kyxstark | 13:178eaf022d60 | 127 | ventouse[AV_GAUCHE]->action(0); |
kyxstark | 13:178eaf022d60 | 128 | ventouse[AV_CENTRE]->action(0); |
kyxstark | 13:178eaf022d60 | 129 | ventouse[AV_DROIT]->action(0); |
marwanesaich | 0:84a8c24e29ae | 130 | break; |
kyxstark | 8:a25a9c22ba91 | 131 | |
kyxstark | 9:8193c05bd0a0 | 132 | case HACHEUR_ID_COUROIES : |
kyxstark | 8:a25a9c22ba91 | 133 | set_ascensseur(msgRxBuffer[FIFO_lecture].data[0]); |
kyxstark | 8:a25a9c22ba91 | 134 | break; |
marwanesaich | 0:84a8c24e29ae | 135 | |
marwanesaich | 0:84a8c24e29ae | 136 | #endif |
marwanesaich | 0:84a8c24e29ae | 137 | } |
marwanesaich | 0:84a8c24e29ae | 138 | FIFO_lecture=(FIFO_lecture+1)%SIZE_FIFO; |
marwanesaich | 0:84a8c24e29ae | 139 | } |
marwanesaich | 0:84a8c24e29ae | 140 | } |
marwanesaich | 0:84a8c24e29ae | 141 | |
marwanesaich | 0:84a8c24e29ae | 142 | int main() { |
marwanesaich | 0:84a8c24e29ae | 143 | |
marwanesaich | 0:84a8c24e29ae | 144 | can.attach(&canRx_ISR); // création de l'interrupt attachée à la réception sur le CAN |
marwanesaich | 0:84a8c24e29ae | 145 | wait(1); |
marwanesaich | 1:8a55f1d5cb26 | 146 | #ifdef ROBOT_SMALL |
kyxstark | 10:765b4ff6d721 | 147 | pc.printf("\nPetit robot\n\n"); |
marwanesaich | 16:5e00af31ae8a | 148 | ventouse[AV_GAUCHE] = new Ventouse(PB_7, PB_6, PC_0, AV_GAUCHE); |
marwanesaich | 2:4cc8fa2f64be | 149 | ventouse[AR_CENTRE] = new Ventouse(PC_9, PA_8, PB_0, AR_CENTRE); |
marwanesaich | 2:4cc8fa2f64be | 150 | ventouse[AR_DROIT] = new Ventouse(PA_9, PA_10, PB_1, AR_DROIT); |
marwanesaich | 5:176e7353ba1c | 151 | //ventouse[AR_BAS] = new Ventouse(PA_11, PA_15, PC_1, AR_BAS); |
marwanesaich | 5:176e7353ba1c | 152 | ventouse[AR_BAS] = new Ventouse(PA_11, PC_1, AR_BAS); |
marwanesaich | 0:84a8c24e29ae | 153 | |
marwanesaich | 16:5e00af31ae8a | 154 | ventouse[AV_DROIT] = new Ventouse(PA_0, PA_1, PA_4, AV_DROIT); |
marwanesaich | 2:4cc8fa2f64be | 155 | ventouse[AV_CENTRE] = new Ventouse(PC_7,PC_8 , PC_5, AV_CENTRE); |
marwanesaich | 4:82c90657da4a | 156 | ventouse[AR_GAUCHE] = new Ventouse(PB_10, PB_2, PC_4, AR_GAUCHE); |
marwanesaich | 5:176e7353ba1c | 157 | //ventouse[AV_BAS] = new Ventouse(PA_6, PA_5, PA_7, AV_BAS); |
marwanesaich | 5:176e7353ba1c | 158 | ventouse[AV_BAS] = new Ventouse(PA_6, PA_7, AV_BAS); |
kyxstark | 8:a25a9c22ba91 | 159 | |
marwanesaich | 4:82c90657da4a | 160 | |
kyxstark | 8:a25a9c22ba91 | 161 | #endif |
kyxstark | 8:a25a9c22ba91 | 162 | |
kyxstark | 8:a25a9c22ba91 | 163 | #ifdef ROBOT_BIG |
kyxstark | 10:765b4ff6d721 | 164 | pc.printf("\nGros robot\n\n"); |
kyxstark | 13:178eaf022d60 | 165 | ventouse[AV_GAUCHE] = new Ventouse(PA_6, PA_5, PA_7, AV_GAUCHE); |
kyxstark | 13:178eaf022d60 | 166 | ventouse[AV_CENTRE] = new Ventouse(PA_0, PA_1, PA_4, AV_CENTRE); |
kyxstark | 13:178eaf022d60 | 167 | ventouse[AV_DROIT] = new Ventouse(PA_11, PA_15, PC_1, AV_DROIT); |
kyxstark | 8:a25a9c22ba91 | 168 | |
kyxstark | 8:a25a9c22ba91 | 169 | for (int i=0; i<8; i++){ |
kyxstark | 8:a25a9c22ba91 | 170 | ascenseur[i].period_us(50); |
kyxstark | 8:a25a9c22ba91 | 171 | } |
kyxstark | 8:a25a9c22ba91 | 172 | |
kyxstark | 8:a25a9c22ba91 | 173 | ascenseur_D = ascenseur; |
kyxstark | 8:a25a9c22ba91 | 174 | ascenseur_G = ascenseur + 4; |
kyxstark | 8:a25a9c22ba91 | 175 | |
kyxstark | 8:a25a9c22ba91 | 176 | |
kyxstark | 8:a25a9c22ba91 | 177 | set_ascensseur(0); |
kyxstark | 8:a25a9c22ba91 | 178 | wait(1); |
marwanesaich | 1:8a55f1d5cb26 | 179 | #endif |
kyxstark | 8:a25a9c22ba91 | 180 | |
marwanesaich | 1:8a55f1d5cb26 | 181 | pc.printf("LAUNCHED"); |
marwanesaich | 0:84a8c24e29ae | 182 | while(1) { |
marwanesaich | 0:84a8c24e29ae | 183 | canProcessRx(); |
kyxstark | 8:a25a9c22ba91 | 184 | for(int i=0; i<NB_VENTOUSES; i++){ |
marwanesaich | 2:4cc8fa2f64be | 185 | ventouse[i]->automate(); |
marwanesaich | 2:4cc8fa2f64be | 186 | } |
marwanesaich | 0:84a8c24e29ae | 187 | if(end_game){ |
kyxstark | 8:a25a9c22ba91 | 188 | for(int i=0; i<NB_VENTOUSES;i++){ |
marwanesaich | 0:84a8c24e29ae | 189 | ventouse[i]->setPompe(0.0); |
kyxstark | 8:a25a9c22ba91 | 190 | ventouse[i]->setElectrovanne(0); |
marwanesaich | 0:84a8c24e29ae | 191 | } |
marwanesaich | 11:98dfe1a61df5 | 192 | #ifdef ROBOT_BIG |
marwanesaich | 11:98dfe1a61df5 | 193 | set_ascensseur(0); |
marwanesaich | 11:98dfe1a61df5 | 194 | #endif |
marwanesaich | 0:84a8c24e29ae | 195 | while(1){;} |
marwanesaich | 0:84a8c24e29ae | 196 | } |
marwanesaich | 0:84a8c24e29ae | 197 | } |
marwanesaich | 0:84a8c24e29ae | 198 | } |
marwanesaich | 0:84a8c24e29ae | 199 | |
marwanesaich | 0:84a8c24e29ae | 200 | |
kyxstark | 8:a25a9c22ba91 | 201 | |
kyxstark | 8:a25a9c22ba91 | 202 | #ifdef ROBOT_BIG |
kyxstark | 8:a25a9c22ba91 | 203 | void set_ascensseur(int allume){ |
kyxstark | 8:a25a9c22ba91 | 204 | float vit = VIT_D*allume; |
kyxstark | 8:a25a9c22ba91 | 205 | for (int i=0; i<4; i++){ |
kyxstark | 8:a25a9c22ba91 | 206 | ascenseur_D[i] = vit; |
kyxstark | 8:a25a9c22ba91 | 207 | } |
kyxstark | 8:a25a9c22ba91 | 208 | vit = VIT_G*allume; |
kyxstark | 8:a25a9c22ba91 | 209 | for (int i=0; i<4; i++){ |
kyxstark | 8:a25a9c22ba91 | 210 | ascenseur_G[i] = vit; |
kyxstark | 8:a25a9c22ba91 | 211 | } |
kyxstark | 8:a25a9c22ba91 | 212 | } |
kyxstark | 8:a25a9c22ba91 | 213 | #endif |
kyxstark | 8:a25a9c22ba91 | 214 | |
marwanesaich | 0:84a8c24e29ae | 215 | void get_etat_ventouses() |
marwanesaich | 0:84a8c24e29ae | 216 | { |
marwanesaich | 0:84a8c24e29ae | 217 | CANMessage etat_ventouses = CANMessage(); |
marwanesaich | 0:84a8c24e29ae | 218 | etat_ventouses.id=HACHEUR_STATUT_VENTOUSES; |
marwanesaich | 0:84a8c24e29ae | 219 | etat_ventouses.len=2; |
marwanesaich | 0:84a8c24e29ae | 220 | etat_ventouses.format=CANStandard; |
marwanesaich | 0:84a8c24e29ae | 221 | etat_ventouses.type=CANData; |
marwanesaich | 2:4cc8fa2f64be | 222 | etat_ventouses.data[0]=0; |
marwanesaich | 2:4cc8fa2f64be | 223 | etat_ventouses.data[0]=1; |
kyxstark | 10:765b4ff6d721 | 224 | for(int i = (NB_VENTOUSES - 1); i >= 0; i--){ |
marwanesaich | 0:84a8c24e29ae | 225 | etat_ventouses.data[0] = (etat_ventouses.data[0]<<1) + ventouse[i]->getPompe(); |
marwanesaich | 0:84a8c24e29ae | 226 | etat_ventouses.data[1] = (etat_ventouses.data[1]<<1) + ventouse[i]->getPression(); |
marwanesaich | 0:84a8c24e29ae | 227 | } |
marwanesaich | 0:84a8c24e29ae | 228 | can.write(etat_ventouses); |
marwanesaich | 0:84a8c24e29ae | 229 | |
marwanesaich | 0:84a8c24e29ae | 230 | } |