From 12c609c1da60ed0bf7899ea1311a72e825b8fe77 Mon Sep 17 00:00:00 2001
From: Charles JAVERLIAT <charles.javerliat@gmail.com>
Date: Sat, 27 Feb 2021 19:42:03 +0100
Subject: [PATCH] Add sending interval + compact LCD code

---
 .gitignore                    |   1 +
 .vscode/c_cpp_properties.json |  18 +++---
 .vscode/launch.json           |   6 +-
 platformio.ini                |  12 +---
 src/main.cpp                  | 101 +++++++++++++++++-----------------
 5 files changed, 62 insertions(+), 76 deletions(-)

diff --git a/.gitignore b/.gitignore
index 03f4a3c..3b8da3a 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1 +1,2 @@
 .pio
+.vscode
\ No newline at end of file
diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index 6630f93..e0cbe23 100644
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -8,11 +8,11 @@
         {
             "name": "PlatformIO",
             "includePath": [
-                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/include",
-                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/src",
-                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/lib/ros_lib",
+                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/include",
+                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/src",
+                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/lib/ros_lib",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/SPI/src",
-                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/lib/LiquidCrystal_I2C-1.1.3",
+                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/lib/LiquidCrystal_I2C-1.1.3",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/Wire/src",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/cores/arduino/avr",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/cores/arduino/stm32",
@@ -36,7 +36,6 @@
                 "/home/charles/.platformio/packages/framework-cmsis/CMSIS/DSP/Include",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/cores/arduino",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/variants/NUCLEO_F303K8",
-                "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/.pio/libdeps/nucleo_f303k8/LiquidCrystal/src",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/CMSIS_DSP/src",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/EEPROM/src",
                 "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/IWatchdog/src",
@@ -51,11 +50,11 @@
             "browse": {
                 "limitSymbolsToIncludedHeaders": true,
                 "path": [
-                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/include",
-                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/src",
-                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/lib/ros_lib",
+                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/include",
+                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/src",
+                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/lib/ros_lib",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/SPI/src",
-                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/lib/LiquidCrystal_I2C-1.1.3",
+                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/lib/LiquidCrystal_I2C-1.1.3",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/Wire/src",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/cores/arduino/avr",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/cores/arduino/stm32",
@@ -79,7 +78,6 @@
                     "/home/charles/.platformio/packages/framework-cmsis/CMSIS/DSP/Include",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/cores/arduino",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/variants/NUCLEO_F303K8",
-                    "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/.pio/libdeps/nucleo_f303k8/LiquidCrystal/src",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/CMSIS_DSP/src",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/EEPROM/src",
                     "/home/charles/.platformio/packages/framework-arduinoststm32/libraries/IWatchdog/src",
diff --git a/.vscode/launch.json b/.vscode/launch.json
index 1af128f..562b363 100644
--- a/.vscode/launch.json
+++ b/.vscode/launch.json
@@ -12,13 +12,13 @@
             "type": "platformio-debug",
             "request": "launch",
             "name": "PIO Debug",
-            "executable": "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/.pio/build/nucleo_f303k8/firmware.elf",
+            "executable": "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/.pio/build/nucleo_f303k8/firmware.elf",
             "projectEnvName": "nucleo_f303k8",
             "toolchainBinDir": "/home/charles/.platformio/packages/toolchain-gccarmnoneeabi/bin",
             "svdPath": "/home/charles/.platformio/platforms/ststm32/misc/svd/STM32F30x.svd",
             "preLaunchTask": {
                 "type": "PlatformIO",
-                "task": "Pre-Debug (nucleo_f303k8)"
+                "task": "Pre-Debug"
             },
             "internalConsoleOptions": "openOnSessionStart"
         },
@@ -26,7 +26,7 @@
             "type": "platformio-debug",
             "request": "launch",
             "name": "PIO Debug (skip Pre-Debug)",
-            "executable": "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/module-tirette/.pio/build/nucleo_f303k8/firmware.elf",
+            "executable": "/home/charles/Documents/Associatif/Clubelek/Robotique/Coupe de france/Programmation/control-panel/.pio/build/nucleo_f303k8/firmware.elf",
             "projectEnvName": "nucleo_f303k8",
             "toolchainBinDir": "/home/charles/.platformio/packages/toolchain-gccarmnoneeabi/bin",
             "svdPath": "/home/charles/.platformio/platforms/ststm32/misc/svd/STM32F30x.svd",
diff --git a/platformio.ini b/platformio.ini
index 5a25535..4016204 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -9,17 +9,7 @@
 ; https://docs.platformio.org/page/projectconf.html
 
 [platformio]
-default_envs = arduino_uno
-
-[env:arduino_uno]
-platform = atmelavr
-framework = arduino
-board = uno
-
-[env:arduino_nano]
-platform = atmelavr
-framework = arduino
-board = nanoatmega168
+default_envs = nucleo_f303k8
 
 [env:nucleo_f303k8]
 platform = ststm32
diff --git a/src/main.cpp b/src/main.cpp
index 1e4bf30..d859614 100644
--- a/src/main.cpp
+++ b/src/main.cpp
@@ -16,20 +16,18 @@ bool buttonStatus;
 // Last received estimated score
 int estimatedScore = 0;
 
-
-
 /**
  * Tirette (avec gestion du rebond)
  */
 
-int pullCordState;             // the current reading from the input pin
-int lastPullCordState = LOW;   // the previous reading from the input pin
-
-unsigned long lastDebounceTime = 0;  // the last time the output pin was toggled
-unsigned long debounceDelay = 50;    // the debounce time; increase if the output flickers
-
+int pullCordState;            // the current reading from the input pin
+int lastPullCordStatus = LOW; // the previous reading from the input pin
 
+unsigned long lastDebounceTime = 0; // the last time the output pin was toggled
+unsigned long debounceDelay = 50;   // the debounce time; increase if the output flickers
 
+unsigned long lastMessageTime = 0;
+unsigned int const MSG_SENDING_INTERVAL = 200;
 
 ros::NodeHandle nh;
 
@@ -41,14 +39,14 @@ ros::Publisher teamStatusPub("team", &teamMsg);
 ros::Publisher buttonStatusPub("button_status", &buttonStatusMsg);
 ros::Publisher pullCordStatusPub("pull_cord_status", &pullCordStatusMsg);
 
-void estimatedScoreCallback(const std_msgs::Int32& estimatedScore);
+void estimatedScoreCallback(const std_msgs::Int32 &estimatedScore);
 ros::Subscriber<std_msgs::Int32> estimatedScoreSub("estimated_score", &estimatedScoreCallback);
 
 // LCD screen
 LiquidCrystal_I2C lcd(0x27, 16, 2);
 
-
-void refreshScreen() {
+void refreshScreen()
+{
   lcd.clear();
 
   lcd.setCursor(0, 0);
@@ -57,29 +55,11 @@ void refreshScreen() {
   lcd.print(estimatedScore);
 
   lcd.setCursor(0, 1);
-
-  if (team) {
-    lcd.print("Team=JAUNE");
-  } else {
-    lcd.print("Team=BLEU");
-  }
-
+  lcd.print("Team=" + team ? "JAUNE" : "BLEU");
   lcd.setCursor(12, 1);
-  
-  if (pullCordState) {
-    lcd.print("GO");
-  } else {
-    lcd.print("STOP");
-  }
-
+  lcd.print(pullCordState ? "GO" : "STOP");
   lcd.setCursor(13, 0);
-  
-  if (buttonStatus) {
-    lcd.print("ON");
-  } else {
-    lcd.print("OFF");
-  }
-
+  lcd.print(buttonStatus ? "ON" : "OFF");
 }
 
 void setup()
@@ -94,17 +74,28 @@ void setup()
   team = digitalRead(switchPin);
   buttonStatus = digitalRead(buttonPin);
 
-  refreshScreen();
-
   nh.initNode();
   nh.advertise(teamStatusPub);
   nh.advertise(buttonStatusPub);
   nh.advertise(pullCordStatusPub);
   nh.subscribe(estimatedScoreSub);
+
+  lcd.clear();
+  lcd.setCursor(0, 0);
+  lcd.print("Waiting ROS...");
+
+  while (!nh.connected())
+  {
+    nh.spinOnce();
+    delay(MSG_SENDING_INTERVAL);
+  }
+
+  refreshScreen();
 }
 
 // Appelé quand le score est mis à jour (message de score reçu sur l'Arduino depuis la raspi)
-void estimatedScoreCallback(const std_msgs::Int32& estimatedScoreMsg) {
+void estimatedScoreCallback(const std_msgs::Int32 &estimatedScoreMsg)
+{
   estimatedScore = estimatedScoreMsg.data;
   refreshScreen();
 }
@@ -117,49 +108,55 @@ void loop()
   int pullCordReading = digitalRead(pullCordPin);
 
   // If the switch changed, due to noise or pressing:
-  if (pullCordReading != lastPullCordState) {
+  if (pullCordReading != lastPullCordStatus)
+  {
     // reset the debouncing timer
     lastDebounceTime = millis();
   }
 
-  if ((millis() - lastDebounceTime) > debounceDelay) {
+  if ((millis() - lastDebounceTime) > debounceDelay)
+  {
     // whatever the reading is at, it's been there for longer than the debounce
     // delay, so take it as the actual current state:
 
     // if the button state has changed:
-    if (pullCordReading != pullCordState) {
+    if (pullCordReading != pullCordState)
+    {
       pullCordState = pullCordReading;
       refreshScreen();
     }
   }
 
-  lastPullCordState = pullCordReading;
-
-
+  lastPullCordStatus = pullCordReading;
 
   // FIN PARTIE TIRETTE
 
-
-  if(!digitalRead(buttonPin) != buttonStatus) {
+  if (!digitalRead(buttonPin) != buttonStatus)
+  {
     // Appui bouton
     buttonStatus = !digitalRead(buttonPin);
     refreshScreen();
   }
 
-  if(digitalRead(switchPin) != team) {
+  if (digitalRead(switchPin) != team)
+  {
     //Changement d'équipe
     team = digitalRead(switchPin);
     refreshScreen();
   }
-  
-  teamMsg.data = team;
-  teamStatusPub.publish(&teamMsg);
 
-  pullCordStatusMsg.data = pullCordState;
-  pullCordStatusPub.publish(&pullCordStatusMsg);
+  if (millis() - lastMessageTime >= MSG_SENDING_INTERVAL)
+  {
+    teamMsg.data = team;
+    teamStatusPub.publish(&teamMsg);
+
+    pullCordStatusMsg.data = pullCordState;
+    pullCordStatusPub.publish(&pullCordStatusMsg);
 
-  buttonStatusMsg.data = buttonStatus;
-  buttonStatusPub.publish(&buttonStatusMsg);
+    buttonStatusMsg.data = buttonStatus;
+    buttonStatusPub.publish(&buttonStatusMsg);
 
-  nh.spinOnce();
+    lastMessageTime = millis();
+    nh.spinOnce();
+  }
 }
\ No newline at end of file
-- 
GitLab