]> git.piffa.net Git - rover/commitdiff
Merge branch 'andrea' with motors functions
authorAndrea Manni <andrea@piffa.net>
Mon, 3 Apr 2017 09:56:42 +0000 (11:56 +0200)
committerAndrea Manni <andrea@piffa.net>
Mon, 3 Apr 2017 09:56:42 +0000 (11:56 +0200)
15 files changed:
libraries/rover/rover.cpp
libraries/rover/rover.h
prototypes/motor/README [new file with mode: 0644]
prototypes/motor/drive/drive.ino [new file with mode: 0644]
prototypes/motor/motor_func/motor_func.ino [new file with mode: 0644]
prototypes/motor/motor_pwm/motor_pwm.ino [new file with mode: 0644]
prototypes/motor/motors/motors.ino [new file with mode: 0644]
prototypes/motor/single/single.ino [new file with mode: 0644]
prototypes/servo/README [new file with mode: 0644]
prototypes/servo/base/base.ino [new file with mode: 0644]
prototypes/servo/rotation/rotation.ino [new file with mode: 0644]
prototypes/servo/rotation_func/rotation_func.ino [new file with mode: 0644]
prototypes/servo/rotation_lib/rotation_lib.ino [new file with mode: 0644]
prototypes/ultra/check_func/check_func.ino [new file with mode: 0644]
prototypes/ultra/ultrasonic_distance_simple/ultrasonic_distance_simple.ino [new file with mode: 0644]

index 363d5909e91e2a73d65a4505582ac0949fc6ff53..1b6c88e16c32d3c86a55c2ed2d9932205a55f2aa 100644 (file)
@@ -13,6 +13,94 @@ Licenza:    GPLv3
 
 #define dEBUG
 
-//////////////////
+// Configurazione con OUTPUT digitali
+// motor one
+const int enA = 6;
+const int in1 = 7;
+const int in2 = 8;
+byte speedA = 255;
+// motor two
+const int enB = 5;
+const int in3 = 4;
+const int in4 = 3;
+byte speedB = 255;
 // Funzioni
 
+void abilita() {
+// Abilita i PINs come OUTPUTS
+    pinMode(enA, OUTPUT);
+    pinMode(in1, OUTPUT);
+    pinMode(in2, OUTPUT);
+    pinMode(enB, OUTPUT);
+    pinMode(in3, OUTPUT);
+    pinMode(in4, OUTPUT);
+}
+
+
+// MotorA
+void forwardA() {
+    // Avanzamento motore
+    digitalWrite(in1,LOW);
+    digitalWrite(in2,HIGH);
+    analogWrite(enA,speedA);
+}
+
+void forwardA(byte speedA) {
+    // Avanzamento motore
+    digitalWrite(in1,LOW);
+    digitalWrite(in2,HIGH);
+    analogWrite(enA,speedA);
+}
+
+void backwardA() {
+    // Reverse motore
+    digitalWrite(in2,LOW);
+    digitalWrite(in1,HIGH);
+    analogWrite(enA,speedA);
+}
+
+void backwardA(byte speedA) {
+    // Reverse motore
+    digitalWrite(in2,LOW);
+    digitalWrite(in1,HIGH);
+    analogWrite(enA,speedA);
+}
+
+void stopA() {
+    // Stop
+    digitalWrite(enA,LOW);
+}
+
+// MotorB
+void forwardB() {
+    // Avanzamento motore
+    digitalWrite(in3,LOW);
+    digitalWrite(in4,HIGH);
+    analogWrite(enB,speedB);
+}
+
+void forwardB(byte speedB) {
+    // Avanzamento motore
+    digitalWrite(in3,LOW);
+    digitalWrite(in4,HIGH);
+    analogWrite(enB,speedB);
+}
+
+void backwardB() {
+    // Reverse motore
+    digitalWrite(in4,LOW);
+    digitalWrite(in3,HIGH);
+    analogWrite(enB,speedB);
+}
+
+void backwardB(byte speedB) {
+    // Reverse motore
+    digitalWrite(in4,LOW);
+    digitalWrite(in3,HIGH);
+    analogWrite(enB,speedB);
+}
+
+void stopB() {
+    // Stop
+    digitalWrite(enB,LOW);
+}
index 371023987f38c44875b3984febda39d4c44d9369..7d5da82a795c2f7ddbba35bc394819a5bb5e9c70 100644 (file)
@@ -13,6 +13,21 @@ Licenza:    GPLv3
 #ifndef rover_h
 #define rover_h
 
-
+// Global vars
+
+
+// Funzioni
+
+void abilita() ;
+void forwardA(); // speedA e' dato dalla variabile golabale speedA
+void forwardA(byte speedA); // Overloading
+void backwardA() ;
+void backwardA(byte speedA) ;
+void stopA() ;
+void forwardB() ;
+void forwardB(byte speedB) ;
+void backwardB() ;
+void backwardB(byte speedB) ;
+void stopB() ;
 
 #endif
diff --git a/prototypes/motor/README b/prototypes/motor/README
new file mode 100644 (file)
index 0000000..854e433
--- /dev/null
@@ -0,0 +1,16 @@
+Funzioni
+============
+
+Note a riguardo delle funzioni.
+
+Domande
+---------
+
+La funzione forwardB / forwardA accetta una parametro tramite overloading:
+
+1. Se il parametro non viene passato da dove viene pescato?
+2. Si potrebbe fare la stessa cosa con un valore di default?
+2.1 Con quali differenze?
+
+3 La funzione composita drive pero' non accetta nessun parametro, implementare
+la possibilita' che accetti la velocita' come argomento.
diff --git a/prototypes/motor/drive/drive.ino b/prototypes/motor/drive/drive.ino
new file mode 100644 (file)
index 0000000..8c0c8e9
--- /dev/null
@@ -0,0 +1,76 @@
+/* L298n motor
+Aggiunta
+
+Guida 2WD composta da 2 motori
+
+- 2 motori DC
+- L298n module
+- Batteria > 6v
+
+*/
+
+#include <rover.h>
+
+void setup() {
+    abilita();
+}
+
+
+void loop() {
+// Avanti
+    avanti();
+    delay(2000);
+// Stop
+    stop();
+    delay(1000);
+
+// TurnSX
+    turnSX();
+    delay(1000);
+
+// Avanti
+    avanti();
+    delay(2000);
+// Stop
+    stop();
+    delay(1000);
+
+
+// TurnDX
+    turnDX();
+    delay(1000);
+
+// Stop
+    stop();
+    delay(1000);
+}
+
+// Functions
+void avanti() {
+    // Drive ahead: funzione composita
+    forwardA() ;
+    forwardB() ;
+}
+
+void indietro() {
+    // Drive backward: funzione composita
+    backwardA();
+    backwardB();
+}
+
+void turnDX() {
+    // Gira a DX
+    forwardB() ;
+    backwardA();
+}
+
+void turnSX() {
+    // Gira a DX
+    forwardA() ;
+    backwardB();
+}
+
+void stop() {
+    stopA();
+    stopB();
+}
diff --git a/prototypes/motor/motor_func/motor_func.ino b/prototypes/motor/motor_func/motor_func.ino
new file mode 100644 (file)
index 0000000..83a3748
--- /dev/null
@@ -0,0 +1,118 @@
+/* L298n motor
+Aggiunta
+
+Pilotare 2 motore DC con un modulo l928n
+Enable in PWM per settare velocita' massima
+
+- 2 motori DC
+- L298n module
+- Batteria > 6v
+
+*/
+
+
+// Configurazione con OUTPUT digitali
+// motor one
+const int enA = 6;
+const int in1 = 7;
+const int in2 = 8;
+byte speedA = 255;
+// motor two
+const int enB = 5;
+const int in3 = 4;
+const int in4 = 3;
+byte speedB = 255;
+
+void setup() {
+    pinMode(enA, OUTPUT);
+    pinMode(in1, OUTPUT);
+    pinMode(in2, OUTPUT);
+    pinMode(enB, OUTPUT);
+    pinMode(in3, OUTPUT);
+    pinMode(in4, OUTPUT);
+}
+
+
+void loop() {
+// Forward
+    forwardA();
+    forwardB();
+    delay(2000);
+
+// Stop
+    stopA();
+    stopB();
+    delay(1000);
+
+// Backward
+    backwardA();
+    backwardB();
+    delay(2000);
+
+// Stop
+    stopA();
+    stopB();
+    delay(1000);
+
+// Left
+    backwardA();
+    forwardB();
+    delay(2000);
+
+// Stop
+    stopA();
+    stopB();
+    delay(1000);
+
+// right
+    backwardB();
+    forwardA();
+    delay(2000);
+
+// Stop
+    stopA();
+    stopB();
+    delay(1000);
+}
+
+// Functions
+
+// MotorB
+void forwardA() {
+    // Avanzamento motore
+    digitalWrite(in1,LOW);
+    digitalWrite(in2,HIGH);
+    analogWrite(enA,speedA);
+}
+
+void backwardA() {
+    // Reverse motore
+    digitalWrite(in2,LOW);
+    digitalWrite(in1,HIGH);
+    analogWrite(enA,speedA);
+}
+
+void stopA() {
+    // Stop
+    digitalWrite(enA,LOW);
+}
+
+// MotorB
+void forwardB() {
+    // Avanzamento motore
+    digitalWrite(in3,LOW);
+    digitalWrite(in4,HIGH);
+    analogWrite(enB,speedB);
+}
+
+void backwardB() {
+    // Reverse motore
+    digitalWrite(in4,LOW);
+    digitalWrite(in3,HIGH);
+    analogWrite(enB,speedB);
+}
+
+void stopB() {
+    // Stop
+    digitalWrite(enB,LOW);
+}
diff --git a/prototypes/motor/motor_pwm/motor_pwm.ino b/prototypes/motor/motor_pwm/motor_pwm.ino
new file mode 100644 (file)
index 0000000..718e5ba
--- /dev/null
@@ -0,0 +1,56 @@
+/* L298n motor
+Aggiunta
+
+Pilotare 1 motore DC con un modulo l928n
+Enable in PWM per settare velocita' massima
+
+- 1 motori DC
+- L298n module
+- Batteria > 6v
+
+*/
+
+
+// Configurazione con OUTPUT digitali
+// motor one
+const int enA = 6;
+const int in1 = 7;
+const int in2 = 8;
+byte speedA = 255
+// motor two
+const int enB = 5;
+const int in3 = 4;
+const int in4 = 3;
+byte speedB = 0;
+
+void setup() {
+    pinMode(enA, OUTPUT);
+    pinMode(in1, OUTPUT);
+    pinMode(in2, OUTPUT);
+//  pinMode(enB, OUTPUT);
+//  pinMode(in3, OUTPUT);
+//  pinMode(in4, OUTPUT);
+}
+
+
+void loop() {
+// Forward
+    digitalWrite(in1,LOW);
+    digitalWrite(in2,HIGH);
+    analogWrite(enA,speed);
+    delay(2000);
+
+// Stop
+    digitalWrite(enA,LOW);
+    delay(1000);
+
+// Backward
+    digitalWrite(in2,LOW);
+    digitalWrite(in1,HIGH);
+    analogWrite(enA,speed);
+    delay(2000);
+
+// Stop
+    digitalWrite(enA,LOW);
+    delay(1000);
+}
diff --git a/prototypes/motor/motors/motors.ino b/prototypes/motor/motors/motors.ino
new file mode 100644 (file)
index 0000000..e27762c
--- /dev/null
@@ -0,0 +1,39 @@
+/* L298n motor
+
+Pilotare 2 motore DC con un modulo l928n
+Enable in PWM per settare velocita' massima
+
+- 2 motori DC
+- L298n module
+- Batteria > 6v
+
+*/
+#include <rover.h>
+
+
+void setup() {
+    abilita();
+}
+
+
+void loop() {
+// Forward
+    forwardA();
+    forwardB();
+    delay(2000);
+
+// Stop
+    stopA();
+    stopB();
+    delay(1000);
+
+// Backward
+    backwardA();
+    backwardB();
+    delay(2000);
+
+// Stop
+    stopA();
+    stopB();
+    delay(1000);
+}
diff --git a/prototypes/motor/single/single.ino b/prototypes/motor/single/single.ino
new file mode 100644 (file)
index 0000000..47e0c04
--- /dev/null
@@ -0,0 +1,55 @@
+/* L298n motor
+Aggiunta
+
+Pilotare 1 motore DC con un modulo l928n
+
+- 1 motori DC
+- L298n module
+- Batteria > 6v
+
+*/
+
+
+// Configurazione con OUTPUT digitali
+// motor one
+const int enA = 6;
+const int in1 = 7;
+const int in2 = 8;
+byte speedA = 0;
+// motor two
+const int enB = 5;
+const int in3 = 4;
+const int in4 = 3;
+byte speedB = 0;
+
+void setup() {
+    pinMode(enA, OUTPUT);
+    pinMode(in1, OUTPUT);
+    pinMode(in2, OUTPUT);
+//  pinMode(enB, OUTPUT);
+//  pinMode(in3, OUTPUT);
+//  pinMode(in4, OUTPUT);
+}
+
+
+void loop() {
+// Forward
+    digitalWrite(in1,LOW);
+    digitalWrite(in2,HIGH);
+    digitalWrite(enA,HIGH);
+    delay(2000);
+
+// Stop
+    digitalWrite(enA,LOW);
+    delay(1000);
+
+// Backward
+    digitalWrite(in2,LOW);
+    digitalWrite(in1,HIGH);
+    digitalWrite(enA,HIGH);
+    delay(2000);
+
+// Stop
+    digitalWrite(enA,LOW);
+    delay(1000);
+}
diff --git a/prototypes/servo/README b/prototypes/servo/README
new file mode 100644 (file)
index 0000000..1b38c0e
--- /dev/null
@@ -0,0 +1,10 @@
+ToDO
+====
+
+
+Vedere come implemetare il controllo di presenza di ostacoli laterali:
+
+* Un funzione "check" type boolean per l'ultrasuoni che riotorna 0/1 per la presenza di un oggetto
+* due funzione turnSX / turnDX che ruotano il servo, eseguono check, ritornano
+se libero
+* Nella FSM decidere / prevedere da che parte controllare (es spigolo, due rotazioni consecutive che si annullano).
diff --git a/prototypes/servo/base/base.ino b/prototypes/servo/base/base.ino
new file mode 100644 (file)
index 0000000..2a1b3f2
--- /dev/null
@@ -0,0 +1,47 @@
+/* Sweep
+
+   Rotazione di un servomotore tramite la librerio Servo.h .
+
+L'utilizzo della libreria Servo rende inutilizzabile analogWrite()
+sui pin 9 e 10 dato che utilizza i timer associati a questi PIN.
+
+Power: un servo da 9g puo' arrivare ad impegnare 750mA sotto carico
+(se viene opposta resistenza al movimento del servo), un  SG90 prende 
+~52mA se il movimento e' libero. Quindi in fase di test il servo puo'
+essere alimentato direttamente da una scheda Arduino (200ma dal PIN 5v)
+ma per l'uso finale dovra' essere alimentato autonomamente.
+
+Schema: https://www.arduino.cc/en/uploads/Tutorial/sweep_bb.png
+        http://microbotlabs.com/images/mearm-uno-servo-1.jpg
+   */
+
+#include <Servo.h> 
+Servo myservo;  // create servo object to control a servo 
+                // a maximum of eight servo objects can be created 
+// Servo vars
+int pos = 0;    // variable to store the servo position 
+const byte servo =9 ;
+void setup() 
+{ 
+  myservo.attach(servo);  // attaches the servo on pin 9 to the servo object 
+    myservo.write(90);              // tell servo to go to position in variable 'pos' 
+    delay(2000);
+} 
+void loop() 
+{ 
+  for(pos = 20; pos < 160; pos += 1)  // goes from 0 degrees to 180 degrees 
+  {                                  // in steps of 1 degree 
+    myservo.write(pos);              // tell servo to go to position in variable 'pos' 
+    delay(15);                       // waits 15ms for the servo to reach the position 
+  } 
+  for(pos = 160; pos>=20; pos-=1)     // goes from 180 degrees to 0 degrees 
+  {                                
+    myservo.write(pos);              // tell servo to go to position in variable 'pos' 
+    delay(15);                       // waits 15ms for the servo to reach the position 
+  } 
+} 
diff --git a/prototypes/servo/rotation/rotation.ino b/prototypes/servo/rotation/rotation.ino
new file mode 100644 (file)
index 0000000..1193a23
--- /dev/null
@@ -0,0 +1,53 @@
+/* Rotazione
+
+   Rotazione di un servomotore tramite la librerio Servo.h .
+
+L'utilizzo della libreria Servo rende inutilizzabile analogWrite()
+sui pin 9 e 10 dato che utilizza i timer associati a questi PIN.
+
+Power: un servo da 9g puo' arrivare ad impegnare 750mA sotto carico
+(se viene opposta resistenza al movimento del servo), un  SG90 prende 
+~52mA se il movimento e' libero. Quindi in fase di test il servo puo'
+essere alimentato direttamente da una scheda Arduino (200ma dal PIN 5v)
+ma per l'uso finale dovra' essere alimentato autonomamente.
+
+
+Rotazione a SX di 90'
+Rotazione a DC di 90'
+
+Schema: https://www.arduino.cc/en/uploads/Tutorial/sweep_bb.png
+        http://microbotlabs.com/images/mearm-uno-servo-1.jpg
+   */
+
+#include <Servo.h> 
+Servo myservo;  // create servo object to control a servo 
+                // a maximum of eight servo objects can be created 
+// Servo vars
+int pos = 0;    // variable to store the servo position 
+const byte servo =9 ;
+const byte middle = 90; // Centratura servo
+const int pausa = 1000; // Centratura servo
+void setup() 
+{ 
+  myservo.attach(servo);  // attaches the servo on pin 9 to the servo object 
+    myservo.write(middle);              // tell servo to go to position in variable 'pos' 
+    delay(2000);
+} 
+void loop() 
+{ 
+// Turn DX
+    myservo.write(170);
+    delay(pausa);     
+    myservo.write(middle);              
+    delay(1000);     
+// Turn SX
+    myservo.write(10);
+    delay(pausa);      
+    myservo.write(middle);              
+    delay(1000);     
+} 
diff --git a/prototypes/servo/rotation_func/rotation_func.ino b/prototypes/servo/rotation_func/rotation_func.ino
new file mode 100644 (file)
index 0000000..5a660c3
--- /dev/null
@@ -0,0 +1,81 @@
+/* Rotazione
+
+   Rotazione di un servomotore tramite la librerio Servo.h .
+
+L'utilizzo della libreria Servo rende inutilizzabile analogWrite()
+sui pin 9 e 10 dato che utilizza i timer associati a questi PIN.
+
+Power: un servo da 9g puo' arrivare ad impegnare 750mA sotto carico
+(se viene opposta resistenza al movimento del servo), un  SG90 prende 
+~52mA se il movimento e' libero. Quindi in fase di test il servo puo'
+essere alimentato direttamente da una scheda Arduino (200ma dal PIN 5v)
+ma per l'uso finale dovra' essere alimentato autonomamente.
+
+
+Rotazione a SX di 90'
+Rotazione a DC di 90'
+
+Schema: https://www.arduino.cc/en/uploads/Tutorial/sweep_bb.png
+        http://microbotlabs.com/images/mearm-uno-servo-1.jpg
+   */
+
+#include <Servo.h> 
+Servo myservo;  // create servo object to control a servo 
+                // a maximum of eight servo objects can be created 
+// Servo vars
+int pos = 0;    // variable to store the servo position 
+const byte servo =9 ;
+const byte middle = 90; // Centratura servo
+const int spausa = 30; // Pausa movimenti servo
+const byte left = 170;
+const byte right = 10;
+void setup() 
+{ 
+  myservo.attach(servo);  // attaches the servo on pin 9 to the servo object 
+
+  // Centratura iniziale
+  myservo.write(middle);              // tell servo to go to position in variable 'pos' 
+  delay(2000);
+} 
+void loop() 
+{ 
+// Turn DX
+    turnDX();
+    delay(1000);     
+
+    turnMiddle();
+    delay(1000);     
+
+// Turn SX
+      turnSX();
+      delay(1000);     
+  
+      turnMiddle();
+      delay(1000);     
+} 
+
+// Functions
+
+void turnDX() {
+    // TurnDX
+    myservo.write(right);
+    delay(spausa);     
+}
+
+void turnSX() {
+    // TurnSX
+    myservo.write(left);
+    delay(spausa);     
+}
+
+void turnMiddle() {
+    // TurnDX
+    myservo.write(middle);
+    delay(spausa);     
+}
+
diff --git a/prototypes/servo/rotation_lib/rotation_lib.ino b/prototypes/servo/rotation_lib/rotation_lib.ino
new file mode 100644 (file)
index 0000000..ac463ea
--- /dev/null
@@ -0,0 +1,77 @@
+/* Rotazione
+
+   Rotazione di un servomotore tramite la librerio Servo.h .
+
+L'utilizzo della libreria Servo rende inutilizzabile analogWrite()
+sui pin 9 e 10 dato che utilizza i timer associati a questi PIN.
+
+Power: un servo da 9g puo' arrivare ad impegnare 750mA sotto carico
+(se viene opposta resistenza al movimento del servo), un  SG90 prende 
+~52mA se il movimento e' libero. Quindi in fase di test il servo puo'
+essere alimentato direttamente da una scheda Arduino (200ma dal PIN 5v)
+ma per l'uso finale dovra' essere alimentato autonomamente.
+
+
+Rotazione a SX di 90'
+Rotazione a DC di 90'
+
+Schema: https://www.arduino.cc/en/uploads/Tutorial/sweep_bb.png
+        http://microbotlabs.com/images/mearm-uno-servo-1.jpg
+   */
+
+#include <Servo.h> 
+Servo myservo;  // create servo object to control a servo 
+                // a maximum of eight servo objects can be created 
+// Servo vars
+int pos = 0;    // variable to store the servo position 
+const byte servo =9 ;
+const byte middle = 90; // Centratura servo
+const int spausa = 30; // Pausa movimenti servo
+void setup() 
+{ 
+  myservo.attach(servo);  // attaches the servo on pin 9 to the servo object 
+    myservo.write(middle);              // tell servo to go to position in variable 'pos' 
+    delay(2000);
+} 
+void loop() 
+{ 
+// Turn DX
+    turnDX();
+    delay(1000);     
+
+    turnMiddle();
+    delay(1000);     
+
+// Turn SX
+    turnSX();
+    delay(1000);     
+
+    turnMiddle();
+    delay(1000);     
+} 
+
+// Functions
+
+void turnDX() {
+    // TurnDX
+    myservo.write(170);
+    delay(spausa);     
+}
+
+void turnSX() {
+    // TurnSX
+    myservo.write(10);
+    delay(spausa);     
+}
+
+void turnMiddle() {
+    // TurnDX
+    myservo.write(middle);
+    delay(spausa);     
+}
+
diff --git a/prototypes/ultra/check_func/check_func.ino b/prototypes/ultra/check_func/check_func.ino
new file mode 100644 (file)
index 0000000..40481b1
--- /dev/null
@@ -0,0 +1,58 @@
+/* Ultrasonic rilevatore distanza
+
+Rilevatore distanza minore di 5cm.
+funzione
+
+HC-SR04 Ping distance sensor
+VCC to arduino 5v - GND to arduino GND
+
+ */
+# define DEBUG
+
+// Ultrasuoni
+const byte trig = 11;
+const byte echo = 12;
+const byte led = 13;
+long duration, distance;
+boolean allarm = 0;
+
+void setup() {
+    pinMode(trig, OUTPUT);
+    pinMode(echo, INPUT);
+    pinMode(led, OUTPUT);
+
+
+    //Debug
+    Serial.begin (9600);
+}
+
+void loop() {
+if (check()) {
+    digitalWrite(led,HIGH);
+} else {
+    digitalWrite(led,LOW);
+}
+
+#ifdef DEBUG
+Serial.begin(9600);
+#endif
+
+}
+
+boolean check() {
+    digitalWrite(trig, LOW);  // Prepare for ping
+    delayMicroseconds(2); //
+    digitalWrite(trig, HIGH); // Send a ping
+    delayMicroseconds(10); //
+    digitalWrite(trig, LOW); // Set down ping
+    duration = pulseIn(echo, HIGH);
+    distance = (duration/2) / 29.1; // Speed is ~300m/s,
+    // so it takes ~29.1 milliseconds for a cm.
+    // Distance is half of (out + back)
+    if (distance < 5) {  // This is where the LED On/Off happens
+        return 1;
+    }
+    else {
+        return 0;
+    }
+}
diff --git a/prototypes/ultra/ultrasonic_distance_simple/ultrasonic_distance_simple.ino b/prototypes/ultra/ultrasonic_distance_simple/ultrasonic_distance_simple.ino
new file mode 100644 (file)
index 0000000..dc0e8ad
--- /dev/null
@@ -0,0 +1,46 @@
+/* Ultrasonic rilevatore distanza
+
+Rilevatore distanza minore di 5cm.
+
+HC-SR04 Ping distance sensor
+VCC to arduino 5v - GND to arduino GND
+
+
+ */
+
+// Ultrasuoni
+const byte trig = 11;
+const byte echo = 12;
+const byte led = 13;
+long duration, distance;
+
+void setup() {
+    pinMode(trig, OUTPUT);
+    pinMode(echo, INPUT);
+    pinMode(led, OUTPUT);
+
+
+    //Debug
+    Serial.begin (9600);
+}
+
+void loop() {
+    digitalWrite(trig, LOW);  // Prepare for ping
+    delayMicroseconds(2); //
+    digitalWrite(trig, HIGH); // Send a ping
+    delayMicroseconds(10); //
+    digitalWrite(trig, LOW); // Set down ping
+    duration = pulseIn(echo, HIGH);
+    distance = (duration/2) / 29.1; // Speed is ~300m/s,
+    // so it takes ~29.1 milliseconds for a cm.
+    // Distance is half of (out + back)
+    if (distance < 5) {  // This is where the LED On/Off happens
+        digitalWrite(led,HIGH); // When the Red condition is met, the Green LED should turn off
+    }
+    else {
+        digitalWrite(led,LOW);
+    }
+    delay(200);
+    Serial.println(distance);
+}
+