/**** import des biblioteques ****/
#include <SPI.h>
#include "RF24.h"
#include <Servo.h>
/**** definition des constantes et variables ****/
#define moteur1_enablePin 3 //pwm
#define moteur1_in1Pin 7
#define moteur1_in2Pin 6
#define moteur2_enablePin 5 //pwm
#define moteur2_in1Pin 2
#define moteur2_in2Pin 4
#define ledR A0
#define ledB A1
#define PH_Av A2
#define PH_Ar A3
#define piezo A4
int toneVal = 0;
int etatLed1 = LOW;
int etatLed2 = LOW;
int commande;
boolean girophare;
boolean lum;
boolean sirene;
unsigned long previousMillis = 0ul;
unsigned long previousMillis2 = 0ul;
const long interval = 250ul;
const long interval2 = 500ul;
const uint64_t adresse = 0x1111111111;
RF24 radio(9, 10);
Servo myservo;
/**** le setup ****/
void setup()
{
// Serial.begin(115200); // pour debug
delay(1000);
// Serial.println("Joystick moteur demo"); // pour debug
radio.begin();
radio.openReadingPipe(1, adresse);
radio.startListening();
// On initialise les pins du moteur 1
pinMode(moteur1_in1Pin, OUTPUT);
pinMode(moteur1_in2Pin, OUTPUT);
pinMode(moteur1_enablePin, OUTPUT);
pinMode(moteur2_in1Pin, OUTPUT);
pinMode(moteur2_in2Pin, OUTPUT);
pinMode(moteur2_enablePin, OUTPUT);
pinMode(ledB, OUTPUT);
pinMode(ledR, OUTPUT);
pinMode(piezo, OUTPUT);
pinMode(PH_Av, OUTPUT);
pinMode(PH_Ar, OUTPUT);
girophare = false;
lum = false;
sirene = false;
myservo.attach(8, 1000, 2000); // servo z sur pin 2
myservo.write(90); // va en position initial 90°
}
/**** La fonction "Setmoteur(xxx, yyy)" qui envoi la commande ***/
// Fonctions qui set le moteur
void Setmoteur(int speed, boolean reverse)
{
analogWrite(moteur1_enablePin, speed);
analogWrite(moteur2_enablePin, speed);
digitalWrite(moteur1_in1Pin, ! reverse);
digitalWrite(moteur2_in1Pin, ! reverse);
digitalWrite(moteur1_in2Pin, reverse);
digitalWrite(moteur2_in2Pin, reverse);
}
/***** la boucle ****/
void loop()
{
while ( radio.available() )
{
radio.read( &commande, sizeof(commande) ); // si on reçoi quelque chose, on le met dans la variable "commande"
// Serial.println(commande); // pour debug
switch (commande) { // suivant ce que vaut commande :
case 0: // STOP // si vaut 0
Setmoteur(0, true); // MOTEUR OFF
myservo.write(90); // TOUT DROIT
break;
case 1: // AVANT1 // si vaut 1
Setmoteur(170, true); // MOTEUR AV VITESSE 1
myservo.write(90); // TOUT DROIT
break;
case -1: // ARRIERE 1 // si vaut -1
Setmoteur(170, false); // MOTEUR AR VITESSE 1
myservo.write(90); // TOUT DROIT
break;
case 2: // AVANT2
Setmoteur(255, true); // MOTEUR AV VITESSE 2
myservo.write(90); // TOUT DROIT
break;
case -2: // ARRIERE2
Setmoteur(255, false); // MOTEUR AR VITESSE 2
myservo.write(90); // TOUT DROIT
break;
case 3: // DROITE
Setmoteur(0, true); // MOTEUR OFF
myservo.write(135); // DROITE
break;
case 4: // GAUCHE
Setmoteur(0, true); // MOTEUR OFF
myservo.write(45); // GAUCHE
break;
case 13: // AV1_DROITE
Setmoteur(170, true); // MOTEUR AV VITESSE 1
myservo.write(135); // DROITE
break;
case 14: // AV1_GAUCHE
Setmoteur(170, true); // MOTEUR AV VITESSE 1
myservo.write(45); // GAUCHE
break;
case -13: // AR1_DROITE
Setmoteur(170, false); // MOTEUR AR VITESSE 1
myservo.write(135); // DROITE
break;
case -14: // AR1_GAUCHE
Setmoteur(170, false); // MOTEUR AR VITESSE 1
myservo.write(45); // GAUCHE
break;
case 23: // AV2_DROITE
Setmoteur(255, true); // MOTEUR AV VITESSE 2
myservo.write(135); // DROITE
break;
case 24: // AV2_GAUCHE
Setmoteur(255, true); // MOTEUR AV VITESSE 2
myservo.write(45); // GAUCHE
break;
case -23: // AR2_DROITE
Setmoteur(255, false); // MOTEUR AR VITESSE 2
myservo.write(135); // DROITE
break;
case -24: // AR2_GAUCHE
Setmoteur(255, false); // MOTEUR AR VITESSE 2
myservo.write(45); // GAUCHE
break;
case 5 : // BOUTON PAD
break;
case 6 : // BOUTON A
girophare = !girophare;
break;
case 7: // BOUTON B
lum = !lum;
break;
case 8: // BOUTON C
sirene = !sirene;
break;
case 9: // BOUTON D
break;
case 10: // BOUTON E
break;
case 11: // BOUTON F
break;
}
///// ON LANCE LES FONCTIONS DES BOUTONS \\\\\
giro();
phare();
deuton();
}
}
/**** La fonction "giro()" qui allume ou éteint le girophare ***/
void giro()
{
if ( girophare == true )
{
unsigned long currentMillis = millis();
if (currentMillis - previousMillis >= interval) {
previousMillis = currentMillis;
if (etatLed1 == LOW ) {
etatLed1 = HIGH;
etatLed2 = LOW;
} else {
etatLed1 = LOW;
etatLed2 = HIGH;
}
digitalWrite(ledB, etatLed1);
digitalWrite(ledR, etatLed2);
}
}
else {
digitalWrite(ledB, LOW);
digitalWrite(ledR, LOW);
girophare = false;
}
}
/**** La fonction "phare()" qui allume ou éteint les phares ***/
void phare()
{
if ( lum == true )
{
analogWrite(PH_Av, HIGH);
analogWrite(PH_Ar, HIGH);
}
else {
analogWrite(PH_Av, LOW);
analogWrite(PH_Ar, LOW);
lum = false;
}
}
/**** La fonction "deuton()" qui allume ou éteint le deuton et allume les girophares (ne les éteint pas) ***/
void deuton()
{
if ( sirene == true )
{
unsigned long currentMillis2 = millis();
if (millis() - previousMillis2 > interval2)
{
previousMillis2 = millis();
if (toneVal == 400) {
toneVal = 700;
}
else {
toneVal = 400;
}
tone(piezo, toneVal);
girophare = true;
}
}
else
{
noTone(piezo);
sirene = false;
}
}