PINOUT à jour, trame CAN OK
Dependencies: mbed ident_crac
Code carte pompe
main.cpp@17:fcfdd7de9039, 2019-05-25 (annotated)
- Committer:
- kyxstark
- Date:
- Sat May 25 00:56:34 2019 +0000
- Revision:
- 17:fcfdd7de9039
- Parent:
- 16:5e00af31ae8a
- Child:
- 18:972d29c668a5
dif courrioes
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 | CANMessage msgRxBuffer[SIZE_FIFO]; |
marwanesaich | 0:84a8c24e29ae | 9 | unsigned char FIFO_ecriture=0; //Position du fifo pour la reception CAN |
marwanesaich | 0:84a8c24e29ae | 10 | signed char FIFO_lecture=0;//Position du fifo de lecture des messages CAN |
kyxstark | 8:a25a9c22ba91 | 11 | char end_game = 0; |
marwanesaich | 0:84a8c24e29ae | 12 | |
kyxstark | 8:a25a9c22ba91 | 13 | Ventouse* ventouse[NB_VENTOUSES]; |
kyxstark | 8:a25a9c22ba91 | 14 | |
kyxstark | 17:fcfdd7de9039 | 15 | BusIn contacts(PC_11, PC_12, PB_4, PB_5, PC_13, PC_14, PC_2, PC_3); |
kyxstark | 17:fcfdd7de9039 | 16 | DigitalIn Contact1(PC_11, PullNone); |
kyxstark | 17:fcfdd7de9039 | 17 | DigitalIn Contact2(PC_12, PullNone); |
kyxstark | 17:fcfdd7de9039 | 18 | DigitalIn Contact3(PB_4, PullNone); |
kyxstark | 17:fcfdd7de9039 | 19 | DigitalIn Contact4(PB_5, PullNone); |
kyxstark | 17:fcfdd7de9039 | 20 | DigitalIn Contact5(PC_13, PullNone); |
kyxstark | 17:fcfdd7de9039 | 21 | DigitalIn Contact6(PC_14, PullNone); |
kyxstark | 17:fcfdd7de9039 | 22 | DigitalIn Contact7(PC_2, PullNone); |
kyxstark | 17:fcfdd7de9039 | 23 | DigitalIn Contact8(PC_3, PullNone); |
kyxstark | 17:fcfdd7de9039 | 24 | |
kyxstark | 17:fcfdd7de9039 | 25 | void lecture_contacts(void); |
kyxstark | 17:fcfdd7de9039 | 26 | |
kyxstark | 8:a25a9c22ba91 | 27 | #ifdef ROBOT_SMALL |
kyxstark | 8:a25a9c22ba91 | 28 | |
kyxstark | 8:a25a9c22ba91 | 29 | #endif |
kyxstark | 8:a25a9c22ba91 | 30 | |
kyxstark | 8:a25a9c22ba91 | 31 | #ifdef ROBOT_BIG |
kyxstark | 17:fcfdd7de9039 | 32 | |
kyxstark | 8:a25a9c22ba91 | 33 | PwmOut ascenseur[8] = {PC_9, PA_8, PA_9, PA_10, PC_7, PC_8, PB_10 ,PB_2}; |
kyxstark | 8:a25a9c22ba91 | 34 | PwmOut* ascenseur_D; |
kyxstark | 8:a25a9c22ba91 | 35 | PwmOut* ascenseur_G; |
kyxstark | 8:a25a9c22ba91 | 36 | |
kyxstark | 17:fcfdd7de9039 | 37 | #define VIT_COURROIE_V 0.6 |
kyxstark | 17:fcfdd7de9039 | 38 | #define VIT_COURROIE_L 0.5 |
kyxstark | 8:a25a9c22ba91 | 39 | |
kyxstark | 8:a25a9c22ba91 | 40 | void set_ascensseur(int allume); |
kyxstark | 8:a25a9c22ba91 | 41 | #endif |
kyxstark | 8:a25a9c22ba91 | 42 | |
marwanesaich | 0:84a8c24e29ae | 43 | |
marwanesaich | 0:84a8c24e29ae | 44 | |
marwanesaich | 0:84a8c24e29ae | 45 | void get_etat_ventouses(); |
marwanesaich | 0:84a8c24e29ae | 46 | |
kyxstark | 8:a25a9c22ba91 | 47 | |
marwanesaich | 2:4cc8fa2f64be | 48 | CAN can(PB_8,PB_9,1000000); |
marwanesaich | 2:4cc8fa2f64be | 49 | Serial pc(USBTX,USBRX); |
marwanesaich | 0:84a8c24e29ae | 50 | |
marwanesaich | 0:84a8c24e29ae | 51 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 52 | /* FUNCTION NAME: canRx_ISR */ |
marwanesaich | 0:84a8c24e29ae | 53 | /* DESCRIPTION : lit les messages sur le can et les stocke dans la FIFO */ |
marwanesaich | 0:84a8c24e29ae | 54 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 55 | void canRx_ISR (void) |
marwanesaich | 0:84a8c24e29ae | 56 | { |
marwanesaich | 0:84a8c24e29ae | 57 | if (can.read(msgRxBuffer[FIFO_ecriture])) |
marwanesaich | 0:84a8c24e29ae | 58 | FIFO_ecriture=(FIFO_ecriture+1)%SIZE_FIFO; |
marwanesaich | 0:84a8c24e29ae | 59 | } |
marwanesaich | 0:84a8c24e29ae | 60 | |
marwanesaich | 0:84a8c24e29ae | 61 | |
marwanesaich | 0:84a8c24e29ae | 62 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 63 | /* FUNCTION NAME: canProcessRx */ |
marwanesaich | 0:84a8c24e29ae | 64 | /* DESCRIPTION : Fonction de traitement des messages CAN */ |
marwanesaich | 0:84a8c24e29ae | 65 | /*********************************************************************************************************/ |
marwanesaich | 0:84a8c24e29ae | 66 | void canProcessRx(void){ |
marwanesaich | 0:84a8c24e29ae | 67 | static signed char FIFO_occupation=0,FIFO_max_occupation=0; |
marwanesaich | 0:84a8c24e29ae | 68 | CANMessage msgTx=CANMessage(); |
marwanesaich | 0:84a8c24e29ae | 69 | FIFO_occupation=FIFO_ecriture-FIFO_lecture; |
marwanesaich | 0:84a8c24e29ae | 70 | if(FIFO_occupation<0) |
marwanesaich | 0:84a8c24e29ae | 71 | FIFO_occupation=FIFO_occupation+SIZE_FIFO; |
marwanesaich | 0:84a8c24e29ae | 72 | if(FIFO_max_occupation<FIFO_occupation) |
marwanesaich | 0:84a8c24e29ae | 73 | FIFO_max_occupation=FIFO_occupation; |
marwanesaich | 0:84a8c24e29ae | 74 | if(FIFO_occupation!=0) { |
marwanesaich | 0:84a8c24e29ae | 75 | int identifiant=msgRxBuffer[FIFO_lecture].id; |
marwanesaich | 1:8a55f1d5cb26 | 76 | char BRAS = 0; |
marwanesaich | 1:8a55f1d5cb26 | 77 | |
marwanesaich | 0:84a8c24e29ae | 78 | switch(identifiant){ |
marwanesaich | 0:84a8c24e29ae | 79 | |
marwanesaich | 0:84a8c24e29ae | 80 | case HACHEUR_GET_ATOM: |
marwanesaich | 1:8a55f1d5cb26 | 81 | BRAS = msgRxBuffer[FIFO_lecture].data[0]; |
marwanesaich | 2:4cc8fa2f64be | 82 | ventouse[BRAS]->action(1); |
marwanesaich | 0:84a8c24e29ae | 83 | break; |
kyxstark | 8:a25a9c22ba91 | 84 | |
marwanesaich | 0:84a8c24e29ae | 85 | case HACHEUR_RELEASE_ATOM: |
marwanesaich | 1:8a55f1d5cb26 | 86 | BRAS = msgRxBuffer[FIFO_lecture].data[0]; |
marwanesaich | 2:4cc8fa2f64be | 87 | ventouse[BRAS]->action(0); |
kyxstark | 8:a25a9c22ba91 | 88 | break; |
kyxstark | 8:a25a9c22ba91 | 89 | |
kyxstark | 8:a25a9c22ba91 | 90 | case HACHEUR_STATUT_VENTOUSES: |
kyxstark | 8:a25a9c22ba91 | 91 | get_etat_ventouses(); |
kyxstark | 8:a25a9c22ba91 | 92 | break; |
kyxstark | 8:a25a9c22ba91 | 93 | |
kyxstark | 8:a25a9c22ba91 | 94 | case GLOBAL_GAME_END: |
kyxstark | 8:a25a9c22ba91 | 95 | end_game = 1; |
kyxstark | 8:a25a9c22ba91 | 96 | break; |
kyxstark | 17:fcfdd7de9039 | 97 | |
kyxstark | 17:fcfdd7de9039 | 98 | case HACHEUR_ETAT_CONTACTS: |
kyxstark | 17:fcfdd7de9039 | 99 | char contacts_tmp = contacts; |
kyxstark | 17:fcfdd7de9039 | 100 | can.write(CANMessage(HACHEUR_ETAT_CONTACTS,&contacts_tmp,1)); |
kyxstark | 17:fcfdd7de9039 | 101 | break; |
kyxstark | 8:a25a9c22ba91 | 102 | |
kyxstark | 8:a25a9c22ba91 | 103 | #ifdef ROBOT_SMALL |
kyxstark | 8:a25a9c22ba91 | 104 | |
marwanesaich | 0:84a8c24e29ae | 105 | |
marwanesaich | 4:82c90657da4a | 106 | case HACHEUR_GET_PRESENTOIR_AR: |
marwanesaich | 5:176e7353ba1c | 107 | ventouse[AR_GAUCHE]->action(1); |
marwanesaich | 5:176e7353ba1c | 108 | ventouse[AR_CENTRE]->action(1); |
marwanesaich | 5:176e7353ba1c | 109 | ventouse[AR_DROIT]->action(1); |
marwanesaich | 0:84a8c24e29ae | 110 | break; |
marwanesaich | 0:84a8c24e29ae | 111 | |
marwanesaich | 5:176e7353ba1c | 112 | case HACHEUR_RELEASE_AR: |
marwanesaich | 5:176e7353ba1c | 113 | ventouse[AR_GAUCHE]->action(0); |
marwanesaich | 5:176e7353ba1c | 114 | ventouse[AR_CENTRE]->action(0); |
marwanesaich | 5:176e7353ba1c | 115 | ventouse[AR_DROIT]->action(0); |
marwanesaich | 5:176e7353ba1c | 116 | break; |
marwanesaich | 5:176e7353ba1c | 117 | |
marwanesaich | 1:8a55f1d5cb26 | 118 | case HACHEUR_GET_PRESENTOIR_AV : |
marwanesaich | 5:176e7353ba1c | 119 | ventouse[AV_GAUCHE]->action(1); |
marwanesaich | 5:176e7353ba1c | 120 | ventouse[AV_CENTRE]->action(1); |
marwanesaich | 5:176e7353ba1c | 121 | ventouse[AV_DROIT]->action(1); |
marwanesaich | 0:84a8c24e29ae | 122 | break; |
marwanesaich | 0:84a8c24e29ae | 123 | |
marwanesaich | 5:176e7353ba1c | 124 | case HACHEUR_RELEASE_AV : |
marwanesaich | 5:176e7353ba1c | 125 | ventouse[AV_GAUCHE]->action(0); |
marwanesaich | 5:176e7353ba1c | 126 | ventouse[AV_CENTRE]->action(0); |
marwanesaich | 5:176e7353ba1c | 127 | ventouse[AV_DROIT]->action(0); |
marwanesaich | 5:176e7353ba1c | 128 | break; |
marwanesaich | 5:176e7353ba1c | 129 | |
kyxstark | 8:a25a9c22ba91 | 130 | |
kyxstark | 8:a25a9c22ba91 | 131 | |
kyxstark | 8:a25a9c22ba91 | 132 | #endif |
kyxstark | 8:a25a9c22ba91 | 133 | |
kyxstark | 8:a25a9c22ba91 | 134 | #ifdef ROBOT_BIG |
kyxstark | 8:a25a9c22ba91 | 135 | |
kyxstark | 8:a25a9c22ba91 | 136 | case HACHEUR_GET_PRESENTOIR_AV : |
kyxstark | 13:178eaf022d60 | 137 | ventouse[AV_GAUCHE]->action(1); |
kyxstark | 13:178eaf022d60 | 138 | ventouse[AV_CENTRE]->action(1); |
kyxstark | 13:178eaf022d60 | 139 | ventouse[AV_DROIT]->action(1); |
marwanesaich | 0:84a8c24e29ae | 140 | break; |
marwanesaich | 0:84a8c24e29ae | 141 | |
kyxstark | 8:a25a9c22ba91 | 142 | case HACHEUR_RELEASE_AV : |
kyxstark | 13:178eaf022d60 | 143 | ventouse[AV_GAUCHE]->action(0); |
kyxstark | 13:178eaf022d60 | 144 | ventouse[AV_CENTRE]->action(0); |
kyxstark | 13:178eaf022d60 | 145 | ventouse[AV_DROIT]->action(0); |
marwanesaich | 0:84a8c24e29ae | 146 | break; |
kyxstark | 8:a25a9c22ba91 | 147 | |
kyxstark | 9:8193c05bd0a0 | 148 | case HACHEUR_ID_COUROIES : |
kyxstark | 8:a25a9c22ba91 | 149 | set_ascensseur(msgRxBuffer[FIFO_lecture].data[0]); |
kyxstark | 8:a25a9c22ba91 | 150 | break; |
marwanesaich | 0:84a8c24e29ae | 151 | |
marwanesaich | 0:84a8c24e29ae | 152 | #endif |
marwanesaich | 0:84a8c24e29ae | 153 | } |
marwanesaich | 0:84a8c24e29ae | 154 | FIFO_lecture=(FIFO_lecture+1)%SIZE_FIFO; |
marwanesaich | 0:84a8c24e29ae | 155 | } |
marwanesaich | 0:84a8c24e29ae | 156 | } |
marwanesaich | 0:84a8c24e29ae | 157 | |
marwanesaich | 0:84a8c24e29ae | 158 | int main() { |
marwanesaich | 0:84a8c24e29ae | 159 | |
marwanesaich | 0:84a8c24e29ae | 160 | can.attach(&canRx_ISR); // création de l'interrupt attachée à la réception sur le CAN |
marwanesaich | 0:84a8c24e29ae | 161 | wait(1); |
marwanesaich | 1:8a55f1d5cb26 | 162 | #ifdef ROBOT_SMALL |
kyxstark | 10:765b4ff6d721 | 163 | pc.printf("\nPetit robot\n\n"); |
marwanesaich | 16:5e00af31ae8a | 164 | ventouse[AV_GAUCHE] = new Ventouse(PB_7, PB_6, PC_0, AV_GAUCHE); |
marwanesaich | 2:4cc8fa2f64be | 165 | ventouse[AR_CENTRE] = new Ventouse(PC_9, PA_8, PB_0, AR_CENTRE); |
marwanesaich | 2:4cc8fa2f64be | 166 | ventouse[AR_DROIT] = new Ventouse(PA_9, PA_10, PB_1, AR_DROIT); |
marwanesaich | 5:176e7353ba1c | 167 | //ventouse[AR_BAS] = new Ventouse(PA_11, PA_15, PC_1, AR_BAS); |
marwanesaich | 5:176e7353ba1c | 168 | ventouse[AR_BAS] = new Ventouse(PA_11, PC_1, AR_BAS); |
marwanesaich | 0:84a8c24e29ae | 169 | |
marwanesaich | 16:5e00af31ae8a | 170 | ventouse[AV_DROIT] = new Ventouse(PA_0, PA_1, PA_4, AV_DROIT); |
marwanesaich | 2:4cc8fa2f64be | 171 | ventouse[AV_CENTRE] = new Ventouse(PC_7,PC_8 , PC_5, AV_CENTRE); |
marwanesaich | 4:82c90657da4a | 172 | ventouse[AR_GAUCHE] = new Ventouse(PB_10, PB_2, PC_4, AR_GAUCHE); |
marwanesaich | 5:176e7353ba1c | 173 | //ventouse[AV_BAS] = new Ventouse(PA_6, PA_5, PA_7, AV_BAS); |
marwanesaich | 5:176e7353ba1c | 174 | ventouse[AV_BAS] = new Ventouse(PA_6, PA_7, AV_BAS); |
kyxstark | 8:a25a9c22ba91 | 175 | |
marwanesaich | 4:82c90657da4a | 176 | |
kyxstark | 8:a25a9c22ba91 | 177 | #endif |
kyxstark | 8:a25a9c22ba91 | 178 | |
kyxstark | 8:a25a9c22ba91 | 179 | #ifdef ROBOT_BIG |
kyxstark | 10:765b4ff6d721 | 180 | pc.printf("\nGros robot\n\n"); |
kyxstark | 13:178eaf022d60 | 181 | ventouse[AV_GAUCHE] = new Ventouse(PA_6, PA_5, PA_7, AV_GAUCHE); |
kyxstark | 13:178eaf022d60 | 182 | ventouse[AV_CENTRE] = new Ventouse(PA_0, PA_1, PA_4, AV_CENTRE); |
kyxstark | 13:178eaf022d60 | 183 | ventouse[AV_DROIT] = new Ventouse(PA_11, PA_15, PC_1, AV_DROIT); |
kyxstark | 8:a25a9c22ba91 | 184 | |
kyxstark | 8:a25a9c22ba91 | 185 | for (int i=0; i<8; i++){ |
kyxstark | 8:a25a9c22ba91 | 186 | ascenseur[i].period_us(50); |
kyxstark | 8:a25a9c22ba91 | 187 | } |
kyxstark | 8:a25a9c22ba91 | 188 | |
kyxstark | 8:a25a9c22ba91 | 189 | ascenseur_D = ascenseur; |
kyxstark | 8:a25a9c22ba91 | 190 | ascenseur_G = ascenseur + 4; |
kyxstark | 8:a25a9c22ba91 | 191 | |
kyxstark | 8:a25a9c22ba91 | 192 | |
kyxstark | 8:a25a9c22ba91 | 193 | set_ascensseur(0); |
kyxstark | 8:a25a9c22ba91 | 194 | wait(1); |
marwanesaich | 1:8a55f1d5cb26 | 195 | #endif |
kyxstark | 8:a25a9c22ba91 | 196 | |
marwanesaich | 1:8a55f1d5cb26 | 197 | pc.printf("LAUNCHED"); |
marwanesaich | 0:84a8c24e29ae | 198 | while(1) { |
marwanesaich | 0:84a8c24e29ae | 199 | canProcessRx(); |
kyxstark | 8:a25a9c22ba91 | 200 | for(int i=0; i<NB_VENTOUSES; i++){ |
marwanesaich | 2:4cc8fa2f64be | 201 | ventouse[i]->automate(); |
kyxstark | 17:fcfdd7de9039 | 202 | } |
kyxstark | 17:fcfdd7de9039 | 203 | lecture_contacts(); |
kyxstark | 17:fcfdd7de9039 | 204 | |
kyxstark | 17:fcfdd7de9039 | 205 | |
marwanesaich | 0:84a8c24e29ae | 206 | if(end_game){ |
kyxstark | 8:a25a9c22ba91 | 207 | for(int i=0; i<NB_VENTOUSES;i++){ |
marwanesaich | 0:84a8c24e29ae | 208 | ventouse[i]->setPompe(0.0); |
kyxstark | 8:a25a9c22ba91 | 209 | ventouse[i]->setElectrovanne(0); |
marwanesaich | 0:84a8c24e29ae | 210 | } |
kyxstark | 17:fcfdd7de9039 | 211 | #ifdef ROBOT_BIG |
marwanesaich | 11:98dfe1a61df5 | 212 | set_ascensseur(0); |
kyxstark | 17:fcfdd7de9039 | 213 | #endif |
marwanesaich | 0:84a8c24e29ae | 214 | while(1){;} |
marwanesaich | 0:84a8c24e29ae | 215 | } |
marwanesaich | 0:84a8c24e29ae | 216 | } |
marwanesaich | 0:84a8c24e29ae | 217 | } |
marwanesaich | 0:84a8c24e29ae | 218 | |
kyxstark | 17:fcfdd7de9039 | 219 | void lecture_contacts(void) |
kyxstark | 17:fcfdd7de9039 | 220 | { |
kyxstark | 17:fcfdd7de9039 | 221 | static char prev_contacts = contacts; |
kyxstark | 17:fcfdd7de9039 | 222 | |
kyxstark | 17:fcfdd7de9039 | 223 | if(contacts != prev_contacts) |
kyxstark | 17:fcfdd7de9039 | 224 | { |
kyxstark | 17:fcfdd7de9039 | 225 | prev_contacts = contacts; |
kyxstark | 17:fcfdd7de9039 | 226 | can.write(CANMessage(HACHEUR_ETAT_CONTACTS,&prev_contacts,1)); |
kyxstark | 17:fcfdd7de9039 | 227 | } |
kyxstark | 17:fcfdd7de9039 | 228 | } |
kyxstark | 8:a25a9c22ba91 | 229 | #ifdef ROBOT_BIG |
kyxstark | 8:a25a9c22ba91 | 230 | void set_ascensseur(int allume){ |
kyxstark | 17:fcfdd7de9039 | 231 | float vitG, vitD; |
kyxstark | 17:fcfdd7de9039 | 232 | |
kyxstark | 17:fcfdd7de9039 | 233 | switch(allume){ |
kyxstark | 17:fcfdd7de9039 | 234 | case 1: |
kyxstark | 17:fcfdd7de9039 | 235 | vitG = VIT_COURROIE_V; |
kyxstark | 17:fcfdd7de9039 | 236 | vitD = VIT_COURROIE_L; |
kyxstark | 17:fcfdd7de9039 | 237 | break; |
kyxstark | 17:fcfdd7de9039 | 238 | case 2: |
kyxstark | 17:fcfdd7de9039 | 239 | vitG = VIT_COURROIE_L; |
kyxstark | 17:fcfdd7de9039 | 240 | vitD = VIT_COURROIE_V; |
kyxstark | 17:fcfdd7de9039 | 241 | break; |
kyxstark | 17:fcfdd7de9039 | 242 | default: |
kyxstark | 17:fcfdd7de9039 | 243 | vitG = 0; |
kyxstark | 17:fcfdd7de9039 | 244 | vitD = 0; |
kyxstark | 17:fcfdd7de9039 | 245 | break; |
kyxstark | 8:a25a9c22ba91 | 246 | } |
kyxstark | 17:fcfdd7de9039 | 247 | |
kyxstark | 17:fcfdd7de9039 | 248 | for (int i=0; i<4; i++) |
kyxstark | 17:fcfdd7de9039 | 249 | { |
kyxstark | 17:fcfdd7de9039 | 250 | ascenseur_D[i] = vitD; |
kyxstark | 17:fcfdd7de9039 | 251 | ascenseur_G[i] = vitG; |
kyxstark | 8:a25a9c22ba91 | 252 | } |
kyxstark | 8:a25a9c22ba91 | 253 | } |
kyxstark | 8:a25a9c22ba91 | 254 | #endif |
kyxstark | 8:a25a9c22ba91 | 255 | |
marwanesaich | 0:84a8c24e29ae | 256 | void get_etat_ventouses() |
marwanesaich | 0:84a8c24e29ae | 257 | { |
marwanesaich | 0:84a8c24e29ae | 258 | CANMessage etat_ventouses = CANMessage(); |
marwanesaich | 0:84a8c24e29ae | 259 | etat_ventouses.id=HACHEUR_STATUT_VENTOUSES; |
marwanesaich | 0:84a8c24e29ae | 260 | etat_ventouses.len=2; |
marwanesaich | 0:84a8c24e29ae | 261 | etat_ventouses.format=CANStandard; |
marwanesaich | 0:84a8c24e29ae | 262 | etat_ventouses.type=CANData; |
marwanesaich | 2:4cc8fa2f64be | 263 | etat_ventouses.data[0]=0; |
marwanesaich | 2:4cc8fa2f64be | 264 | etat_ventouses.data[0]=1; |
kyxstark | 10:765b4ff6d721 | 265 | for(int i = (NB_VENTOUSES - 1); i >= 0; i--){ |
marwanesaich | 0:84a8c24e29ae | 266 | etat_ventouses.data[0] = (etat_ventouses.data[0]<<1) + ventouse[i]->getPompe(); |
marwanesaich | 0:84a8c24e29ae | 267 | etat_ventouses.data[1] = (etat_ventouses.data[1]<<1) + ventouse[i]->getPression(); |
marwanesaich | 0:84a8c24e29ae | 268 | } |
marwanesaich | 0:84a8c24e29ae | 269 | can.write(etat_ventouses); |
marwanesaich | 0:84a8c24e29ae | 270 | |
marwanesaich | 0:84a8c24e29ae | 271 | } |