Samuel Alexander
Published © GPL3+

Smart Table Tennis Bat with Live Analytics

A custom smart table tennis bat for real-time stroke classification and motivational feedback.

IntermediateFull instructions provided8 hours79
Smart Table Tennis Bat with Live Analytics

Things used in this project

Hardware components

Arduino Nano 33 BLE Sense
Arduino Nano 33 BLE Sense
×1

Software apps and online services

Arduino IDE
Arduino IDE
Edge Impulse Studio
Edge Impulse Studio

Hand tools and fabrication machines

3D Printer (generic)
3D Printer (generic)

Story

Read more

Custom parts and enclosures

top-handle_Fl7DKu6qaC.stl

Sketchfab still processing.

bottom-handle_BrI6FsRFXE.stl

Sketchfab still processing.

Code

smart-table-tennis-main.ino

Arduino
/* Smart Table Tennis Bat - Sliding Window with 250ms hop
Arduino Nano 33 BLE Sense Rev2
Edge Impulse model + enhanced UI/UX + acceleration threshold
Implements overlapping inference windows with half-hop (250ms)
*/

#include <Wire.h>
#include <Arduino_BMI270_BMM150.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <table_tennis_2_inferencing.h>

// Display setup
#define SCREEN_WIDTH       128
#define SCREEN_HEIGHT      32
#define OLED_RESET         -1
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);

// Timing & thresholds
#define SAMPLE_INTERVAL_MS    20    // 50Hz sampling
#define WINDOW_SIZE           EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE
#define AXIS_COUNT            EI_CLASSIFIER_RAW_SAMPLES_PER_FRAME
#define WINDOW_SAMPLES        (WINDOW_SIZE / AXIS_COUNT)  // e.g. 25
#define HOP_SAMPLES           ((WINDOW_SAMPLES + 1) / 2)   // ~half window (~12 or 13)
#define CONF_THRESH           0.50f
#define ACCEL_THRESH_G        2.0f
#define FLASH_DURATION_MS     3000
#define IDLE_TIMEOUT_MS       10000
#define ANIM_INTERVAL_MS      200
#define CONVERT_G_TO_MS2      9.80665f

const uint8_t IDLE_LABEL_INDEX = EI_CLASSIFIER_LABEL_COUNT - 1;

// Animation
#define BALL_COUNT 5
const uint8_t ballX[BALL_COUNT] = {16, 40, 64, 88, 112};
const uint8_t ballYBase = 22, ballYUp = 18;

enum State { STATE_OPENING, STATE_MAIN, STATE_FLASH, STATE_IDLE };
State currentState = STATE_OPENING;

// Buffers & counters
typedef float BufferRow[AXIS_COUNT];
static BufferRow imuBuffer[WINDOW_SAMPLES];
static uint16_t bufIndex = 0;
static uint16_t sampleCount = 0;    // counts until window full
static uint16_t sampleCounter = 0;  // counts since last inference

static uint16_t countBHdrive=0, countBHsmash=0;
static uint16_t countFHdrive=0, countFHloop=0, countFHsmash=0;
static uint16_t totalStrokes = 0;

// Timing
uint32_t lastIMUread=0, lastDisplay=0, lastIdleAnim=0;
uint32_t lastStrokeTime=0, flashStart=0;

// Encouragement messages
const char* encMsgs[5][2] = {
{Solid backhand!,Clean drive!},
{Backhand power!,What a backhand!},
{Nice drive!,Perfect contact!},
{Heavy topspin!,Great loop!},
{Pure power!,Smashed it!}
};
uint8_t encCount[5] = {2,2,2,2,2}, encIndex[5] = {0};

// Inference result
typedef struct { uint8_t index; float confidence; } InferenceResult;

// Helpers
bool accelAboveThreshold() {
float thr = ACCEL_THRESH_G * CONVERT_G_TO_MS2;
float thr2 = thrthr;
for(uint16_t i=0;i<WINDOW_SAMPLES;i++){
float ax=imuBuffer[i][0], ay=imuBuffer[i][1], az=imuBuffer[i][2];
if((axax+ayay+azaz)>thr2) return true;
}
return false;
}

void readIMU(){
float ax=0,ay=0,az=0;
if(IMU.accelerationAvailable()) IMU.readAcceleration(ax,ay,az);
float gx=0,gy=0,gz=0;
if(IMU.gyroscopeAvailable())    IMU.readGyroscope(gx,gy,gz);
BufferRow &r = imuBuffer[bufIndex];
r[0]=axCONVERT_G_TO_MS2; r[1]=ayCONVERT_G_TO_MS2; r[2]=az*CONVERT_G_TO_MS2;
r[3]=gx; r[4]=gy; r[5]=gz;
bufIndex = (bufIndex+1)%WINDOW_SAMPLES;
if(sampleCount<WINDOW_SAMPLES) sampleCount++;
sampleCounter++;
}

InferenceResult runInference(){
static float sig[WINDOW_SIZE];
for(uint16_t i=0;i<WINDOW_SAMPLES;i++){
uint16_t p=(bufIndex+i)%WINDOW_SAMPLES;
for(uint8_t j=0;j<AXIS_COUNT;j++) sig[i*AXIS_COUNT+j]=imuBuffer[p][j];
}
signal_t signal;
if(numpy::signal_from_buffer(sig,WINDOW_SIZE,&signal)!=0) return {0,0.0f};
ei_impulse_result_t res;
if(run_classifier(&signal,&res,false)!=EI_IMPULSE_OK) return {0,0.0f};
size_t best=0;
for(size_t i=1;i<EI_CLASSIFIER_LABEL_COUNT;i++)
if(res.classification[i].value>res.classification[best].value) best=i;
return {(uint8_t)best,res.classification[best].value};
}

void drawMainScreen(){
display.clearDisplay(); display.setTextSize(1); display.setTextColor(SSD1306_WHITE);
// BH drive
display.fillRect(0,2,5,2,SSD1306_WHITE); display.setCursor(8,0); display.print(drive ); display.print(countBHdrive);
// FH drive
display.fillRect(64,2,5,2,SSD1306_WHITE); display.setCursor(71,0); display.print(drive ); display.print(countFHdrive);
// BH smash
display.drawTriangle(0,5,2,0,5,5,SSD1306_WHITE); display.setCursor(8,8); display.print(smash ); display.print(countBHsmash);
// FH smash
display.drawTriangle(64,13,66,8,69,13,SSD1306_WHITE); display.setCursor(71,8); display.print(smash ); display.print(countFHsmash);
// FH loop
display.drawCircle(66,18,2,SSD1306_WHITE); display.setCursor(71,16); display.print(loop  ); display.print(countFHloop);
// Total
display.setCursor(0,24); display.print(Total: ); display.print(totalStrokes);
display.display();
}

void drawFlash(uint8_t idx){
display.clearDisplay(); display.setTextSize(1); display.setTextColor(SSD1306_WHITE);
uint8_t m = encIndex[idx]++ % encCount[idx]; const char* msg = encMsgs[idx][m];
int16_t x=(SCREEN_WIDTH-strlen(msg)*6)/2; display.setCursor(x,12); display.print(msg); display.display();
}

void drawIdle(){
display.clearDisplay(); display.setTextSize(1); display.setTextColor(SSD1306_WHITE);
const char* msg=Ready? Swing!; int16_t x=(SCREEN_WIDTH-strlen(msg)*6)/2;
display.setCursor(x,8); display.print(msg);
bool up=((millis()-lastIdleAnim)/ANIM_INTERVAL_MS)&1;
int y= up?ballYUp:ballYBase;
for(uint8_t i=0;i<BALL_COUNT;i++) display.fillCircle(ballX[i],y,2,SSD1306_WHITE);
display.display();
}

void playAnim(){ for(uint8_t f=0;f<4;f++){ display.clearDisplay(); int y=(f&1)?ballYUp:ballYBase; for(uint8_t i=0;i<BALL_COUNT;i++) display.fillCircle(ballX[i],y,2,SSD1306_WHITE); display.display(); delay(ANIM_INTERVAL_MS);} }

void setup(){
Serial.begin(115200);
if(!IMU.begin()) while(1);
if(!display.begin(SSD1306_SWITCHCAPVCC,0x3C)) while(1);
display.clearDisplay(); playAnim();
lastIMUread=millis(); lastDisplay=millis(); lastIdleAnim=millis(); lastStrokeTime=millis();
currentState=STATE_MAIN;
}

void loop(){ uint32_t now=millis();
if(now-lastIMUread>=SAMPLE_INTERVAL_MS){ lastIMUread=now; readIMU(); }
switch(currentState){
case STATE_MAIN:
if(sampleCount>=WINDOW_SAMPLES && sampleCounter>=HOP_SAMPLES){
sampleCounter-=HOP_SAMPLES;
InferenceResult inf=runInference();
if(inf.confidence>CONF_THRESH && inf.index<IDLE_LABEL_INDEX && accelAboveThreshold()){
switch(inf.index){case 0:countBHdrive++;break;case1:countBHsmash++;break;case2:countFHdrive++;break;case3:countFHloop++;break;case4:countFHsmash++;break;}
totalStrokes++; flashStart=now; drawFlash(inf.index); currentState=STATE_FLASH;
}
}
if(now-lastStrokeTime>=IDLE_TIMEOUT_MS){ currentState=STATE_IDLE; lastIdleAnim=now; }
if(now-lastDisplay>=ANIM_INTERVAL_MS){ lastDisplay=now; drawMainScreen(); }
break;

case STATE_FLASH:
  if(sampleCount>=WINDOW_SAMPLES && sampleCounter>=HOP_SAMPLES){
    sampleCounter-=HOP_SAMPLES;
    InferenceResult inf=runInference();
    if(inf.confidence>CONF_THRESH && inf.index<IDLE_LABEL_INDEX && accelAboveThreshold()){
      switch(inf.index){case0:countBHdrive++;break;case1:countBHsmash++;break;case2:countFHdrive++;break;case3:countFHloop++;break;case4:countFHsmash++;break;}
      totalStrokes++; flashStart=now; drawFlash(inf.index);
    }
  }
  if(now-flashStart>=FLASH_DURATION_MS){ lastDisplay=now; lastStrokeTime=now; drawMainScreen(); currentState=STATE_MAIN; }
  break;

case STATE_IDLE:
  if(now-lastIdleAnim>=ANIM_INTERVAL_MS){ lastIdleAnim=now; drawIdle(); }
  if(sampleCount>=WINDOW_SAMPLES && sampleCounter>=HOP_SAMPLES){
    sampleCounter-=HOP_SAMPLES;
    InferenceResult inf=runInference();
    if(inf.confidence>CONF_THRESH && inf.index<IDLE_LABEL_INDEX && accelAboveThreshold()){
      switch(inf.index){case0:countBHdrive++;break;case1:countBHsmash++;break;case2:countFHdrive++;break;case3:countFHloop++;break;case4:countFHsmash++;break;}
      totalStrokes++; flashStart=now; drawFlash(inf.index); currentState=STATE_FLASH;
    }
  }
  break;

default:
  currentState=STATE_MAIN;

}
}

smart-table-tennis-main.ino

Arduino
/*
  Smart Table Tennis Bat - Bluetooth Data Collection System
  Arduino Nano 33 BLE Sense Rev2
  
  Features:
  - BMI270 IMU sampling at 100Hz
  - Swing detection with motion thresholds
  - 1-second data capture window
  - Bluetooth LE data transmission
  - OLED status display
  - JSON data formatting
*/

#include <Arduino_BMI270_BMM150.h>
#include <ArduinoBLE.h>
#include <Adafruit_SSD1306.h>
#include <Wire.h>
#include <ArduinoJson.h>

// OLED Display Configuration
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 32
#define OLED_RESET -1
#define SCREEN_ADDRESS 0x3C
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);

// Sampling Configuration
#define SAMPLE_RATE_HZ 50         //changed to 50Hz to get constant rate
#define SAMPLE_INTERVAL_MS 20     //changed to follow 1000 / SAMPLE_RATE_HZ
#define PRE_TRIGGER_MS 100
#define POST_TRIGGER_MS 400
#define TOTAL_WINDOW_MS 500
#define PRE_TRIGGER_SAMPLES (PRE_TRIGGER_MS / SAMPLE_INTERVAL_MS)  // 10 samples
#define POST_TRIGGER_SAMPLES (POST_TRIGGER_MS / SAMPLE_INTERVAL_MS) // 40 samples
#define TOTAL_SAMPLES (TOTAL_WINDOW_MS / SAMPLE_INTERVAL_MS)        // 50 samples

// Detection Thresholds
#define ACCEL_THRESHOLD 2.0  // 2G
#define GYRO_THRESHOLD 200.0 // 200 degrees/second
#define COOLDOWN_MS 200      // 200ms between detections

// Data Structure for IMU readings
struct IMUData {
  unsigned long timestamp;
  float accelX, accelY, accelZ;
  float gyroX, gyroY, gyroZ;
};

// Circular buffer for continuous data collection (full 500ms window)
IMUData circularBuffer[TOTAL_SAMPLES];
int bufferIndex = 0;
bool bufferFull = false;

// Swing detection variables
bool swingDetected = false;
int triggerIndex = -1;
unsigned long lastSwingTime = 0;
unsigned long swingStartTime = 0;
unsigned long triggerTime = 0;
int swingCount = 0;
unsigned long sessionStartTime = 0;

// BLE Configuration
BLEService dataService("12345678-1234-1234-1234-123456789ABC");
BLECharacteristic swingCharacteristic("87654321-4321-4321-4321-CBA987654321", BLERead | BLENotify, 2048);

// Display and timing variables
unsigned long lastSampleTime = 0;
unsigned long lastDisplayUpdate = 0;
bool bleConnected = false;

void setup() {
  Serial.begin(115200);
  
  // Initialize display
  if (!display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {
    Serial.println("SSD1306 allocation failed");
    for (;;); // Don't proceed, loop forever
  }
  
  display.clearDisplay();
  display.setTextSize(1);
  display.setTextColor(SSD1306_WHITE);
  display.setCursor(0, 0);
  display.println("Initializing...");
  display.display();
  
  // Initialize IMU
  if (!IMU.begin()) {
    display.clearDisplay();
    display.setCursor(0, 0);
    display.println("IMU Init Failed!");
    display.println("Press Reset");
    display.display();
    Serial.println("Failed to initialize IMU!");
    while (1);
  }
  
  // Initialize BLE
  if (!BLE.begin()) {
    display.clearDisplay();
    display.setCursor(0, 0);
    display.println("BLE Init Failed!");
    display.println("Press Reset");
    display.display();
    Serial.println("Starting BLE failed!");
    while (1);
  }
  
  // Set up BLE
  BLE.setLocalName("TT-Stroke-Collector");
  BLE.setAdvertisedService(dataService);
  dataService.addCharacteristic(swingCharacteristic);
  BLE.addService(dataService);
  
  // Start advertising
  BLE.advertise();
  
  sessionStartTime = millis();
  
  display.clearDisplay();
  display.setCursor(0, 0);
  display.println("TT-Stroke-Collector");
  display.println("Waiting for");
  display.println("connection...");
  display.display();
  
  Serial.println("Arduino ready - waiting for BLE connection");
}

void loop() {
  // Handle BLE connections
  BLEDevice central = BLE.central();
  
  if (central && !bleConnected) {
    bleConnected = true;
    sessionStartTime = millis();
    swingCount = 0;
    Serial.println("Connected to central: " + String(central.address()));
    updateDisplay();
  }
  
  if (!central && bleConnected) {
    bleConnected = false;
    Serial.println("Disconnected from central");
    updateDisplay();
  }
  
  // Sample IMU at 100Hz
  if (millis() - lastSampleTime >= SAMPLE_INTERVAL_MS) {
    lastSampleTime = millis();
    sampleIMU();
  }
  
  // Update display every 500ms
  if (millis() - lastDisplayUpdate >= 500) {
    lastDisplayUpdate = millis();
    updateDisplay();
  }
}

void sampleIMU() {
  float ax, ay, az, gx, gy, gz;
  
  if (IMU.accelerationAvailable() && IMU.gyroscopeAvailable()) {
    IMU.readAcceleration(ax, ay, az);
    IMU.readGyroscope(gx, gy, gz);
    
    // Store in circular buffer (continuous collection)
    circularBuffer[bufferIndex].timestamp = millis();
    circularBuffer[bufferIndex].accelX = ax;
    circularBuffer[bufferIndex].accelY = ay;
    circularBuffer[bufferIndex].accelZ = az;
    circularBuffer[bufferIndex].gyroX = gx;
    circularBuffer[bufferIndex].gyroY = gy;
    circularBuffer[bufferIndex].gyroZ = gz;
    
    bufferIndex = (bufferIndex + 1) % TOTAL_SAMPLES;
    if (bufferIndex == 0) bufferFull = true;
    
    // Check for swing detection
    if (bleConnected && !swingDetected && (millis() - lastSwingTime > COOLDOWN_MS)) {
      float totalAccel = sqrt(ax*ax + ay*ay + az*az);
      float totalGyro = sqrt(gx*gx + gy*gy + gz*gz);
      
      if (totalAccel > ACCEL_THRESHOLD && totalGyro > GYRO_THRESHOLD) {
        swingDetected = true;
        triggerTime = millis();
        triggerIndex = (bufferIndex - 1 + TOTAL_SAMPLES) % TOTAL_SAMPLES; // Current sample index
        lastSwingTime = millis();
        Serial.println("Swing detected! Collecting data...");
      }
    }
    
    // Check if we have collected enough post-trigger data
    if (swingDetected && bleConnected) {
      if (millis() - triggerTime >= POST_TRIGGER_MS) {
        captureAndTransmitSwing();
        swingDetected = false;
        swingCount++;
      }
    }
  }
}

void captureAndTransmitSwing() {
  Serial.println("Transmitting swing data...");
  
  // Send swing header (compact format)
  String header = String(swingCount + 1) + "|" + String(triggerTime) + "|";
  swingCharacteristic.writeValue(header.c_str());
  delay(5);
  
  // Calculate start index for 500ms window
  int startIndex = (triggerIndex - PRE_TRIGGER_SAMPLES + TOTAL_SAMPLES) % TOTAL_SAMPLES;
  
  // Send data in compact format: timestamp,ax,ay,az,gx,gy,gz per line
  for (int i = 0; i < TOTAL_SAMPLES; i++) {
    int dataIndex = (startIndex + i) % TOTAL_SAMPLES;
    
    // Use relative timestamp
    int relativeTime = i * SAMPLE_INTERVAL_MS;
    
    String dataLine = String(relativeTime) + "," +
                     String(circularBuffer[dataIndex].accelX, 3) + "," +
                     String(circularBuffer[dataIndex].accelY, 3) + "," +
                     String(circularBuffer[dataIndex].accelZ, 3) + "," +
                     String(circularBuffer[dataIndex].gyroX, 1) + "," +
                     String(circularBuffer[dataIndex].gyroY, 1) + "," +
                     String(circularBuffer[dataIndex].gyroZ, 1) + "\n";
    
    swingCharacteristic.writeValue(dataLine.c_str());
    delay(2); // Minimal delay for BLE stability
  }
  
  // Send end marker
  swingCharacteristic.writeValue("END_SWING");
  
  Serial.println("Swing data transmitted - Swing #" + String(swingCount + 1));
}

void updateDisplay() {
  display.clearDisplay();
  display.setCursor(0, 0);
  
  if (!bleConnected) {
    display.println("TT-Stroke-Collector");
    display.println("Waiting for");
    display.println("connection...");
  } else {
    display.println("Connected!");
    display.print("Swings: ");
    display.println(swingCount);
    
    // Session time
    unsigned long sessionTime = (millis() - sessionStartTime) / 1000;
    display.print("Time: ");
    display.print(sessionTime / 60);
    display.print(":");
    if (sessionTime % 60 < 10) display.print("0");
    display.println(sessionTime % 60);
    
    // Status
    if (swingDetected) {
      display.println("Capturing...");
    } else {
      display.println("Ready");
    }
  }
  
  display.display();
}

python-data-collector.py

Python
#!/usr/bin/env python3
"""
Table Tennis Data Collector - USB Serial Version
Collects continuous IMU data from Arduino via USB serial connection at 50Hz.

Requirements:
- pyserial (pip install pyserial)
- Arduino Nano 33 BLE Sense Rev2 connected via USB

Author: TT Data Collection System
"""

import serial
import serial.tools.list_ports
import time
import sys
import os
import threading
from datetime import datetime

class TTDataCollector:
    def __init__(self):
        self.serial_conn = None
        self.recording = False
        self.samples_collected = 0
        self.csv_file = None
        self.start_time = None
        self.stop_recording = False
        
    def find_arduino(self):
        """Scan for Arduino on serial ports"""
        print(" Scanning for Arduino...")
        
        # Get list of available ports
        ports = serial.tools.list_ports.comports()
        arduino_ports = []
        
        for port in ports:
            # Look for Arduino-like devices
            if any(keyword in port.description.lower() for keyword in ['arduino', 'nano', 'usb serial']):
                arduino_ports.append(port.device)
            elif 'cu.usbmodem' in port.device or 'ttyACM' in port.device:
                arduino_ports.append(port.device)
        
        if not arduino_ports:
            print(" No Arduino found. Please check connection.")
            return None
        
        # Try to connect to each potential Arduino
        for port in arduino_ports:
            try:
                print(f" Trying {port}...")
                ser = serial.Serial(port, 115200, timeout=2)
                time.sleep(3)  # Wait for Arduino to initialize
                
                # Clear any existing data in buffer
                ser.flushInput()
                
                # Send a test command to see if Arduino responds
                ser.write(b"TEST\n")
                time.sleep(0.5)
                
                # Check for any response (Arduino might send READY again or respond to TEST)
                response_received = False
                for attempt in range(10):  # Try for 5 seconds
                    if ser.in_waiting > 0:
                        try:
                            response = ser.readline().decode().strip()
                            print(f" Arduino response: '{response}'")
                            if response in ["READY", "STARTED", "STOPPED"] or "TT" in response:
                                print(f" Arduino connected on {port}")
                                return ser
                            response_received = True
                        except:
                            pass
                    time.sleep(0.5)
                
                if not response_received:
                    print(f" No response from {port}")
                
                ser.close()
                
            except Exception as e:
                print(f" Failed to connect to {port}: {e}")
                continue
        
        print(" No Arduino found with correct firmware.")
        return None
    
    def get_filename(self):
        """Get filename from user input"""
        while True:
            filename = input("\n Enter filename (e.g., FHdrive.csv): ").strip()
            
            if not filename:
                print(" Please enter a filename.")
                continue
            
            if not filename.endswith('.csv'):
                filename += '.csv'
            
            # Check if file exists
            if os.path.exists(filename):
                overwrite = input(f"  File {filename} exists. Overwrite? (y/n): ").strip().lower()
                if overwrite != 'y':
                    continue
            
            return filename
    
    def start_recording(self, filename):
        """Start recording session"""
        try:
            # Open CSV file
            self.csv_file = open(filename, 'w')
            self.csv_file.write("Timestamp,AccelX,AccelY,AccelZ,GyroX,GyroY,GyroZ\n")
            self.csv_file.flush()
            
            # Clear any pending data in serial buffer
            self.serial_conn.flushInput()
            time.sleep(0.1)
            
            # Send START command to Arduino
            self.serial_conn.write(b"START\n")
            
            # Wait for Arduino acknowledgment (be more tolerant)
            max_attempts = 10
            for attempt in range(max_attempts):
                try:
                    response = self.serial_conn.readline().decode().strip()
                    print(f" Arduino response: '{response}'")
                    
                    if response == "STARTED":
                        print(" Arduino confirmed START")
                        break
                    elif response == "READY":
                        print(" Got READY, sending START again...")
                        self.serial_conn.write(b"START\n")
                    elif response == "":
                        print(" No response, retrying...")
                        self.serial_conn.write(b"START\n")
                        
                except Exception as e:
                    print(f" Communication error: {e}")
                
                time.sleep(0.5)
                
                if attempt == max_attempts - 1:
                    print(" Failed to get START confirmation from Arduino")
                    return False
            
            self.recording = True
            self.samples_collected = 0
            self.start_time = time.time()
            self.stop_recording = False
            
            print(f" Recording started - {filename}")
            print(" Press 'q' + ENTER to stop recording")
            print("  Max recording time: 2 minutes")
            print("-" * 50)
            
            return True
            
        except Exception as e:
            print(f" Failed to start recording: {e}")
            return False
    
    def stop_recording_session(self):
        """Stop recording session"""
        if not self.recording:
            return
        
        try:
            # Send STOP command to Arduino
            self.serial_conn.write(b"STOP\n")
            
            # Wait for Arduino acknowledgment
            response = self.serial_conn.readline().decode().strip()
            if response == "STOPPED":
                print("\n Arduino stopped successfully")
            
            self.recording = False
            
            # Close CSV file
            if self.csv_file:
                self.csv_file.close()
                self.csv_file = None
            
            elapsed_time = time.time() - self.start_time
            print(f" Recording completed!")
            print(f" Samples collected: {self.samples_collected}")
            print(f"  Duration: {elapsed_time:.1f} seconds")
            print(f" Average sample rate: {self.samples_collected/elapsed_time:.1f} Hz")
            
        except Exception as e:
            print(f" Error stopping recording: {e}")
    
    def data_collection_thread(self):
        """Thread for collecting data from Arduino"""
        max_duration = 120  # 2 minutes in seconds (yields ~6,000 samples at 50Hz)
        
        while self.recording and not self.stop_recording:
            try:
                # Check for timeout
                elapsed = time.time() - self.start_time
                if elapsed >= max_duration:
                    print(f"\n Maximum recording time ({max_duration/60:.1f} minutes) reached!")
                    self.stop_recording = True
                    break
                
                # Read data from Arduino
                if self.serial_conn.in_waiting > 0:
                    line = self.serial_conn.readline().decode().strip()
                    
                    # Skip empty lines and command responses
                    if not line or line in ['READY', 'STARTED', 'STOPPED']:
                        continue
                    
                    # Write to CSV file
                    self.csv_file.write(line + '\n')
                    self.csv_file.flush()  # Ensure data is written immediately
                    
                    self.samples_collected += 1
                    
                    # Update display every 100 samples
                    if self.samples_collected % 100 == 0:
                        elapsed = time.time() - self.start_time
                        rate = self.samples_collected / elapsed if elapsed > 0 else 0
                        print(f" Samples: {self.samples_collected:,} | Time: {elapsed:.1f}s | Rate: {rate:.1f} Hz", end='\r')
                
                time.sleep(0.001)  # Small delay to prevent busy waiting
                
            except Exception as e:
                print(f"\n Error during data collection: {e}")
                break
        
        # Stop recording
        self.stop_recording_session()
    
    def user_input_thread(self):
        """Thread for handling user input"""
        while self.recording:
            try:
                user_input = input().strip().lower()
                if user_input == 'q':
                    print("\n Stopping recording...")
                    self.stop_recording = True
                    break
            except EOFError:
                break
            except KeyboardInterrupt:
                print("\n Stopping recording...")
                self.stop_recording = True
                break
    
    def run_session(self):
        """Run a single recording session"""
        filename = self.get_filename()
        
        if not self.start_recording(filename):
            return False
        
        # Start data collection thread
        data_thread = threading.Thread(target=self.data_collection_thread)
        data_thread.daemon = True
        data_thread.start()
        
        # Start user input thread
        input_thread = threading.Thread(target=self.user_input_thread)
        input_thread.daemon = True
        input_thread.start()
        
        # Wait for threads to complete
        data_thread.join()
        
        return True
    
    def run(self):
        """Main program loop"""
        print(" Table Tennis Data Collector v2.0")
        print("=" * 50)
        
        # Find and connect to Arduino
        self.serial_conn = self.find_arduino()
        if not self.serial_conn:
            return
        
        try:
            while True:
                print("\n" + "=" * 50)
                print(" Main Menu:")
                print("1. Start new recording session")
                print("2. Quit")
                
                choice = input("\nEnter choice (1-2): ").strip()
                
                if choice == '1':
                    self.run_session()
                    
                elif choice == '2':
                    print(" Goodbye!")
                    break
                    
                else:
                    print(" Invalid choice. Please enter 1 or 2.")
        
        except KeyboardInterrupt:
            print("\n\n Program interrupted by user")
        
        finally:
            if self.recording:
                self.stop_recording_session()
            
            if self.serial_conn and self.serial_conn.is_open:
                self.serial_conn.close()
                print(" Serial connection closed")

def main():
    """Main entry point"""
    collector = TTDataCollector()
    collector.run()

if __name__ == "__main__":
    main()

tt_data_collector_app.html

HTML
<!DOCTYPE html>
<html lang="en">
<head>
    <meta charset="UTF-8">
    <meta name="viewport" content="width=device-width, initial-scale=1.0">
    <title>TT Stroke Collector</title>
    <script src="https://cdnjs.cloudflare.com/ajax/libs/jszip/3.10.1/jszip.min.js"></script>
    <style>
        * {
            margin: 0;
            padding: 0;
            box-sizing: border-box;
        }

        body {
            font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
            background: linear-gradient(135deg, #667eea 0%, #764ba2 100%);
            min-height: 100vh;
            padding: 20px;
            color: white;
        }

        .container {
            max-width: 400px;
            margin: 0 auto;
            background: rgba(255, 255, 255, 0.1);
            backdrop-filter: blur(10px);
            border-radius: 20px;
            padding: 30px;
            box-shadow: 0 8px 32px rgba(0, 0, 0, 0.1);
        }

        h1 {
            text-align: center;
            margin-bottom: 30px;
            font-size: 24px;
            font-weight: 700;
        }

        .input-group {
            margin-bottom: 25px;
        }

        label {
            display: block;
            margin-bottom: 8px;
            font-weight: 600;
            font-size: 16px;
        }

        input[type="text"] {
            width: 100%;
            padding: 15px;
            font-size: 16px;
            border: none;
            border-radius: 12px;
            background: rgba(255, 255, 255, 0.9);
            color: #333;
        }

        input[type="text"]:focus {
            outline: none;
            box-shadow: 0 0 0 3px rgba(255, 255, 255, 0.3);
        }

        .button {
            width: 100%;
            padding: 18px;
            font-size: 18px;
            font-weight: 600;
            border: none;
            border-radius: 12px;
            cursor: pointer;
            margin-bottom: 15px;
            transition: all 0.3s ease;
            touch-action: manipulation;
        }

        .btn-primary {
            background: #4CAF50;
            color: white;
        }

        .btn-primary:hover:not(:disabled) {
            background: #45a049;
            transform: translateY(-2px);
        }

        .btn-secondary {
            background: #2196F3;
            color: white;
        }

        .btn-secondary:hover:not(:disabled) {
            background: #1976D2;
            transform: translateY(-2px);
        }

        .btn-danger {
            background: #f44336;
            color: white;
        }

        .btn-danger:hover:not(:disabled) {
            background: #d32f2f;
            transform: translateY(-2px);
        }

        .button:disabled {
            background: #ccc;
            cursor: not-allowed;
            transform: none;
        }

        .status-panel {
            background: rgba(255, 255, 255, 0.1);
            border-radius: 12px;
            padding: 20px;
            margin-bottom: 20px;
            text-align: center;
        }

        .status-item {
            margin-bottom: 15px;
        }

        .status-item:last-child {
            margin-bottom: 0;
        }

        .status-label {
            font-size: 14px;
            opacity: 0.8;
            margin-bottom: 5px;
        }

        .status-value {
            font-size: 24px;
            font-weight: 700;
        }

        .connection-status {
            padding: 10px;
            border-radius: 8px;
            margin-bottom: 20px;
            text-align: center;
            font-weight: 600;
        }

        .status-disconnected {
            background: rgba(244, 67, 54, 0.2);
            border: 1px solid rgba(244, 67, 54, 0.5);
        }

        .status-connected {
            background: rgba(76, 175, 80, 0.2);
            border: 1px solid rgba(76, 175, 80, 0.5);
        }

        .status-connecting {
            background: rgba(255, 193, 7, 0.2);
            border: 1px solid rgba(255, 193, 7, 0.5);
        }

        .log {
            background: rgba(0, 0, 0, 0.3);
            border-radius: 8px;
            padding: 15px;
            max-height: 200px;
            overflow-y: auto;
            font-family: monospace;
            font-size: 12px;
            margin-top: 20px;
        }

        .log-entry {
            margin-bottom: 5px;
            opacity: 0.9;
        }

        .swing-animation {
            animation: pulse 0.5s ease-in-out;
        }

        @keyframes pulse {
            0% { transform: scale(1); }
            50% { transform: scale(1.05); }
            100% { transform: scale(1); }
        }

        .hidden {
            display: none;
        }

        @media (max-width: 480px) {
            .container {
                padding: 20px;
                margin: 10px;
            }
            
            h1 {
                font-size: 20px;
            }
            
            .button {
                padding: 16px;
                font-size: 16px;
            }
        }
    </style>
</head>
<body>
    <div class="container">
        <h1> TT Stroke Collector</h1>
        
        <div class="connection-status status-disconnected" id="connectionStatus">
            Disconnected
        </div>

        <div class="input-group">
            <label for="strokeType">Stroke Type:</label>
            <input type="text" id="strokeType" placeholder="e.g., FHdrive, BHchop, FHsmash" value="">
        </div>

        <button class="button btn-primary" id="connectBtn" onclick="connectToDevice()">
            Connect to Arduino
        </button>

        <div id="sessionPanel" class="hidden">
            <div class="status-panel">
                <div class="status-item">
                    <div class="status-label">Current Stroke</div>
                    <div class="status-value" id="currentStroke">-</div>
                </div>
                <div class="status-item">
                    <div class="status-label">Swings Collected</div>
                    <div class="status-value" id="swingCount">0</div>
                </div>
                <div class="status-item">
                    <div class="status-label">Session Time</div>
                    <div class="status-value" id="sessionTime">00:00</div>
                </div>
            </div>

            <button class="button btn-secondary" id="downloadBtn" onclick="downloadSwings()" disabled>
                Download CSV Files
            </button>

            <button class="button btn-danger" id="resetBtn" onclick="resetSession()">
                Reset Session
            </button>
        </div>

        <div class="log" id="logContainer">
            <div class="log-entry">Ready to connect...</div>
        </div>
    </div>

    <script>
        // Global variables
        let bleDevice = null;
        let bleCharacteristic = null;
        let isConnected = false;
        let sessionStartTime = null;
        let sessionTimer = null;
        let swingData = [];
        let currentSwingBuffer = '';
        let swingCount = 0;

        // Logging function
        function log(message) {
            const logContainer = document.getElementById('logContainer');
            const entry = document.createElement('div');
            entry.className = 'log-entry';
            entry.textContent = `${new Date().toLocaleTimeString()}: ${message}`;
            logContainer.appendChild(entry);
            logContainer.scrollTop = logContainer.scrollHeight;
        }

        // Update connection status
        function updateConnectionStatus(status) {
            const statusEl = document.getElementById('connectionStatus');
            statusEl.className = 'connection-status';
            
            switch(status) {
                case 'connected':
                    statusEl.className += ' status-connected';
                    statusEl.textContent = 'Connected to Arduino';
                    break;
                case 'connecting':
                    statusEl.className += ' status-connecting';
                    statusEl.textContent = 'Connecting...';
                    break;
                case 'disconnected':
                default:
                    statusEl.className += ' status-disconnected';
                    statusEl.textContent = 'Disconnected';
                    break;
            }
        }

        // Start session timer
        function startSessionTimer() {
            sessionStartTime = Date.now();
            sessionTimer = setInterval(() => {
                const elapsed = Math.floor((Date.now() - sessionStartTime) / 1000);
                const minutes = Math.floor(elapsed / 60);
                const seconds = elapsed % 60;
                document.getElementById('sessionTime').textContent = 
                    `${minutes.toString().padStart(2, '0')}:${seconds.toString().padStart(2, '0')}`;
            }, 1000);
        }

        // Stop session timer
        function stopSessionTimer() {
            if (sessionTimer) {
                clearInterval(sessionTimer);
                sessionTimer = null;
            }
        }

        // Connect to BLE device
        async function connectToDevice() {
            const strokeType = document.getElementById('strokeType').value.trim();
            if (!strokeType) {
                alert('Please enter a stroke type first!');
                return;
            }

            try {
                updateConnectionStatus('connecting');
                log('Scanning for TT-Stroke-Collector...');

                bleDevice = await navigator.bluetooth.requestDevice({
                    filters: [{ name: 'TT-Stroke-Collector' }],
                    optionalServices: ['12345678-1234-1234-1234-123456789abc']
                });

                log('Device found, connecting...');
                const server = await bleDevice.gatt.connect();
                
                log('Getting service...');
                const service = await server.getPrimaryService('12345678-1234-1234-1234-123456789abc');
                
                log('Getting characteristic...');
                bleCharacteristic = await service.getCharacteristic('87654321-4321-4321-4321-cba987654321');
                
                // Set up notifications
                await bleCharacteristic.startNotifications();
                bleCharacteristic.addEventListener('characteristicvaluechanged', handleDataReceived);
                
                // Set up disconnect handler
                bleDevice.addEventListener('gattserverdisconnected', handleDisconnection);
                
                isConnected = true;
                updateConnectionStatus('connected');
                log('Connected successfully!');
                
                // Start session
                startSession();
                
            } catch (error) {
                log(`Connection failed: ${error.message}`);
                updateConnectionStatus('disconnected');
                isConnected = false;
            }
        }

        // Handle data received from Arduino
        function handleDataReceived(event) {
            const decoder = new TextDecoder();
            const data = decoder.decode(event.target.value);
            
            if (data === 'END_SWING') {
                // Process complete swing data
                processSwingData();
                currentSwingBuffer = '';
            } else {
                // Accumulate data chunks
                currentSwingBuffer += data;
            }
        }

        // Process complete swing data (new compact format)
        function processSwingData() {
            try {
                const lines = currentSwingBuffer.trim().split('\n');
                if (lines.length < 2) {
                    log('Error: Incomplete swing data received');
                    return;
                }
                
                // Parse header: swingNumber|timestamp|
                const headerParts = lines[0].split('|');
                const swingNumber = parseInt(headerParts[0]);
                const timestamp = parseInt(headerParts[1]);
                
                log(`Processing swing #${swingNumber}`);
                
                // Parse CSV data lines
                const csvData = [];
                for (let i = 1; i < lines.length; i++) {
                    const line = lines[i].trim();
                    if (line && !line.includes('|')) { // Skip header and empty lines
                        const values = line.split(',');
                        if (values.length === 7) {
                            csvData.push(values.map(v => parseFloat(v)));
                        }
                    }
                }
                
                if (csvData.length === 0) {
                    log('Error: No valid CSV data found in swing');
                    return;
                }
                
                // Fill timestamp gaps if needed
                const refinedCsv = refineTimestamps(csvData);
                
                // Convert to CSV format
                const csvString = convertArrayToCSV(refinedCsv);
                swingData.push({
                    number: swingNumber,
                    csv: csvString,
                    timestamp: timestamp
                });
                
                // Update UI
                swingCount = swingData.length;
                document.getElementById('swingCount').textContent = swingCount;
                document.getElementById('swingCount').classList.add('swing-animation');
                setTimeout(() => {
                    document.getElementById('swingCount').classList.remove('swing-animation');
                }, 500);
                
                // Enable download if we have data
                document.getElementById('downloadBtn').disabled = false;
                
                log(`Swing processed. Total: ${swingCount} (${csvData.length} samples)`);
                
            } catch (error) {
                log(`Error processing swing data: ${error.message}`);
                // Don't throw error, just log and continue
            }
        }

        // Refine timestamps - fill gaps and ensure 10ms intervals
        function refineTimestamps(csvData) {
            if (csvData.length === 0) return csvData;
            
            const refined = [];
            const expectedSamples = 25; // 500ms / 20ms
            
            // Sort by timestamp to handle any out-of-order data
            csvData.sort((a, b) => a[0] - b[0]);
            
            for (let i = 0; i < expectedSamples; i++) {
                const expectedTime = i * 20; // 0, 10, 20, ... 490ms
                
                // Find closest actual sample
                let closestIndex = 0;
                let closestDiff = Math.abs(csvData[0][0] - expectedTime);
                
                for (let j = 1; j < csvData.length; j++) {
                    const diff = Math.abs(csvData[j][0] - expectedTime);
                    if (diff < closestDiff) {
                        closestDiff = diff;
                        closestIndex = j;
                    }
                }
                
                // Use closest sample but fix timestamp
                const sample = [...csvData[closestIndex]];
                sample[0] = expectedTime; // Fix timestamp
                refined.push(sample);
            }
            
            return refined;
        }

        // Convert array data to CSV string
        function convertArrayToCSV(csvData) {
            let csv = 'Timestamp,AccelX,AccelY,AccelZ,GyroX,GyroY,GyroZ\n';
            
            csvData.forEach(sample => {
                csv += sample.join(',') + '\n';
            });
            
            return csv;
        }

        // Start session
        function startSession() {
            const strokeType = document.getElementById('strokeType').value.trim();
            document.getElementById('currentStroke').textContent = strokeType;
            document.getElementById('sessionPanel').classList.remove('hidden');
            document.getElementById('connectBtn').disabled = true;
            document.getElementById('strokeType').disabled = true;
            
            // Reset counters
            swingData = [];
            swingCount = 0;
            document.getElementById('swingCount').textContent = '0';
            document.getElementById('downloadBtn').disabled = true;
            
            startSessionTimer();
            log(`Session started for: ${strokeType}`);
        }

        // Handle disconnection
        function handleDisconnection() {
            isConnected = false;
            updateConnectionStatus('disconnected');
            log('Device disconnected');
            stopSessionTimer();
        }

        // Download swing data as zip file
        async function downloadSwings() {
            if (swingData.length === 0) {
                alert('No swing data to download!');
                return;
            }

            const strokeType = document.getElementById('strokeType').value.trim();
            log(`Creating zip file for ${swingData.length} swings...`);

            try {
                const zip = new JSZip();
                
                // Add each swing as a separate CSV file
                swingData.forEach((swing, index) => {
                    const filename = `${strokeType}${(index + 1).toString().padStart(4, '0')}.csv`;
                    zip.file(filename, swing.csv);
                });
                
                // Generate zip file
                const content = await zip.generateAsync({type: 'blob'});
                
                // Create download link
                const url = URL.createObjectURL(content);
                const a = document.createElement('a');
                a.href = url;
                a.download = `${strokeType}.zip`;
                document.body.appendChild(a);
                a.click();
                document.body.removeChild(a);
                URL.revokeObjectURL(url);
                
                log(`Downloaded: ${strokeType}.zip (${swingData.length} files)`);
                
            } catch (error) {
                log(`Download failed: ${error.message}`);
                alert('Download failed. Please try again.');
            }
        }

        // Reset session
        function resetSession() {
            if (confirm('Reset session and clear all data?')) {
                // Disconnect if connected
                if (isConnected && bleDevice) {
                    bleDevice.gatt.disconnect();
                }
                
                // Reset UI
                isConnected = false;
                updateConnectionStatus('disconnected');
                document.getElementById('sessionPanel').classList.add('hidden');
                document.getElementById('connectBtn').disabled = false;
                document.getElementById('strokeType').disabled = false;
                document.getElementById('strokeType').value = '';
                document.getElementById('currentStroke').textContent = '-';
                document.getElementById('swingCount').textContent = '0';
                document.getElementById('sessionTime').textContent = '00:00';
                
                // Clear data
                swingData = [];
                swingCount = 0;
                currentSwingBuffer = '';
                
                stopSessionTimer();
                log('Session reset');
            }
        }

        // Check for Web Bluetooth support
        window.addEventListener('load', () => {
            if (!navigator.bluetooth) {
                alert('Web Bluetooth is not supported. Please use Chrome on Android or enable experimental features.');
                log('Web Bluetooth not supported');
            } else {
                log('Web Bluetooth supported - ready to connect');
            }
        });
    </script>
</body>
</html>

smart-table-tennis-bat-with-edge-impulse.git

Credits

Samuel Alexander
7 projects • 32 followers

Comments