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
RobotFinale52.cpp
00001 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00002 // Revisione del 21/03/2019 00003 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00004 00005 // mbed specific header files. 00006 #include "mbed.h" 00007 00008 // numero di acqusizioni su cui effettuare la media della temperatura 00009 #define NUMSAMPLE 300 00010 00011 // include suono del motore 00012 #include "SampledSoundGurgle.h" // rumore del motore da fermo durante gli spsotamenti 00013 #include "SampledSoundWelcomeDizione.h" // messaggio di benvenuto 00014 #include "SampledSoundFarewellDizione.h" // messaggio di Arrivederci 00015 #include "SampledSoundMotosega.h" // rumore durante lo spostamento con Cesoia 00016 #include "SampledSoundDontTouch.h" // Messaggio di Don't Touch Me 00017 00018 //#include "SampledSoundMotosega.h" 00019 //#include "SampledSoundTrattore.h" 00020 00021 00022 // TimeOut in [microsec] per verificare la presenza del sensore prossimità. Se il sensore non è presente il timer supera TIMEOUTPROXSENSOR 00023 #define TIMEOUTPROXSENSOR 1000 //tempo in [microsec] 00024 00025 // numero di campioni che compongono un periodo della sinusoide in Output sull'ADC 00026 #define CLACSONSAMPLENUM 45 // consigliabile avere multipli di 45 00027 00028 // numero di campioni acquisiti su cui effettuare la media di luminosità 00029 #define NUMLIGHTSAMPLE 100 00030 00031 // Parametri di soglia per la luce. Accendi/spegni Luci se la luminosità scende/sale sotto/sopra SOGLIALUCIMAX e SOGLIALUCIMIN 00032 #define SOGLIALUCIMAX (1.85) 00033 #define SOGLIALUCIMIN (1.45) 00034 00035 // parametri dell'onda coseno da generare 00036 #define PI (3.141592653589793238462) 00037 #define AMPLITUDE 32767 //(1.0) // x * 3.3V 00038 #define PHASE (PI/2) // 2*pi è un periodo 00039 #define OFFSET 32767 //(0x7FFF) 00040 00041 // variabile che modula l'amplificazione dei segnali audio. 1= non cambia niente. 0=amplificazione 0; 00042 #define SOUNDGAIN (1.0) 00043 00044 // ticker per la generazione dell'onda con DAC 00045 Ticker SampleOutTicker; 00046 00047 00048 // Timer per il calcolo dei tempi del sensore di prossimità 00049 Timer TimerProxSensor; 00050 00051 // distanza in cm dell'ostacolo 00052 double fDistance; 00053 00054 00055 // tempo inizio intermedio e fine del timer che misura la distanza con il sensore ultrasuoni 00056 int nTimerStart, nTimerCurrent, nTimerStop, nTimerTillNow; 00057 00058 // Buffer contenente la sinusoide da porre in output come Clacson. 00059 unsigned short usaClacson[CLACSONSAMPLENUM]; 00060 00061 // prototipo di funzione che genera i campioni della sinusoide da utilizzare per la generazione tramite DAC 00062 void CalculateSinewave(void); 00063 00064 00065 // Periodo di generazione campioni in output DeltaT = T/NumSample 00066 double fDeltaTClacsonSound; 00067 double fDeltaTEngineSound; 00068 00069 // amplificazione per i suoni da generare con l'ADC 00070 double fAmpEngineSound; // rumore di Engine 00071 double fAmpClacsonSound; // rumore di Clacson 00072 double fAmpShearSound; // rumore di Shear 00073 00074 // frequenza segnale audio da generare per clacson e motore 00075 double fFreqClacsonSound; 00076 double fFreqEngineSound; 00077 00078 // periodo della sinusoide audio da generare come suono del clacson 00079 double fPeriodClacsonSOund; 00080 00081 // numero di campioni di clacson già inviati in output sul DAC 00082 int nClacsonSampleCount; 00083 // indice dell'array di generazione campioni clacson 00084 int nClacsonSampleIndex; 00085 00086 // indice dell'Array di generazione suoni del motore 00087 volatile int nEngineSampleIndex; 00088 00089 // Flag che decide se generare oppure no il suono del motore. '1'=non generare il suono del motore, '0'=genera il suono del motore 00090 int bEngineSoundStop; 00091 00092 00093 00094 // valore medio della Luminosità su NUMACQUISIZIONI acquisizioni 00095 double fAvgLight; 00096 00097 // valore numerico, di tensione e di luce letto dall'ADC 00098 volatile unsigned short usReadADC; 00099 volatile float fReadVoltage; 00100 00101 // valore di luminosità letto dall'ADC 00102 volatile float fLight; 00103 00104 // posizione del Cofano '0' = chiuso, '1'=aperto. Inizialmente DEVE essere chiuso (cioè '0') 00105 int nPosizioneCofano=0; 00106 00107 00108 // indice per il conteggio dei campioni di luce acquisiti dal fotoresistore 00109 int nLightSampleIndex; 00110 00111 // timer per il calcolo della velocità 00112 Timer TimerHall; 00113 00114 // variabile che conta il numero di fronti si salita del segnale encoder del motore di movimento robot 00115 volatile int nCountRiseEdge; 00116 00117 // variabile che ricorda lo stato di StandBy: '0' = Operativo, '1'=StandBy 00118 int nStandBy; 00119 00120 // variabile che permette di modificare il Gain di tutti i suoni 00121 float fSoundGain=SOUNDGAIN; // inizialmente fissato da un define 00122 00123 // sensore di prossimità. '1' = Sensore Presente, '0' = Sesnore Assente 00124 int nProximitySensorPresent; 00125 00126 00127 //*************************** 00128 // Acquisizione da ADC 00129 //*************************** 00130 00131 // ticker per l'acquisizione dell'onda con ADC 00132 Ticker SamplingTicker; 00133 00134 // carattere in arrivo dal PC ed equivalente numerico 00135 volatile char cReadChar; 00136 volatile int nReadChar; 00137 00138 // flag che diventa true quando si vuole fermare l'acquisizione 00139 volatile bool bStop; 00140 00141 // valore letto dall'ADC e corrispondente in tensione 00142 //volatile unsigned short usReadADC; 00143 //volatile float fReadVoltage; 00144 00145 // valore di temperatura letto dall'ADC 00146 volatile float fTemp; 00147 00148 /*********************************************/ 00149 /*********************************************/ 00150 00151 00152 // pin di pilotaggio Motore DC 00153 DigitalOut OutMotorA (PB_0); 00154 DigitalOut OutMotorB (PC_1); 00155 00156 // Output Digitali usati per i LED 00157 DigitalOut LedWAD (PC_2); 00158 DigitalOut LedWAS (PC_3); 00159 DigitalOut LedWPD (PH_0); 00160 DigitalOut LedWPS (PA_0) ; 00161 DigitalOut LedYAD (PC_9); 00162 DigitalOut LedYAS (PC_8); 00163 DigitalOut LedRPD (PA_13); 00164 DigitalOut LedRPS (PA_14) ; 00165 DigitalOut LedYRAll (PC_7); // Con questo pin si pilotano contemporaneamente i Led: YLD1, YLD2, YLD3, YLD4, YLS1, YLS2, YLS3, YLS4, RPD1, RPS1 00166 AnalogIn InWave(PC_0); 00167 00168 // Input/Output Digitali usati per interfaccia RPI 00169 DigitalIn InShearRPI (PB_11, PullDown); // arriva un segnale alto su questo input quando Raspberry Invia un comando di apertura/chiusura cesoie. Collegato a Raspberry GPIO17 00170 DigitalIn InLightSwitchRPI (PB_9, PullDown); // accende e spegne le Luci rosse e gialle. Collegato al Raspberry GPIO20 00171 DigitalIn InMotorSwitchRPI (PB_8, PullDown); // accende e spegne il motore del Cofano. Collegato al Raspberry GPIO16 00172 //DigitalIn InFutureUse0RPI (PB_7); // usi futuri 0 di comunicazione. Collegato al Raspberry GPIO13 00173 DigitalIn InDontTouchRPI (PB_7, PullDown); // usi futuri 0 di comunicazione. Collegato al Raspberry GPIO13 00174 00175 DigitalIn InFutureUse2RPI (PC_15); // usi futuri 1 di comunicazione. Collegato al Raspberry GPIO25 00176 //DigitalIn InFutureUse1PI (PC_15); // usi futuri 2 di comunicazione. Collegato al Raspberry GPIO12 00177 DigitalIn InStandByRPI (PB_2,PullDown); // StandBy ON/OFF. '1' = robot in StandBy; '0' = robot operativo. Collegato al Raspberry GPIO12 00178 00179 // Input e Output per i sensori e attuatori 00180 AnalogOut OutWave(PA_4); // pin A2 di output per la forma d'onda analogica dedicata al suono 00181 AnalogIn InWaveLight(PA_1); // pin A1 di input per la forma d'onda analogica dedicata alla luminosità 00182 DigitalInOut InOutProxSensor (PC_0, PIN_OUTPUT, PullDown, 0); // Pin di tipo In-Out per la gestione del segnale Sig del Sensore di prossimità a ultrasuoni 00183 00184 InterruptIn InEncoderA(PA_9); // Primo Pin di input dall'encoder ottico collegato al motore per misurare lo spostamento 00185 //InterruptIn InEncoderB(PC_7); // Secondo Pin di input dall'encoder ottico collegato al motore. predisposizione per usi futuri 00186 00187 // Input/Output utilizzati da funzioni default su scheda NUCLEO 00188 DigitalOut led2(LED2);// LED verde sulla scheda. Associato a PA_5 00189 Serial pc(SERIAL_TX, SERIAL_RX); // seriale di comunicazione con il PC. Associati a PA_11 e PA_12 00190 DigitalIn myButton(USER_BUTTON); // pulsante Blu sulla scheda. Associato a PC_13 00191 00192 // input di diagnostica 00193 DigitalIn InDiag1(PA_15,PullUp); // Di Default è a Vcc. Può essere collegato a GND con un ponticello su CN7 pin17-pin19 00194 //DigitalIn InDiag2(PB_11,PullUp); // Di Default è a Vcc. Può essere collegato a GND con un ponticello su CN10 pin18-pin20 00195 00196 00197 //**************************** 00198 // Create the sinewave buffer 00199 //**************************** 00200 void CalculateSinewave(int nOffset, int nAmplitude, double fPhase) 00201 { 00202 // variabile contenente l'angolo in radianti 00203 double fRads; 00204 // indici per i cicli 00205 int nIndex; 00206 // passo in frequenza fissato dal numero di campioni in cui voglio dividere un periodo di sinusoide: DeltaF = 360°/NUMSAMPLE 00207 double fDeltaF; 00208 // angolo per il quale bisogna calcolare il valore di sinusoide: fAngle = nIndex*DeltaF 00209 double fAngle; 00210 00211 fDeltaF = 360.0/CLACSONSAMPLENUM; 00212 for (nIndex = 0; nIndex < CLACSONSAMPLENUM; nIndex++) 00213 { 00214 fAngle = nIndex*fDeltaF; // angolo per il quale bisogna calcolare il campione di sinusoide 00215 fRads = (PI * fAngle)/180.0; // Convert degree in radian 00216 //usaSine[nIndex] = AMPLITUDE * cos(fRads + PHASE) + OFFSET; 00217 usaClacson[nIndex] = fSoundGain * nAmplitude * cos(fRads + fPhase) + nOffset; 00218 } 00219 } 00220 00221 /********************************************************/ 00222 /* Funzione avviata all'inizio come saluto e Benvenuto */ 00223 /********************************************************/ 00224 void WelcomeMessage() 00225 { 00226 // indice per i cicli interni alla funzione 00227 int nIndex; 00228 00229 // indice per l'array di welcome message 00230 int nWelcomeMsgIndex; 00231 // parametri per generare il messaggio di welcome 00232 double fAmpWelcomeSound; 00233 //double fFreqWelcomeSound; 00234 //double fDeltaTWelcomeSound; 00235 00236 //++++++++++++ INIZIO Accendi le Luci in sequenza +++++++++++++++++ 00237 // accendi tutte le luci 00238 LedWAD = 1; 00239 wait_ms(100); 00240 LedWAS = 1; 00241 wait_ms(100); 00242 LedWPD = 1; 00243 wait_ms(100); 00244 LedWPS = 1; 00245 wait_ms(100); 00246 LedYAD = 1; 00247 wait_ms(100); 00248 LedYAS = 1; 00249 wait_ms(100); 00250 LedRPD = 1; 00251 wait_ms(100); 00252 LedRPS = 1; 00253 //++++++++++++ FINE Accendi le Luci in sequenza +++++++++++++++++ 00254 00255 //++++++++++++ INIZIO generazione messaggio di benvenuto +++++++++++++++++ 00256 fAmpWelcomeSound = 1.0; // fissa l'amplificazione per il messaggio di welcome. Valori da 0[min] a 1[max] 00257 //fFreqWelcomeSound=nSamplePerSecWelcome/nUnderSampleFactorWelcome;// campioni per secondo del welcome message da generare = nSamplePerSec/nUnderSampleFactor 00258 //fDeltaTWelcomeSound = (1.0/fFreqWelcomeSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00259 00260 00261 for(nWelcomeMsgIndex=0; nWelcomeMsgIndex < nSampleNumWelcome; nWelcomeMsgIndex++) 00262 { 00263 // mette in output un campione della forma d'onda del welcome message moltiplicato per l'amplificazione fAmp 00264 OutWave.write_u16(naInputSoundWaveWelcome[nWelcomeMsgIndex]*fAmpWelcomeSound*fSoundGain); 00265 00266 // tra un campione e l'altro attendi un periodo pari al periodo di campionamento 00267 //wait(fDeltaTWelcomeSound); 00268 wait_us(37); 00269 } 00270 //++++++++++++ FINE generazione messaggio di benvenuto +++++++++++++++++ 00271 00272 //++++++++++++ INIZIO Spegni le Luci in sequenza +++++++++++++++++ 00273 // spegni le Luci in sequenza 00274 for(nIndex=0; nIndex<3; nIndex++) 00275 { 00276 wait_ms(50); 00277 LedWAD = 1; 00278 wait_ms(50); 00279 LedWAD = 0; 00280 } 00281 for(nIndex=0; nIndex<3; nIndex++) 00282 { 00283 wait_ms(50); 00284 LedWAS = 1; 00285 wait_ms(50); 00286 LedWAS = 0; 00287 } 00288 for(nIndex=0; nIndex<3; nIndex++) 00289 { 00290 wait_ms(50); 00291 LedWPD = 1; 00292 wait_ms(50); 00293 LedWPD = 0; 00294 } 00295 for(nIndex=0; nIndex<3; nIndex++) 00296 { 00297 wait_ms(50); 00298 LedWPS = 1; 00299 wait_ms(50); 00300 LedWPS = 0; 00301 } 00302 for(nIndex=0; nIndex<3; nIndex++) 00303 { 00304 wait_ms(50); 00305 LedYAD = 1; 00306 wait_ms(50); 00307 LedYAD =0; 00308 } 00309 for(nIndex=0; nIndex<3; nIndex++) 00310 { 00311 wait_ms(50); 00312 LedYAS = 1; 00313 wait_ms(50); 00314 LedYAS = 0; 00315 } 00316 for(nIndex=0; nIndex<3; nIndex++) 00317 { 00318 wait_ms(50); 00319 LedRPD = 1; 00320 wait_ms(50); 00321 LedRPD = 0; 00322 } 00323 for(nIndex=0; nIndex<3; nIndex++) 00324 { 00325 wait_ms(50); 00326 LedRPS = 1; 00327 wait_ms(50); 00328 LedRPS = 0; 00329 } 00330 for(nIndex=0; nIndex<3; nIndex++) 00331 { 00332 wait_ms(50); 00333 LedYRAll = 1; 00334 wait_ms(50); 00335 LedYRAll = 0; 00336 } 00337 //++++++++++++ FINE Spegni le Luci in sequenza +++++++++++++++++ 00338 00339 } 00340 00341 /***************************************************************************/ 00342 /* Genera Messaggio di Arrivederci e spegni i LED quando passa in SyandBy */ 00343 /***************************************************************************/ 00344 void FarewellMessage() 00345 { 00346 // indice per l'array di Farewell message 00347 int nFarewellMsgIndex; 00348 // parametri per generare il messaggio di Farewell 00349 double fAmpFarewellSound; 00350 //double fFreqFarewellSound; 00351 //double fDeltaTFarewellSound; 00352 00353 00354 00355 //++++++++++++ INIZIO generazione messaggio di Arrivederci +++++++++++++++++ 00356 fAmpFarewellSound = 1.0; // fissa l'amplificazione per il messaggio di Farewell. Valori da 0[min] a 1[max] 00357 //fFreqFarewellSound=nSamplePerSecFarewell/nUnderSampleFactorFarewell;// campioni per secondo del Farewell message da generare = nSamplePerSec/nUnderSampleFactor 00358 //fDeltaTFarewellSound = (1.0/fFreqFarewellSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00359 00360 00361 for(nFarewellMsgIndex=0; nFarewellMsgIndex < nSampleNumFarewell; nFarewellMsgIndex++) 00362 { 00363 // mette in output un campione della forma d'onda del Farewell message moltiplicato per l'amplificazione fAmp 00364 OutWave.write_u16(naInputSoundWaveFarewell[nFarewellMsgIndex]*fAmpFarewellSound*fSoundGain); 00365 00366 // tra un campione e l'altro attendi un periodo pari al periodo di campionamento 00367 //wait(fDeltaTFarewellSound); 00368 wait_us(57); 00369 } 00370 //++++++++++++ FINE generazione messaggio di Arrivederci +++++++++++++++++ 00371 00372 00373 00374 00375 00376 //++++++++++++ INIZIO Spegni tutti i LED in sequenza +++++++++++++++++ 00377 // spegni tutti i LED 00378 LedWAD = 0; 00379 wait_ms(100); 00380 LedWAS = 0; 00381 wait_ms(100); 00382 LedWPD = 0; 00383 wait_ms(100); 00384 LedWPS = 0; 00385 wait_ms(100); 00386 LedYAD = 0; 00387 wait_ms(100); 00388 LedYAS = 0; 00389 wait_ms(100); 00390 LedRPD = 0; 00391 wait_ms(100); 00392 LedRPS = 0; 00393 wait_ms(100); 00394 LedYRAll = 0; 00395 //++++++++++++ FINE Spegni tutti i LED in sequenza +++++++++++++++++ 00396 00397 } 00398 00399 /****************************************/ 00400 /*Genera messaggio temperatura*/ 00401 /***************************************/ 00402 void Sampling() 00403 { 00404 // indice per l'array di DontTouch message 00405 int nDontTouchMsgIndex; 00406 // parametri per generare il messaggio di DontTouch 00407 double fAmpDontTouchSound; 00408 //double fFreqDontTouchSound; 00409 //double fDeltaTDontTouchSound; 00410 //++++++++++++ INIZIO generazione messaggio di Don't Touch +++++++++++++++++ 00411 fAmpDontTouchSound = 1.0; // fissa l'amplificazione per il messaggio di DontTouch. Valori da 0[min] a 1[max] 00412 //fFreqDontTouchSound=nSamplePerSecDontTouch/nUnderSampleFactorDontTouch;// campioni per secondo del DontTouch message da generare = nSamplePerSec/nUnderSampleFactor 00413 //fDeltaTDontTouchSound = (1.0/fFreqDontTouchSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00414 00415 // indice per i cicli 00416 int nIndex; 00417 // valore medio della temperatura su NUMACQUISISIONI acquisizioni 00418 float fAvgTemp; 00419 00420 // se è stato inviato il comando Stop, non fare niente fino a nuovo comando 00421 if(bStop) 00422 { 00423 } 00424 else // se non è stato inviato il comando di bStop continua 00425 { 00426 // inizializza il valore medio della temperatura 00427 fAvgTemp=0.0; 00428 for(nIndex=0; nIndex < NUMSAMPLE; nIndex++) 00429 { 00430 // acquisisce dato da ADC 00431 usReadADC = InWave.read_u16(); 00432 fReadVoltage=(usReadADC*3.3)/65535.0; // converte in Volt il valore numerico letto dall'ADC 00433 //fReadVoltage=InWave.read(); // acquisisce il valore dall'ADC come valore di tensione in volt 00434 fTemp= ((fReadVoltage-0.25)*100.0)/(3.05-0.25); //applica la formula della retta tra i valori minimo e massimo del sensore 00435 fAvgTemp+=fTemp; 00436 } 00437 // calcola valore medio su NUMSAMPLE acquisizioni 00438 fAvgTemp/= NUMSAMPLE; 00439 00440 // accendi LED in base a superamento soglie 00441 if (fAvgTemp <= 30.0) 00442 { 00443 // mette in output un campione della forma d'onda del DontTouch message moltiplicato per l'amplificazione fAmp 00444 OutWave.write_u16(naInputSoundWaveDontTouch[nDontTouchMsgIndex]*fAmpDontTouchSound*fSoundGain); 00445 00446 // tra un campione e l'altro attendi un periodo pari al periodo di campionamento 00447 //wait(fDeltaTDontTouchSound); 00448 wait_us(57); 00449 } 00450 else 00451 { 00452 } 00453 // invia il dato al PC 00454 //pc.printf("\n\r--- Voltage= %.1f [Volt]; Temperature= %.1f [Celsius] ---\n\r", fReadVoltage, fTemp); 00455 pc.printf("\n\r--- Digital= %d [Volt]; Temperature= %.2f [Celsius] ---\n\r", usReadADC, fTemp); 00456 00457 00458 00459 /* 00460 // prepara il pacchetto di dati acquisiti da restituire al PC 00461 caTxPacket[nSampleInCount]= (char)(usReadADC&0xFF); 00462 //+++caTxPacket[nSampleInCount]= 'a'; 00463 nSampleInCount++; 00464 caTxPacket[nSampleInCount] = (char)((usReadADC>>8)&0xFF); 00465 //++++caTxPacket[nSampleInCount]= 'b'; 00466 */ 00467 00468 } 00469 } 00470 00471 00472 /**************************************/ 00473 /* Genera Messaggio di Don't Touch Me */ 00474 /**************************************/ 00475 void DontTouchMessage() 00476 { 00477 // indice per l'array di DontTouch message 00478 int nDontTouchMsgIndex; 00479 // parametri per generare il messaggio di DontTouch 00480 double fAmpDontTouchSound; 00481 //double fFreqDontTouchSound; 00482 //double fDeltaTDontTouchSound; 00483 00484 00485 00486 //++++++++++++ INIZIO generazione messaggio di Don't Touch +++++++++++++++++ 00487 fAmpDontTouchSound = 1.0; // fissa l'amplificazione per il messaggio di DontTouch. Valori da 0[min] a 1[max] 00488 //fFreqDontTouchSound=nSamplePerSecDontTouch/nUnderSampleFactorDontTouch;// campioni per secondo del DontTouch message da generare = nSamplePerSec/nUnderSampleFactor 00489 //fDeltaTDontTouchSound = (1.0/fFreqDontTouchSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00490 00491 00492 for(nDontTouchMsgIndex=0; nDontTouchMsgIndex < nSampleNumDontTouch; nDontTouchMsgIndex++) 00493 { 00494 // mette in output un campione della forma d'onda del DontTouch message moltiplicato per l'amplificazione fAmp 00495 OutWave.write_u16(naInputSoundWaveDontTouch[nDontTouchMsgIndex]*fAmpDontTouchSound*fSoundGain); 00496 00497 // tra un campione e l'altro attendi un periodo pari al periodo di campionamento 00498 //wait(fDeltaTDontTouchSound); 00499 wait_us(57); 00500 } 00501 //++++++++++++ FINE generazione messaggio di Don't Touch +++++++++++++++++ 00502 00503 //++++++++++++ INIZIO ACCENDI tutti i LED in sequenza e spegnili subito dopo +++++++++++++++++ 00504 // spegni tutti i LED 00505 LedWAD = 1; 00506 wait_ms(50); 00507 LedWAS = 1; 00508 wait_ms(50); 00509 LedWPD = 1; 00510 wait_ms(50); 00511 LedWPS = 1; 00512 wait_ms(50); 00513 LedYAD = 1; 00514 wait_ms(50); 00515 LedYAS = 1; 00516 wait_ms(50); 00517 LedRPD = 1; 00518 wait_ms(50); 00519 LedRPS = 1; 00520 wait_ms(50); 00521 LedYRAll = 1; 00522 wait(1); 00523 LedWAD = 0; 00524 LedWAS = 0; 00525 LedWPD = 0; 00526 LedWPS = 0; 00527 LedYAD = 0; 00528 LedYAS = 0; 00529 LedRPD = 0; 00530 LedRPS = 0; 00531 LedYRAll = 0; 00532 //++++++++++++ FINE ACCENDI tutti i LED in sequenza e spegnili subito dopo +++++++++++++++++ 00533 00534 } 00535 00536 00537 00538 /***********************************************************************/ 00539 /* Genera il suono di una motosega. */ 00540 /* Attivo quando arriva il comando di spostamento Cesoie da Raspberry */ 00541 /***********************************************************************/ 00542 void ShearSoundGeneration() 00543 { 00544 // indice per l'array di suono Shear 00545 int nShearSoundIndex; 00546 // parametri per generare il messaggio di shear 00547 double fAmpShearSound; 00548 double fFreqShearSound; 00549 double fDeltaTShearSound; 00550 00551 //++++++++++++ INIZIO generazione suono di motosega +++++++++++++++++ 00552 fAmpShearSound = 1.0; // fissa l'amplificazione per il suono di Shear. Valori da 0[min] a 1[max] 00553 fFreqShearSound=nSamplePerSecShear/nUnderSampleFactorShear;// campioni per secondo del Shear da generare = nSamplePerSec/nUnderSampleFactor 00554 fDeltaTShearSound = (1.0/fFreqShearSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00555 00556 00557 for(nShearSoundIndex=0; nShearSoundIndex < nSampleNumShear; nShearSoundIndex++) 00558 { 00559 // mette in output un campione della forma d'onda del suono di Shear, moltiplicato per l'amplificazione fAmp 00560 OutWave.write_u16(naInputSoundWaveShear[nShearSoundIndex]*fAmpShearSound*fSoundGain); 00561 00562 // tra un campione e l'altro attendi un periodo pari al periodo di campionamento 00563 wait(fDeltaTShearSound); 00564 } 00565 //++++++++++++ FINE generazione suono di motosega +++++++++++++++++ 00566 } 00567 00568 00569 00570 /***********************************************************************/ 00571 /* generazione suoni con i sample da file di campioni in SoundSample.h */ 00572 /***********************************************************************/ 00573 void SampleOut() 00574 { 00575 // interrompi il suono del motore per generare altri suoni. '1' = interrompi i suoni 00576 if(bEngineSoundStop == 0) 00577 { 00578 // mette in output un campione della forma d'onda del rumore motore moltiplicato per l'amplificazione fAmp 00579 OutWave.write_u16(naInputSoundWave[nEngineSampleIndex]*fAmpEngineSound*fSoundGain); 00580 // incrementa l'indice del campione in output, nSampleNum è il numero dei campioni nle file Sound.h 00581 nEngineSampleIndex++; 00582 if(nEngineSampleIndex >= nSampleNum) 00583 nEngineSampleIndex=0; 00584 } 00585 } 00586 00587 00588 /**************************************************************************************/ 00589 /* Routine di gestione Interrupt associata al fronte di salita del segnale di encoder */ 00590 /**************************************************************************************/ 00591 void riseEncoderIRQ() 00592 { 00593 nCountRiseEdge++; 00594 } 00595 00596 /********/ 00597 /* Main */ 00598 /********/ 00599 int main() 00600 { 00601 // configura velocità della comunicazione seriale su USB-VirtualCom e invia messaggio di benvenuto 00602 pc.baud(921600); //921600 bps 00603 00604 // definisci il mode del segnale digitale di EncoderA 00605 InEncoderA.mode(PullUp); 00606 00607 // Associa routine di Interrup all'evento fronte di salita del segnale di encoder 00608 InEncoderA.rise(&riseEncoderIRQ); 00609 00610 // abilita interrupt sul segnale di encoder per contare il numero di impulsi e quindi verificare se il robot si muove 00611 InEncoderA.enable_irq(); 00612 00613 // definisci il mode del segnale di InStandBy da RPI ('0' = operativo; '1' = StandBy) 00614 InStandByRPI.mode(PullDown); 00615 InShearRPI.mode(PullDown); // arriva un segnale alto su questo input quando Raspberry Invia un comando di apertura/chiusura cesoie. Collegato a Raspberry GPIO17 00616 InLightSwitchRPI.mode(PullDown); // arriva un segnale alto su questo input quando Raspberry Invia un comando che accende e spegne le Luci rosse e gialle. Collegato al Raspberry GPIO20 00617 InMotorSwitchRPI.mode(PullDown); // arriva un segnale alto su questo input quando Raspberry Invia un comando che accende e spegne il motore del Cofano. Collegato al Raspberry GPIO16 00618 InDontTouchRPI.mode(PullDown); // arriva un segnale alto su questo input quando Raspberry Invia un comando per generare messaggio Audio "don't Touch me" GPIO13 00619 00620 00621 00622 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00623 //+++++++++++++++++++++++++++++++++++++ INIZIO CICLO OPERATIVO ++++++++++++++++++++++++++++++++++ 00624 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00625 00626 //+++++++++++ inizializza Gain dei suoni +++++++++++++ 00627 fSoundGain = SOUNDGAIN; // inizialmente fissato a SOUNDGAIN che può essere fissato a 0 per modalità di debug 00628 00629 //+++++++++++++ INIZIO Genera Sinusoide ++++++++++++++++++ 00630 fFreqClacsonSound = 550.0; // frequenza in Hz del tono del Clacson da generare 00631 fAmpClacsonSound = 1.0; // coefficiente per il quale viene moltiplicato l'ampiezza massima del tono da generare 00632 fDeltaTClacsonSound = 1.0/(fFreqClacsonSound*CLACSONSAMPLENUM); // intervallo di tempo tra un campione e l'altro, per generare la frequenza desiderata 00633 CalculateSinewave(AMPLITUDE, (AMPLITUDE*fAmpClacsonSound*fSoundGain), (PI/2.0)); // generazione della sinusoide con valori nominali 00634 //+++++++++++++ FINE Genera Sinusoide +++++++++++++++++++++ 00635 00636 // avvia routine di saluto di benvenuto 00637 bEngineSoundStop = 1; // per generare il messaggio di benvenuto il suono del motore è spento 00638 WelcomeMessage(); 00639 bEngineSoundStop = 0; // riattiva il suono del motore 00640 00641 //+++++++ INIZIO avvio rumore del motore a frequenza da fermo ++++++++++++++++++++++++++++++++++++++++++++++++ 00642 fAmpEngineSound = 1.0; // fissa l'amplificazione per il rumore motore. Valori da 0[min] a 1[max] 00643 fFreqEngineSound=nSamplePerSec/nUnderSampleFactor;// campioni per secondo del rumore motore da generare = nSamplePerSec/nUnderSampleFactor 00644 fDeltaTEngineSound = (1.0/fFreqEngineSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00645 nEngineSampleIndex =0; // Avvia indice di generazione suono motore 00646 SampleOutTicker.attach(&SampleOut,fDeltaTEngineSound); // avvia generazione 00647 //+++++++ FINE avvio rumore del motore a frequenza da fermo ++++++++++++++++++++++++++++++++++++++++++++++++++ 00648 00649 //++++++++ INIZIO inizializza variabili +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00650 nEngineSampleIndex =0; // avvia l'indice di generazione suoni 00651 nCountRiseEdge=0; // azzera il contatore dei fronti di salita del segnale di encoder. Saranno contati nella IRQ legata a InEncoderA 00652 bEngineSoundStop =0; // inizialmente il suono del motore è generato 00653 nPosizioneCofano=0; // inizializza la posizione del cofano chiuso 00654 nStandBy=0; // iniazializza la modalità StandBy/Operation del robot. nStandBy=0 : modalità Operation 00655 //++++++++ FINE inizializza variabili +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00656 00657 00658 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00659 //+++++++++++++++++++++++++++++++++++++ INIZIO CICLO TEST ++++++++++++++++++++++++++++++++ 00660 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00661 /* 00662 while(true) 00663 { 00664 } //while(true) 00665 */ 00666 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00667 //+++++++++++++++++++++++++++++++++++++ FINE CICLO TEST ++++++++++++++++++++++++++++++++ 00668 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00669 00670 00671 00672 00673 00674 00675 00676 00677 // Fissa come Output il pin InOutProxSensor 00678 while(true) 00679 { 00680 if(InStandByRPI == 0) 00681 { 00682 // abilita interrupt sul segnale di encoder per contare il numero di impulsi e quindi verificare se il robot si muove 00683 InEncoderA.enable_irq(); 00684 00685 // se appena uscito dalla modalità di StandBy, è ancora nStandBy = 1, emetti messaggio di benvenuto 00686 if(nStandBy == 1) 00687 { 00688 00689 // blocca il suono del motore per emettere messaggio di benvenuto 00690 bEngineSoundStop=1; 00691 00692 // se modalità StandBy = OFF, riattiva audio; 00693 fSoundGain = SOUNDGAIN; 00694 00695 00696 //Genera messaggio di benvenuto 00697 WelcomeMessage(); 00698 00699 // rispristina il suono del motore 00700 bEngineSoundStop=0; 00701 } 00702 00703 // imposta lo stato di StandBy OFF 00704 nStandBy = 0; 00705 //++++++++++ INIZIO calcola spostamento con encoder sul motore +++++++++++++++++ 00706 // abilita interrupt sul segnale di encoder per contare il numero di impulsi e quindi verificare se il robot si muove 00707 //InEncoderA.enable_irq(); 00708 00709 // conta il numero di impulsi del segnale di encoder che si verificano in un timer pari a 500ms 00710 TimerHall.start(); 00711 nTimerStart=TimerHall.read_ms(); 00712 00713 // per 100ms verifica se ci sono impulsi sull'encoder. Gli impulsi vengono contati lungo tutto il ciclo ma se il ciclo è attraversato troppo rapidamente rischio di non contaniente e aggiungo questo ritarda. 00714 while( (nTimerCurrent-nTimerStart) < 50) // attende il passare di 100ms 00715 { 00716 nTimerCurrent=TimerHall.read_ms(); 00717 // pc.printf("CounterTimer= %d\r\n", (nTimerCurrent-nTimerStart)); 00718 } 00719 TimerHall.stop(); 00720 //InEncoderA.disable_irq(); 00721 //++++++++++ FINE calcola spostamento con encoder sul motore +++++++++++++++++ 00722 00723 //++++++++++ INIZIO genera diverso suono con motore fermo e in movimento +++++++++++++++++ 00724 // se nella IRQ sono stati contati fronti di salita del dell'encoder, il robot si sta muovendo 00725 if(nCountRiseEdge != 0) 00726 //if(InDiag1==1) 00727 { 00728 // sono stati contati impulsi di encoder, il robot si sta muovendo 00729 fDeltaTEngineSound = (0.5/fFreqEngineSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00730 SampleOutTicker.attach(&SampleOut,fDeltaTEngineSound); // avvia generazione 00731 //pc.printf("\r\nIn Movimento \r\n"); //Diagnostica 00732 00733 // se il robot si muove, accendi LED indicatori di movimento 00734 LedYAD = 1; 00735 LedYAS = 1; 00736 LedRPD = 1; 00737 LedRPS = 1; 00738 } 00739 else 00740 { 00741 // se non ci sono stati impulsi di encoder, il robot è fermo, genera rumore del motore fermo 00742 fDeltaTEngineSound = (1.0/fFreqEngineSound); // fFreq dipende dal periodo di campionamento e dal fattore di sottocampionamento 00743 SampleOutTicker.attach(&SampleOut,fDeltaTEngineSound); // avvia generazione 00744 //pc.printf("\r\nFermo \r\n"); //Diagnostica 00745 00746 // se il robot è fermo, spegni LED indicatori di movimento 00747 LedYAD = 0; 00748 LedYAS = 0; 00749 LedRPD = 0; 00750 LedRPS = 0; 00751 } 00752 // riazzera il contatore di impulsi di encoder. Questo contatore viene incrementato nella rouine di interrupt 00753 nCountRiseEdge=0; 00754 //++++++++++ FINE genera diverso suono con motore fermo e in movimento +++++++++++++++++ 00755 00756 //++++++++++++ INIZIO Misura della Luminosità e accensione LED Bianchi ++++++++++++++ 00757 // inizializza il valore medio della Luminosità 00758 fAvgLight=0.0; 00759 for(nLightSampleIndex=0; nLightSampleIndex < NUMLIGHTSAMPLE; nLightSampleIndex++) 00760 { 00761 // acquisisce dato da ADC 00762 usReadADC = InWaveLight.read_u16(); 00763 fReadVoltage=(usReadADC*3.3)/65535.0; // converte in Volt il valore numerico letto dall'ADC 00764 //fReadVoltage=InWave.read(); // acquisisce il valore dall'ADC come valore di tensione in volt 00765 fLight= fReadVoltage; //ATTENZIONE Visualizza il valore grezzo letto dall'ADC 00766 fAvgLight+=fLight; 00767 } 00768 // calcola valore medio su NUMSAMPLE acquisizioni 00769 fAvgLight/= NUMLIGHTSAMPLE; 00770 00771 // Accendi/Spegni i LED Bianchi se il valore medio della luminosità è sotto/sopra soglia 00772 if(fAvgLight < SOGLIALUCIMIN) 00773 { 00774 // Accendi LED Bianchi 00775 //led2 = 1; 00776 LedWAD = 1; 00777 LedWAS = 1; 00778 LedWPD = 1; 00779 LedWPS = 1; 00780 } 00781 else 00782 { 00783 if(fAvgLight > SOGLIALUCIMAX) 00784 { 00785 // Spegni LED Bianchi 00786 //led2 = 0; 00787 LedWAD = 0; 00788 LedWAS = 0; 00789 LedWPD = 0; 00790 LedWPS = 0; 00791 } 00792 } 00793 00794 // invia il dato al PC 00795 //pc.printf("\n\r--- Digital= %d [Volt]; Brightness= %.2f ---\n\r", usReadADC, fAvgLight); 00796 //++++++++++++ FINE Misura della Luminosità e accensione LED ++++++++++++++ 00797 00798 //++++++++++++++ INIZIO Acquisisci distanza ostacoli +++++++++ 00799 //inizializza misura di distanza 00800 fDistance=0.0; 00801 // Fissa come Output il pin InOutProxSensor 00802 InOutProxSensor.output(); 00803 // Poni 'L' sul Pin e mantienilo per qualche microsecondo 00804 InOutProxSensor.write(0); 00805 wait_us(5); 00806 // Poni 'H' sul Pin e mantienilo per qualche microsecondo 00807 InOutProxSensor.write(1); 00808 wait_us(10); 00809 // Poni 'L' sul Pin e mantienilo per qualche microsecondo 00810 InOutProxSensor.write(0); 00811 // Attendi assestamento e Fissa come Input il pin InOutProxSensor 00812 wait_us(5); 00813 InOutProxSensor.input(); 00814 InOutProxSensor.mode(PullDown); // se non è presente il sensore, il pin rimane a '0' 00815 00816 // attende la risposta del sensore di prossimità per un tempo fissato da TIMEOUTPROXSENSOR. Dopo tale tempo dichiara inesistente il sensore 00817 TimerProxSensor.start(); 00818 nTimerStart = TimerProxSensor.read_us(); 00819 nTimerTillNow=(TimerProxSensor.read_us()-nTimerStart); 00820 while((InOutProxSensor ==0) && (nTimerTillNow< TIMEOUTPROXSENSOR)) 00821 { 00822 nTimerCurrent = TimerProxSensor.read_us(); 00823 nTimerTillNow=nTimerCurrent-nTimerStart; 00824 led2=1; // se rimane nel while il LED rimane acceso 00825 //pc.printf("sono qui 2 \r\n"); // Diagnotica 00826 } 00827 TimerProxSensor.stop(); // spegne il timer che serve per misurare il timeout quando assente il sensore di prossimità 00828 //pc.printf("\r\nUscita dal while, nTimerTillNow = %d\r\n", nTimerTillNow); // Diagnostica 00829 // se nTimerTillNow è inferiore al TIMEOUT, il sensore è presente e quindi misura la distanza dell'ostacolo 00830 if(nTimerTillNow < TIMEOUTPROXSENSOR) 00831 { 00832 // riattiva il timer per misurare la distanza dell'ostacolo 00833 TimerProxSensor.start(); 00834 nTimerStart = TimerProxSensor.read_us(); 00835 while(InOutProxSensor == 1) 00836 { 00837 led2=1; // se rimane nel while il LED rimane acceso 00838 } 00839 TimerProxSensor.stop(); 00840 nTimerStop = TimerProxSensor.read_us(); 00841 00842 //pc.printf("\r\nSensore Presente, nTimerTillNow = %d\r\n", nTimerTillNow); // Diagnostica 00843 00844 // velocità del suono = 343 [m/s] = 0.0343 [cm/us] = 1/29.1 [cm/us] 00845 // tempo di andata e ritorno del segnale [us] = (TimerStop-TimerStart)[us]; per misurare la distanza bisogna dividere per due questo valore 00846 // distanza dell'ostacolo [cm] = (TimerStop-TimerStart)/2 [us] * 1/29.1[cm/us] 00847 fDistance = (nTimerStop-nTimerStart)/58.2; 00848 // invia il dato al PC 00849 //pc.printf("distanza dell'ostacolo = %f0.2\r\n", fDistance); // Diagnostica 00850 } 00851 00852 //++++++++++++++ FINE Acquisisci distanza ostacoli +++++++++ 00853 //++++++++++++++ INIZIO Suona Clacson +++++++++ 00854 //escludi le misure oltre il max 00855 //if(myButton == 0) fDistance = 20; //Diagnostica 00856 if((fDistance <= 50.0) && (fDistance >= 3)) 00857 //if(InDiag1 == 1) 00858 { 00859 // SUONA IL CLACSON se l'ostacolo si trova ad una distanza tra 10 e 22cm oppure emetti messaggio DON'T TOUCH ME se l'ostacolo è più vicino di 10cm 00860 if(fDistance < 30) 00861 { 00862 // se la distanza a cui si trova l'ostacolo è inferiore a 10cm, genera messaggio "Don't touch me" 00863 if(fDistance < 10) 00864 { 00865 // funzione di generazione messaggio DOn't Touch me 00866 bEngineSoundStop=1; // disattiva suono del motore 00867 DontTouchMessage(); // genera messaggio DON'T TOUCH ME 00868 bEngineSoundStop=0; // riattiva suono del motore 00869 } 00870 else 00871 { 00872 // L'ostacolo si trova tra 10cm e 22cm, GENERA SUONO DEL CLACSON 00873 // blocca altri suoni quando genera suono del clacson 00874 bEngineSoundStop=1; 00875 // INIZIO generazione tono 00876 nClacsonSampleIndex=0; 00877 // Genera il suono del clacson 00878 for(nClacsonSampleCount=0; nClacsonSampleCount<7000; nClacsonSampleCount++) 00879 { 00880 OutWave.write_u16(usaClacson[nClacsonSampleIndex]); //max 32767 00881 //OutWave.write_u16(32767); //uscita analogica per scopi diagnostici 00882 00883 wait(fDeltaTClacsonSound); 00884 00885 // genera ciclicamente 00886 nClacsonSampleIndex++; 00887 if(nClacsonSampleIndex >= CLACSONSAMPLENUM) 00888 { 00889 nClacsonSampleIndex=0; 00890 } 00891 // a metà genera un wait per doppio clacson 00892 if(nClacsonSampleCount == 2000) 00893 { 00894 wait_ms(100); 00895 } 00896 00897 } 00898 //assicurati di inviare 0 come ultimo campione per spegnere l'amplificatore e non dissipare inutilmente corrente 00899 OutWave.write_u16(0); 00900 00901 // sblocca altri suoni dopo aver generato suono del clacson 00902 bEngineSoundStop=0; 00903 }// if(fDistance < 10) 00904 00905 } // if(fDistance < 22)) 00906 00907 } // if( (fDistance < 50) && (fDistance > 3)) 00908 //++++++++++++++ FINE Suona Clacson +++++++++ 00909 00910 //++++++++++++++ INIZIO pilotaggio motore cofano +++++++++++++++++++ 00911 if((InMotorSwitchRPI==1) && (nPosizioneCofano ==0)) 00912 //if((myButton==1) && (nPosizioneCofano ==0)) 00913 { 00914 //Ferma motore 00915 OutMotorA=0; 00916 OutMotorB=0; 00917 //pc.printf("Stop motore; OutA OutB = 00\r\n"); 00918 wait_ms(10); 00919 00920 //Ferma motore 00921 OutMotorA=0; 00922 OutMotorB=1; 00923 //pc.printf("Stop motore; OutA OutB = 01\r\n"); 00924 wait_ms(10); 00925 00926 // Ruota Right 00927 OutMotorA=1; 00928 OutMotorB=1; 00929 //pc.printf("Ruota Right; OutA OutB = 11\r\n"); 00930 wait_ms(710); 00931 00932 // Ferma Motore 00933 OutMotorA=0; 00934 OutMotorB=1; 00935 //pc.printf("Stop Motore; OutA OutB = 01\r\n"); 00936 wait_ms(10); 00937 00938 //Ferma motore 00939 OutMotorA=0; 00940 OutMotorB=0; 00941 //pc.printf("Stop motore; OutA OutB = 00\r\n"); 00942 wait_ms(10); 00943 // cambia posizione del cofano. E' Stato Aperto 00944 nPosizioneCofano = 1; 00945 } 00946 // se arriva comando di chiusura cofano & il cofano è aperto, muovi motore 00947 //if((myButton==0) && (nPosizioneCofano == 1)) 00948 if((InMotorSwitchRPI==0) && (nPosizioneCofano ==1)) 00949 { 00950 //pc.printf("\r\nCofano aperto & comando di chiusura\r\n"); 00951 00952 //Ferma motore 00953 OutMotorA=0; 00954 OutMotorB=0; 00955 //pc.printf("Stop motore; OutA OutB = 00\r\n"); 00956 wait_ms(10); 00957 00958 // Ruota Left 00959 OutMotorA=1; 00960 OutMotorB=0; 00961 //pc.printf("Ruota Left; OutA OutB = 10\r\n"); 00962 wait_ms(730); 00963 00964 //Ferma motore 00965 OutMotorA=0; 00966 OutMotorB=0; 00967 //pc.printf("Stop motore; OutA OutB = 00\r\n"); 00968 wait_ms(10); 00969 00970 // cambia posizione del cofano. E' Stato Chiuso 00971 nPosizioneCofano = 0; 00972 } 00973 //++++++++++++++ FINE Pilotaggio Motore Cofano +++++++++++++ 00974 00975 //++++++++++++++ INIZIO Accensione LED da comando Raspberry +++++++ 00976 if(InLightSwitchRPI ==1) 00977 { 00978 // accendi i LED di abbellimento 00979 LedYRAll = 1; 00980 } 00981 else 00982 { 00983 // spegni i LED di abbellimento 00984 LedYRAll = 0; 00985 00986 } 00987 //++++++++++++++ FINE Accensione LED da comando Raspberry +++++++ 00988 00989 //++++++++++++++ INIZIO Genera Suono MOTOSEGA quando arriva comando di movimento Cesoie da Raspberry +++++++++ 00990 if(InShearRPI == 1) 00991 { 00992 // funzione di generazione suono motosega 00993 bEngineSoundStop=1; // disattiva suono del motore 00994 ShearSoundGeneration(); 00995 bEngineSoundStop=0; // riattiva suono del motore 00996 } 00997 //++++++++++++++ FINE Genera Suono MOTOSEGA quando arriva comando di movimento Cesoie da Raspberry +++++++++ 00998 00999 //++++++++++++++ INIZIO Genera Messaggio Audio "Don't Touch Me" quando arriva il comando da Raspberry +++++++++ 01000 if (InDontTouchRPI == 1) 01001 { 01002 // funzione di generazione messaggio DOn't Touch me 01003 bEngineSoundStop=1; // disattiva suono del motore 01004 DontTouchMessage(); 01005 bEngineSoundStop=0; // riattiva suono del motore 01006 } 01007 //++++++++++++++ Fine Genera Messaggio Audio "Don't Touch Me" quando arriva il comando da Raspberry +++++++++ 01008 01009 01010 }// if(InStandByRPI == 0) 01011 else 01012 { 01013 01014 // ricevuto da RPI, il comando di StandBy = ON 01015 // ricevuto il comando di StandBy (InStandBy == 1) 01016 01017 // la prima volta che entra in questo else, la variabile di stato nStandBy è '0'. Solo la prima volta Genera il messaggio di arrivederci 01018 if(nStandBy == 0) 01019 { 01020 // blocca il suono del motore per emettere messaggio di arrivederci 01021 bEngineSoundStop=1; 01022 01023 //Genera messaggio di arrivederci 01024 FarewellMessage(); 01025 01026 // rispristina il suono del motore 01027 bEngineSoundStop=0; 01028 01029 // cambia lo stato dello StandBy 01030 nStandBy = 1; 01031 } 01032 01033 // se modalità StandBy = ON, disattiva audio; 01034 fSoundGain = 0.0; 01035 } // fine if(nStandByRPI == 1) 01036 01037 } // fine ciclo while(true) 01038 01039 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 01040 //+++++++++++++++++++++++++++++++++++++ FINE CICLO OPERATIVO++++++++++++++++++++++++++++++++ 01041 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 01042 01043 } 01044
Generated on Sun Aug 14 2022 11:03:17 by
1.7.2