Adding graphics and fun things from firefly remote
This commit is contained in:
		
							
								
								
									
										1
									
								
								.gitignore
									
									
									
									
										vendored
									
									
								
							
							
						
						
									
										1
									
								
								.gitignore
									
									
									
									
										vendored
									
									
								
							| @@ -1,2 +1,3 @@ | ||||
| .pioenvs | ||||
| .piolibdeps | ||||
| *.h.gch | ||||
|   | ||||
							
								
								
									
										16
									
								
								src/graphics.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										16
									
								
								src/graphics.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,16 @@ | ||||
| static unsigned char logo_bits[] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x80, 0x3c, 0x01, 0xe0, 0x00, 0x07, 0x70, 0x18, 0x0e, 0x30, 0x18, 0x0c, 0x98, 0x99, 0x19, 0x80, 0xff, 0x01, 0x04, 0xc3, 0x20, 0x0c, 0x99, 0x30, 0xec, 0xa5, 0x37, 0xec, 0xa5, 0x37, 0x0c, 0x99, 0x30, 0x04, 0xc3, 0x20, 0x80, 0xff, 0x01, 0x98, 0x99, 0x19, 0x30, 0x18, 0x0c, 0x70, 0x18, 0x0e, 0xe0, 0x00, 0x07, 0x80, 0x3c, 0x01, 0x00, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; | ||||
|  | ||||
| static unsigned char signal_transmitting_bits[] = { | ||||
|   0x18, 0x00, 0x0c, 0x00, 0xc6, 0x00, 0x66, 0x00, 0x23, 0x06, 0x33, 0x0f, | ||||
|   0x33, 0x0f, 0x23, 0x06, 0x66, 0x00, 0xc6, 0x00, 0x0c, 0x00, 0x18, 0x00 | ||||
| }; | ||||
|  | ||||
| static unsigned char signal_connected_bits[] = { | ||||
|   0x18, 0x00, 0x0c, 0x00, 0xc6, 0x00, 0x66, 0x00, 0x23, 0x06, 0x33, 0x09, | ||||
|   0x33, 0x09, 0x23, 0x06, 0x66, 0x00, 0xc6, 0x00, 0x0c, 0x00, 0x18, 0x00 | ||||
| }; | ||||
|  | ||||
| static unsigned char signal_noconnection_bits[] = { | ||||
|   0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x09, | ||||
|   0x00, 0x09, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 | ||||
| }; | ||||
							
								
								
									
										342
									
								
								src/remote.cpp
									
									
									
									
									
								
							
							
						
						
									
										342
									
								
								src/remote.cpp
									
									
									
									
									
								
							| @@ -7,32 +7,35 @@ | ||||
| #include <EEPROM.h> // ESP32 ? | ||||
|  | ||||
| #include "mac_config.h" | ||||
| #include "graphics.h" | ||||
|  | ||||
| // Defining the type of display used (128x32) | ||||
| U8G2_SSD1306_128X64_NONAME_F_SW_I2C u8g2(U8G2_R2, /* clock=*/ 15, /* data=*/ 4, /* reset=*/ 16); | ||||
| // Defining variables for OLED display | ||||
| U8G2_SSD1306_128X64_NONAME_F_SW_I2C u8g2(U8G2_R2, /* clock=*/ 15, /* data=*/ 4, /* reset=*/ 16); | ||||
| char displayBuffer[20]; | ||||
| String displayString; | ||||
| short displayData = 0; | ||||
| unsigned long lastSignalBlink; | ||||
| unsigned long lastDataRotation; | ||||
|  | ||||
| static unsigned char logo_bits[] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x80, 0x3c, 0x01, 0xe0, 0x00, 0x07, 0x70, 0x18, 0x0e, 0x30, 0x18, 0x0c, 0x98, 0x99, 0x19, 0x80, 0xff, 0x01, 0x04, 0xc3, 0x20, 0x0c, 0x99, 0x30, 0xec, 0xa5, 0x37, 0xec, 0xa5, 0x37, 0x0c, 0x99, 0x30, 0x04, 0xc3, 0x20, 0x80, 0xff, 0x01, 0x98, 0x99, 0x19, 0x30, 0x18, 0x0c, 0x70, 0x18, 0x0e, 0xe0, 0x00, 0x07, 0x80, 0x3c, 0x01, 0x00, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; | ||||
| // Defining variables for Settings menu | ||||
| bool changeSettings = false; | ||||
| bool changeSelectedSetting = false; | ||||
|  | ||||
| static unsigned char signal_transmitting_bits[] = { | ||||
|   0x18, 0x00, 0x0c, 0x00, 0xc6, 0x00, 0x66, 0x00, 0x23, 0x06, 0x33, 0x0f, | ||||
|   0x33, 0x0f, 0x23, 0x06, 0x66, 0x00, 0xc6, 0x00, 0x0c, 0x00, 0x18, 0x00 | ||||
| }; | ||||
| bool settingsLoopFlag = false; | ||||
| bool settingsChangeFlag = false; | ||||
| bool settingsChangeValueFlag = false; | ||||
|  | ||||
| static unsigned char signal_connected_bits[] = { | ||||
|   0x18, 0x00, 0x0c, 0x00, 0xc6, 0x00, 0x66, 0x00, 0x23, 0x06, 0x33, 0x09, | ||||
|   0x33, 0x09, 0x23, 0x06, 0x66, 0x00, 0xc6, 0x00, 0x0c, 0x00, 0x18, 0x00 | ||||
| }; | ||||
| // Defining variables for Hall Effect throttle. | ||||
| short hallMeasurement; | ||||
| int throttle = 127; | ||||
| int sendThrottle = 127; | ||||
| byte hallCenterMargin = 4; | ||||
|  | ||||
| static unsigned char signal_noconnection_bits[] = { | ||||
|   0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x09, | ||||
|   0x00, 0x09, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 | ||||
| }; | ||||
| byte currentSetting = 0; | ||||
| const byte numOfSettings = 11; | ||||
|  | ||||
| const float minVoltage = 3.2; | ||||
| const float maxVoltage = 4.1; | ||||
|  | ||||
| // Global copy of slave | ||||
| esp_now_peer_info_t slave; | ||||
| @@ -41,13 +44,16 @@ esp_now_peer_info_t slave; | ||||
| #define DELETEBEFOREPAIR 0 | ||||
| #define HAL_MIN 1290 | ||||
| #define HAL_MAX 2285 | ||||
| #define HAL_CENTER 1785 | ||||
| #define TRIM_LOW 180 | ||||
| #define TRIM_HIGH 0 | ||||
|  | ||||
| //#define pairingMode | ||||
| #define leverPin 36 | ||||
| #define triggerPin 37 | ||||
| #define batteryMeasurePin 35 | ||||
|  | ||||
|  | ||||
| // ESPNOW functions ############################## | ||||
| // Scan for slaves in AP mode | ||||
| #ifdef pairingMode | ||||
| @@ -224,14 +230,59 @@ void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { | ||||
| } | ||||
| //############ End ESP Now | ||||
|  | ||||
| //############ Hardware Helpers | ||||
| //############ | ||||
| // Check if an integer is within a min and max value | ||||
| bool inRange(int val, int minimum, int maximum) { | ||||
|   return ((minimum <= val) && (val <= maximum)); | ||||
| } | ||||
|  | ||||
| // Return true if trigger is activated, false otherwice | ||||
| boolean triggerActive() { | ||||
| bool triggerActive() { | ||||
|   if (digitalRead(triggerPin) == LOW) | ||||
|     return true; | ||||
|   else | ||||
|     return false; | ||||
| } | ||||
|  | ||||
| void calculateThrottlePosition() { | ||||
|   // Hall sensor reading can be noisy, lets make an average reading. | ||||
|   int total = 0; | ||||
|   for (int i = 0; i < 10; i++) { | ||||
|     total += analogRead(leverPin); | ||||
|   } | ||||
|   hallMeasurement = total / 10; | ||||
|  | ||||
|   //DEBUG_PRINT( (String)hallMeasurement ); | ||||
|  | ||||
|   if (hallMeasurement >= HAL_CENTER) { | ||||
|     throttle = constrain(map(hallMeasurement, HAL_CENTER, HAL_MAX, 127, 255), 127, 255); | ||||
|   } else { | ||||
|     throttle = constrain(map(hallMeasurement, HAL_MIN, HAL_CENTER, 0, 127), 0, 127); | ||||
|   } | ||||
|   // removeing center noise | ||||
|   if (abs(throttle - 127) < hallCenterMargin) { | ||||
|     throttle = 127; | ||||
|   } | ||||
| } | ||||
|  | ||||
| // Function to calculate and return the remotes battery voltage. | ||||
| float batteryVoltage() { | ||||
|   float batteryVoltage = 0.0; | ||||
|   int total = 0; | ||||
|  | ||||
|   return 3.6; // for now always full | ||||
| /* | ||||
|    for (int i = 0; i < 10; i++) { | ||||
|     total += analogRead(batteryMeasurePin); | ||||
|    } | ||||
|  | ||||
|    batteryVoltage = (refVoltage / 1024.0) * ((float)total / 10.0); | ||||
|  | ||||
|    return batteryVoltage; | ||||
|  */ | ||||
| } | ||||
|  | ||||
| // Function used to indicate the remotes battery level. | ||||
| int batteryLevel() { | ||||
|   float voltage = batteryVoltage(); | ||||
| @@ -245,23 +296,222 @@ int batteryLevel() { | ||||
|   } | ||||
| } | ||||
|  | ||||
| // Function to calculate and return the remotes battery voltage. | ||||
| float batteryVoltage() { | ||||
|   float batteryVoltage = 0.0; | ||||
|   int total = 0; | ||||
| // Take a number of measurements of the WiFi strength and return the average result. | ||||
| int getStrength(int points){ | ||||
|   long rssi = 0; | ||||
|   long averageRSSI=0; | ||||
|  | ||||
|   return 3.6; // for now always full | ||||
|  | ||||
|   for (int i = 0; i < 10; i++) { | ||||
|     total += analogRead(batteryMeasurePin); | ||||
|   for (int i=0; i < points; i++) { | ||||
|     rssi += WiFi.RSSI(); | ||||
|     delay(20); | ||||
|   } | ||||
|  | ||||
|   batteryVoltage = (refVoltage / 1024.0) * ((float)total / 10.0); | ||||
|  | ||||
|   return batteryVoltage; | ||||
|   averageRSSI=rssi/points; | ||||
|   return averageRSSI; | ||||
| } | ||||
|  | ||||
| // DRAWING | ||||
| //############ End Hardware Helpers | ||||
|  | ||||
| //############ Drawing Functions | ||||
|  | ||||
| void drawBatteryLevel() { | ||||
|   int level = batteryLevel(); | ||||
|  | ||||
|   // Position on OLED | ||||
|   int x = 108; int y = 4; | ||||
|  | ||||
|   u8g2.drawFrame(x + 2, y, 18, 9); | ||||
|   u8g2.drawBox(x, y + 2, 2, 5); | ||||
|  | ||||
|   for (int i = 0; i < 5; i++) { | ||||
|     int p = round((100 / 5) * i); | ||||
|     if (p <= level) | ||||
|     { | ||||
|       u8g2.drawBox(x + 4 + (3 * i), y + 2, 2, 5); | ||||
|     } | ||||
|   } | ||||
| } | ||||
|  | ||||
| void drawThrottle() { | ||||
|   int x = 0; | ||||
|   int y = 18; | ||||
|  | ||||
|   // Draw throttle | ||||
|   u8g2.drawHLine(x, y, 52); | ||||
|   u8g2.drawVLine(x, y, 10); | ||||
|   u8g2.drawVLine(x + 52, y, 10); | ||||
|   u8g2.drawHLine(x, y + 10, 5); | ||||
|   u8g2.drawHLine(x + 52 - 4, y + 10, 5); | ||||
|  | ||||
|   if (sendThrottle >= 127) { | ||||
|     int width = map(sendThrottle, 127, 255, 0, 49); | ||||
|  | ||||
|     for (int i = 0; i < width; i++) { | ||||
|       u8g2.drawVLine(x + i + 2, y + 2, 7); | ||||
|     } | ||||
|   } else { | ||||
|     int width = map(sendThrottle, 0, 126, 49, 0); | ||||
|     for (int i = 0; i < width; i++) { | ||||
|       u8g2.drawVLine(x + 50 - i, y + 2, 7); | ||||
|     } | ||||
|   } | ||||
| } | ||||
|  | ||||
| void drawSignal() { | ||||
|   // Position on OLED | ||||
|   int x = 114; int y = 17; | ||||
| /* | ||||
|    if (connected == true) { | ||||
|     if (triggerActive()) { | ||||
|       u8g2.drawXBM(x, y, 12, 12, signal_transmitting_bits); | ||||
|     } else { | ||||
|       u8g2.drawXBM(x, y, 12, 12, signal_connected_bits); | ||||
|     } | ||||
|    } else { | ||||
|     if (millis() - lastSignalBlink > 500) { | ||||
|       signalBlink = !signalBlink; | ||||
|       lastSignalBlink = millis(); | ||||
|     } | ||||
|  | ||||
|     if (signalBlink == true) { | ||||
|       u8g2.drawXBM(x, y, 12, 12, signal_connected_bits); | ||||
|     } else { | ||||
|       u8g2.drawXBM(x, y, 12, 12, signal_noconnection_bits); | ||||
|     } | ||||
|    } | ||||
|  */ | ||||
| } | ||||
|  | ||||
| void drawTitleScreen(String title) { | ||||
|   u8g2.firstPage(); | ||||
|   do { | ||||
|     title.toCharArray(displayBuffer, 20); | ||||
|     u8g2.setFont(u8g2_font_helvR10_tr  ); | ||||
|     u8g2.drawStr(12, 20, displayBuffer); | ||||
|   } while ( u8g2.nextPage() ); | ||||
|   delay(1500); | ||||
| } | ||||
|  | ||||
| void drawPage() { | ||||
|   /* | ||||
|      int decimals; | ||||
|      float value; | ||||
|      String suffix; | ||||
|      String prefix; | ||||
|  | ||||
|      int first, last; | ||||
|  | ||||
|      int x = 0; | ||||
|      int y = 16; | ||||
|  | ||||
|      // Rotate the realtime data each 4s. | ||||
|      if ((millis() - lastDataRotation) >= 4000) { | ||||
|  | ||||
|      lastDataRotation = millis(); | ||||
|      displayData++; | ||||
|  | ||||
|      if (displayData > 2) { | ||||
|       displayData = 0; | ||||
|      } | ||||
|      } | ||||
|  | ||||
|      switch (displayData) { | ||||
|      case 0: | ||||
|      value = ratioRpmSpeed * data.rpm; | ||||
|      suffix = "KMH"; | ||||
|      prefix = "SPEED"; | ||||
|      decimals = 1; | ||||
|      break; | ||||
|      case 1: | ||||
|      value = ratioPulseDistance * data.tachometerAbs; | ||||
|      suffix = "KM"; | ||||
|      prefix = "DISTANCE"; | ||||
|      decimals = 2; | ||||
|      break; | ||||
|      case 2: | ||||
|      value = data.inpVoltage; | ||||
|      suffix = "V"; | ||||
|      prefix = "BATTERY"; | ||||
|      decimals = 1; | ||||
|      break; | ||||
|      } | ||||
|  | ||||
|      // Display prefix (title) | ||||
|      displayString = prefix; | ||||
|      displayString.toCharArray(displayBuffer, 10); | ||||
|      u8g2.setFont(u8g2_font_profont12_tr); | ||||
|      u8g2.drawStr(x, y - 1, displayBuffer); | ||||
|  | ||||
|      // Split up the float value: a number, b decimals. | ||||
|      first = abs(floor(value)); | ||||
|      last = value * pow(10, 3) - first * pow(10, 3); | ||||
|  | ||||
|      // Add leading zero | ||||
|      if (first <= 9) { | ||||
|      displayString = "0" + (String)first; | ||||
|      } else { | ||||
|      displayString = (String)first; | ||||
|      } | ||||
|  | ||||
|      // Display numbers | ||||
|      displayString.toCharArray(displayBuffer, 10); | ||||
|      u8g2.setFont(u8g2_font_logisoso22_tn ); | ||||
|      u8g2.drawStr(x + 55, y + 13, displayBuffer); | ||||
|  | ||||
|      // Display decimals | ||||
|      displayString = "." + (String)last; | ||||
|      displayString.toCharArray(displayBuffer, decimals + 2); | ||||
|      u8g2.setFont(u8g2_font_profont12_tr); | ||||
|      u8g2.drawStr(x + 86, y - 1, displayBuffer); | ||||
|  | ||||
|      // Display suffix | ||||
|      displayString = suffix; | ||||
|      displayString.toCharArray(displayBuffer, 10); | ||||
|      u8g2.setFont(u8g2_font_profont12_tr); | ||||
|      u8g2.drawStr(x + 86 + 2, y + 13, displayBuffer); | ||||
|    */ | ||||
| } | ||||
|  | ||||
| void drawSettingsMenu() { | ||||
|   /* | ||||
|      // Position on OLED | ||||
|      int x = 0; int y = 10; | ||||
|  | ||||
|      // Draw setting title | ||||
|      displayString = settingPages[currentSetting][0]; | ||||
|      displayString.toCharArray(displayBuffer, displayString.length() + 1); | ||||
|  | ||||
|      u8g2.setFont(u8g2_font_profont12_tr); | ||||
|      u8g2.drawStr(x, y, displayBuffer); | ||||
|  | ||||
|      int val = getSettingValue(currentSetting); | ||||
|  | ||||
|      displayString = (String)val + "" + settingPages[currentSetting][1]; | ||||
|      displayString.toCharArray(displayBuffer, displayString.length() + 1); | ||||
|      u8g2.setFont(u8g2_font_10x20_tr  ); | ||||
|  | ||||
|      if (changeSelectedSetting == true) { | ||||
|      u8g2.drawStr(x + 10, y + 20, displayBuffer); | ||||
|      } else { | ||||
|      u8g2.drawStr(x, y + 20, displayBuffer); | ||||
|      } | ||||
|    */ | ||||
| } | ||||
|  | ||||
| void drawSettingNumber() { | ||||
|   // Position on OLED | ||||
|   int x = 2; int y = 10; | ||||
|  | ||||
|   // Draw current setting number box | ||||
|   u8g2.drawRFrame(x + 102, y - 10, 22, 32, 4); | ||||
|  | ||||
|   // Draw current setting number | ||||
|   displayString = (String)(currentSetting + 1); | ||||
|   displayString.toCharArray(displayBuffer, displayString.length() + 1); | ||||
|  | ||||
|   u8g2.setFont(u8g2_font_profont22_tn); | ||||
|   u8g2.drawStr(x + 108, 22, displayBuffer); | ||||
| } | ||||
|  | ||||
| void updateMainDisplay() { | ||||
|  | ||||
| @@ -269,7 +519,7 @@ void updateMainDisplay() { | ||||
|   do { | ||||
|  | ||||
|     if (changeSettings == true) { | ||||
|       drawSettingsMenu(); | ||||
|       //drawSettingsMenu(); | ||||
|       drawSettingNumber(); | ||||
|     } else { | ||||
|       drawThrottle(); | ||||
| @@ -294,6 +544,8 @@ void drawStartScreen() { | ||||
|   delay(1500); | ||||
| } | ||||
|  | ||||
| //############ End Drawing Functions | ||||
|  | ||||
| void setup() { | ||||
|   Serial.begin(115200); | ||||
|   //Set device in STA mode to begin with | ||||
| @@ -305,11 +557,19 @@ void setup() { | ||||
|   digitalWrite(16, LOW); // set GPIO16 low to reset OLED | ||||
|   delay(50); | ||||
|   digitalWrite(16, HIGH); | ||||
|   Serial.println("ESPNowSkate Sender"); | ||||
|  | ||||
|   // setup other pins | ||||
|   pinMode(triggerPin, INPUT_PULLUP); | ||||
|  | ||||
|   Serial.println("ESPNowSkate Sender"); | ||||
|   u8g2.begin(); | ||||
|   drawStartScreen(); | ||||
|  | ||||
| /* | ||||
|    if (triggerActive()) { | ||||
|     changeSettings = true; | ||||
|     drawTitleScreen("Remote Settings"); | ||||
|    } | ||||
|  */ | ||||
|   // This is the mac address of the Master in Station Mode | ||||
|   Serial.print("STA MAC: "); Serial.println(WiFi.macAddress()); | ||||
|  | ||||
| @@ -336,6 +596,11 @@ void setup() { | ||||
| } | ||||
|  | ||||
| void loop() { | ||||
|   // Call function to update display and LED | ||||
|   updateMainDisplay(); | ||||
|  | ||||
|  | ||||
|   /* update Value | ||||
|      char buf[10]; | ||||
|      sprintf(buf, "%i", map(analogRead(leverPin), HAL_MIN, HAL_MAX, TRIM_LOW, TRIM_HIGH)); | ||||
|      u8g2.firstPage(); | ||||
| @@ -343,7 +608,21 @@ void loop() { | ||||
|      u8g2.setFont(u8g2_font_10x20_tr ); | ||||
|      u8g2.drawStr(0, 20, buf); | ||||
|      } while ( u8g2.nextPage() ); | ||||
|    */ | ||||
|  | ||||
|   calculateThrottlePosition(); | ||||
|  | ||||
|   if (changeSettings == true) { | ||||
|     // Use throttle and trigger to change settings | ||||
|     //controlSettingsMenu(); | ||||
|   } else { | ||||
|     // Use throttle and trigger to drive motors | ||||
|     if (triggerActive()) { | ||||
|       sendThrottle = throttle; | ||||
|     } else { | ||||
|       // 127 is the middle position - no throttle and no brake/reverse | ||||
|       sendThrottle = 127; | ||||
|     } | ||||
|  | ||||
|     // If Slave is found, it would be populate in `slave` variable | ||||
|     // We will check if `slave` is defined and then we proceed further | ||||
| @@ -366,4 +645,5 @@ void loop() { | ||||
|     } | ||||
|  | ||||
|     delay(20); | ||||
|   } | ||||
| } | ||||
|   | ||||
		Reference in New Issue
	
	Block a user