Browse Source

final update before beta!

master
Cailean Finn 4 days ago
parent
commit
79a2b7953e
  1. 3
      include/TCP.h
  2. 2395
      include/icon_clown.h
  3. 50
      src/TCP.cpp
  4. 96
      src/main.cpp

3
include/TCP.h

@ -15,6 +15,7 @@ class TCP {
void connectWiFi(TFT_eSPI& tft); void connectWiFi(TFT_eSPI& tft);
void testConnection(); void testConnection();
void sendData(float& potData, int& emoteIndex); void sendData(float& potData, int& emoteIndex);
void receiveImage();
private: private:
@ -24,6 +25,8 @@ class TCP {
uint16_t port; // Port number uint16_t port; // Port number
WiFiClient client; // WiFi client object WiFiClient client; // WiFi client object
TFT_eSPI* tft; TFT_eSPI* tft;
const int w = 128;
const int h = 180;
}; };
#endif // TCP_H #endif // TCP_H

2395
include/icon_clown.h

File diff suppressed because it is too large

50
src/TCP.cpp

@ -1,4 +1,6 @@
#include "TCP.h" #include "TCP.h"
#include "SPIFFS.h"
#include <esp32-hal-psram.h>
// Constructor // Constructor
TCP::TCP(const char* ssid, const char* password, const char* host, uint16_t port) TCP::TCP(const char* ssid, const char* password, const char* host, uint16_t port)
@ -70,3 +72,51 @@ void TCP::sendData(float& potData, int& emoteIndex) {
} }
} }
void TCP::receiveImage() {
uint8_t* imageData = new uint8_t[w * h * 3]; // Allocate memory for a 64x80 image
// Read bytes from the client and store the count of bytes received
size_t bytesRead = client.readBytes(imageData, w * h * 3);
if (bytesRead == w * h * 3) {
Serial.println("Image data received.");
// Create a buffer for RGB565 line data
uint16_t* lineBuffer = new uint16_t[w]; // Buffer to hold one line of RGB565 data
// Loop through height (80)
for (int y = 0; y < h; y++) {
// Loop through width (64)
for (int x = 0; x < w; x++) {
// Calculate the index in the imageData array
int index = (y * w + x) * 3; // Each pixel has 3 bytes (RGB)
uint8_t r = imageData[index]; // Red channel
uint8_t g = imageData[index + 1]; // Green channel
uint8_t b = imageData[index + 2]; // Blue channel
// Convert RGB to RGB565
uint16_t rgb565 = ((r >> 3) << 11) | ((g >> 2) << 5) | (b >> 3);
// Swap bytes
rgb565 = (rgb565 >> 8) | (rgb565 << 8);
// Set the pixel in the line buffer
lineBuffer[x] = rgb565;
}
// Push the converted line to the TFT display
tft->pushImage(0, y, w, 1, lineBuffer);
}
// Clean up allocated line buffer
delete[] lineBuffer;
} else {
Serial.print("Error: Expected ");
Serial.print(w * h * 3);
Serial.print(" bytes, but received ");
Serial.println(bytesRead);
}
delete[] imageData; // Clean up
}

96
src/main.cpp

@ -12,21 +12,18 @@
driver: driver:
#define ST7735_DRIVER #define ST7735_DRIVER
*/ */
#include <TFT_eSPI.h> // Hardware-specific library #include <TFT_eSPI.h> // Hardware-specific library
#include <SPI.h> #include <SPI.h>
#include "soc/sens_reg.h"
#include <PNGdec.h>
#include "icon_clown.h" // Image is stored here in an 8-bit array
#include "TCP.h" #include "TCP.h"
#define potPin 13 // Potentiometer Pin #define potPin 34 // Potentiometer Pin
#define MAX_IMAGE_WIDTH 240 // Adjust for your images #define MAX_IMAGE_WIDTH 240 // Adjust for your images
// Define some colors to match individual emotions // Define some colors to match individual emotions
const uint16_t emotionColors[] = { const uint16_t emotionColors[] = {
0xFFE0, // HAPPY = YELLOW 0xFFE0, // HAPPY = YELLOW
0x001F, // SAD = BLUE 0x07E0, // SAD = BLUE
0xF800, // ANGRY = RED 0xF800, // ANGRY = RED
0xFA60, // FEAR = ORANGE 0xFA60, // FEAR = ORANGE
0xF8FF, // SURPRISED = PURPLE 0xF8FF, // SURPRISED = PURPLE
@ -44,61 +41,36 @@ enum Emotion {
NEUTRAL NEUTRAL
}; };
float potData = 0; int past_prc_reading = 0;
float deadband_val = 20;
float pot_data = 0;
Emotion emote; Emotion emote;
int screen_width, screen_height; int screen_width, screen_height;
// pass for beta: n->stubborn_vectors p->sv-beta24, and change IP address to server!
TCP tcp("VM9093853", "kfrzuk8UngxyytUz", "192.168.0.169", 12345); TCP tcp("VM9093853", "kfrzuk8UngxyytUz", "192.168.0.169", 12345);
PNG png;
TFT_eSPI tft = TFT_eSPI(); TFT_eSPI tft = TFT_eSPI();
void pngDraw(PNGDRAW *pDraw) {
uint16_t lineBuffer[MAX_IMAGE_WIDTH]; // Line buffer for rendering
uint8_t maskBuffer[1 + MAX_IMAGE_WIDTH / 8]; // Mask buffer
png.getLineAsRGB565(pDraw, lineBuffer, PNG_RGB565_BIG_ENDIAN, 0xffffffff);
if (png.getAlphaMask(pDraw, maskBuffer, 255)) {
// Note: pushMaskedImage is for pushing to the TFT and will not work pushing into a sprite
tft.pushMaskedImage(0, 0 + pDraw->y, pDraw->iWidth, 1, lineBuffer, maskBuffer);
}
}
void setupWiFi(){ void setupWiFi(){
tcp.connectWiFi(tft); tcp.connectWiFi(tft);
tcp.testConnection(); tcp.testConnection();
int emotionIndex = static_cast<int>(emote); int emotionIndex = static_cast<int>(emote);
tcp.sendData(potData, emotionIndex); tcp.sendData(pot_data, emotionIndex);
}
void drawImage(){
// Image sizes will be 128x128, a collection of 10~ per controller
uint16_t pngw = 0, pngh = 0;
int16_t rc = png.openFLASH((uint8_t *)bob, sizeof(bob), pngDraw);
if (rc == PNG_SUCCESS) {
pngw = png.getWidth();
pngh = png.getHeight();
tft.startWrite();
rc = png.decode(NULL, 0);
tft.endWrite();
}
} }
void drawText(String& emotionText, int& i){ void drawText(String& emotionText, int& i){
tft.drawCentreString(emotionText, screen_width / 2, 8, 1); tft.drawCentreString(emotionText, screen_width / 2, 8, 1);
float sinVal = sin(i * 0.05); // Sine output between -1 and 1 float mapped_val = i / 40.96f;
float mappedVal = (50 * sinVal) + 50; // Map it to between 1 and 100 mapped_val = floor(mapped_val);
String ps = String(mappedVal, 2); float dec_val = mapped_val / 100;
String ps = String(mapped_val, 0);
Serial.println(dec_val);
ps.concat("%"); ps.concat("%");
tft.drawCentreString(ps, screen_width / 2, screen_height - (screen_height / 6), 1); tft.drawCentreString(ps, screen_width / 2, screen_height - (screen_height / 6), 1);
int emotionIndex = static_cast<int>(emote); int emotionIndex = static_cast<int>(emote);
tcp.sendData(mappedVal, emotionIndex); tcp.sendData(dec_val, emotionIndex);
i++;
} }
void setupEmotion(String& emotionText){ void setupEmotion(String& emotionText){
@ -117,10 +89,33 @@ void setupEmotion(String& emotionText){
tft.setTextSize(2); tft.setTextSize(2);
} }
int readSensor(int numSamples) {
long sum = 0;
for (int i = 0; i < numSamples; i++) {
sum += analogRead(potPin); // Read the sensor
delay(5); // Small delay between samples
}
int cur_avg_reading = sum / numSamples;
if(abs(cur_avg_reading - past_prc_reading) > deadband_val){
past_prc_reading = cur_avg_reading;
}
return past_prc_reading;
}
// Function to get the next emotion
Emotion getNextEmotion(Emotion currentEmotion) {
int nextEmotionIndex = (static_cast<int>(currentEmotion) + 1) % 7; // 7 is the number of emotions
return static_cast<Emotion>(nextEmotionIndex);
}
void setup(void) { void setup(void) {
// Set emotion // Set emotion
emote = Emotion::NEUTRAL; emote = Emotion::ANGRY;
// Setup screen & serial // Setup screen & serial
tft.init(); tft.init();
@ -140,19 +135,14 @@ void setup(void) {
} }
void loop() { void loop() {
tft.setCursor(0, 0, 2); unsigned long currentTime = millis();
// Sin value
static int i = 0;
// Display the emotion text tft.setCursor(0, 0, 2);
int x = readSensor(5);
String emotionText; String emotionText;
setupEmotion(emotionText); setupEmotion(emotionText);
drawImage(); tcp.receiveImage();
drawText(emotionText, i); drawText(emotionText, x);
delay(60);
} }

Loading…
Cancel
Save