From 9885ce91479dac18885000ed3bf06b4583b4afcd Mon Sep 17 00:00:00 2001
From: Thomas Lambert <t.lambert@uliege.be>
Date: Fri, 4 Nov 2022 17:09:59 +0100
Subject: [PATCH] perf: use precise types to reduce RAM, avoid map for floats

Signed-off-by: Thomas Lambert <t.lambert@uliege.be>
---
 CHANGELOG.md              |  1 +
 controller/controller.ino | 36 ++++++++++++++++++------------------
 2 files changed, 19 insertions(+), 18 deletions(-)

diff --git a/CHANGELOG.md b/CHANGELOG.md
index 207bd21..f9d3bdd 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -21,6 +21,7 @@ to [Semantic Versioning][sem_ver].
 - **Logging**: Minor adaptations to serial-studio interface
 - **Logging**: Output desired frequency as well
 - **All**: Various refactoring and style improvements
+- **All**: Use more precise types to limit RAM
 
 ### Deprecated
 
diff --git a/controller/controller.ino b/controller/controller.ino
index 084ca39..e20fe73 100644
--- a/controller/controller.ino
+++ b/controller/controller.ino
@@ -57,23 +57,23 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
 *******************************************************************************/
 
 // Constant values that can be tweaked here or in the ESC before run
-const int gMAX_SIG = 2000;  // Max signal to the ESC [ms]
-const int gMIN_SIG = 1000;  // Min signal to the ESC [ms]
+const uint16_t gMAX_SIG = 2000;  // Max signal to the ESC [ms]
+const uint16_t gMIN_SIG = 1000;  // Min signal to the ESC [ms]
 
-const int gMAX_RPM = 3000;     // Motor maximum RPM (set in ESC)
-const int gMIN_RPM = 750;      // Motor minimum RPM (set in ESC)
-const int gMAX_ESC_VAL = 160;  // Value at which motor is at max RPM
-const int gMIN_ESC_VAL = 40;   // Min value for ESC to start motor (trial-error)
+const uint16_t gMAX_RPM = 3000;     // Motor maximum RPM (set in ESC)
+const uint16_t gMIN_RPM = 750;      // Motor minimum RPM (set in ESC)
+const uint8_t gMAX_ESC_VAL = 160;  // Value at which motor is at max RPM
+const uint8_t gMIN_ESC_VAL = 40;   // Min value for ESC to start motor (trial-error)
 
-const uint8_t gCSN_PINS[] = CSN_PINS;            // Encoder Chip Select pins
-const float gCUR_FACT = SEN0098_SENSI / 1000.0;  // Factor for current measurement
-const float gCUR_QOV = SEN0098_VIOUT * SEN0098_VCC;
+const uint8_t gCSN_PINS[] = CSN_PINS;                // Encoder Chip Select pins
+const float gCUR_FACT = SEN0098_SENSI / 1000.0;      // Factor for current measurement
+const float gCUR_QOV = SEN0098_VIOUT * SEN0098_VCC;  // [FIXME] Verify
 
 // Other
 Servo gEsc1;  // ESC for front motor
 Servo gEsc2;  // ESC for aft motor
 
-int gEsc_val = 0;  // ESC angle (to use with the Servo library) [0-180]
+uint8_t gEsc_val = 0;  // ESC angle (to use with the Servo library) [0-180]
 String gMode;      // Mode of operation
 
 
@@ -158,11 +158,12 @@ void loop() {
         wing_angles[i] = ReadSensor(gCSN_PINS[i]);
     }
 
-    // Read current and power
+    // Read tension and current from PSU
     float psu_cur[2], psu_vol[2];
     GetPsu(TENS1_PIN, CUR1_PIN, psu_vol[0], psu_cur[0]);
     GetPsu(TENS2_PIN, CUR2_PIN, psu_vol[1], psu_cur[1]);
 
+    // Output all to serial for treatment with serial-studio
     SerialPrint(gMode, potent, gEsc_val, wing_angles, psu_vol, psu_cur);
 }
 
@@ -186,8 +187,7 @@ float SetupSerial() {
     Serial.println(" [Hz]");
 
     while (input > max_freq or input < min_freq) {
-        // Loop indefinitely while waiting for serial input
-        while (Serial.available() == 0) {}
+        while (Serial.available() == 0) {}  // Wait for serial input
 
         input = Serial.parseFloat();
         if (input > max_freq or input < min_freq) {
@@ -211,7 +211,7 @@ float SetupSerial() {
 int FreqToEsc(float freq) {
 
     // Need to scale times 100 so we can have better precision
-    int esc_val = map(freq * 100, 0, 100 * RpmToFreq(gMAX_RPM), 0, 180);
+    int esc_val = freq * (180.0 / RpmToFreq(gMAX_RPM));
 
     if (esc_val < gMIN_ESC_VAL) {
         esc_val = gMIN_ESC_VAL;
@@ -272,12 +272,11 @@ unsigned int ReadSensor(uint8_t csn) {
 
 
 // Output data to use with serial-studio
-// The /* and */ indicate beginning and end of stream data. Do not modify!
 void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[], float psu_vol[], float psu_cur[]) {
 
-    float freq = map(esc_val, 0, 180, 0, RpmToFreq(gMAX_RPM) * 100.0) / 100.0;
+    float freq = esc_val * (RpmToFreq(gMAX_RPM) / 180.0);
 
-    Serial.print("/*");
+    Serial.print("/*");  // Beginning of data stream
     Serial.print(mode);
     Serial.print(",");
     Serial.print(millis() / 1000.0);
@@ -297,7 +296,7 @@ void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[
         Serial.print(",");
         Serial.print(psu_cur[i]);
     }
-    Serial.println("*/");
+    Serial.println("*/");  // End of data stream
 }
 
 
@@ -308,6 +307,7 @@ void GetPsu(byte vol_pin, byte cur_pin, float &vol, float &cur) {
 }
 
 // Measure current consumed by module
+// [FIXME] Check properly
 float GetCurrent(byte cur_pin) {
     float volt_raw = (5.0 / 1023.0) * analogRead(cur_pin);
 
-- 
GitLab