diff --git a/sketch_timecube/Makefile b/sketch_timecube/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..820dcda9677c094388c03fe314284c50d3e5ac64
--- /dev/null
+++ b/sketch_timecube/Makefile
@@ -0,0 +1,108 @@
+TTY=$(shell ls -1 /dev/ttyUSB* | rev | sort -rn | rev | head -n1)
+
+#
+# Folder Configuration
+#
+ARDU_BASE=${HOME}/Arduino/
+ESP32_BASE=${HOME}/.arduino15/packages/esp32/
+FB_BASE=${ESP32_BASE}/hardware/DFRobot_FireBeetle-ESP32/0.0.9/
+
+#
+# Tool Configuration
+#
+CC=${ESP32_BASE}/tools/xtensa-esp32-elf-gcc/1.22.0-61-gab8375a-5.2.0/bin/xtensa-esp32-elf-gcc
+CXX=${ESP32_BASE}/tools/xtensa-esp32-elf-gcc/1.22.0-61-gab8375a-5.2.0/bin/xtensa-esp32-elf-g++
+ESPPART=python ${FB_BASE}/tools/gen_esp32part.py
+ESPTOOL=python ${FB_BASE}/tools/esptool.py
+
+
+#
+# (System) Include Configuration
+#
+ESP32_INCL_BASE=${FB_BASE}/tools/sdk/include/
+ESP32_INCL_FILES=$(wildcard ${ESP32_INCL_BASE}/*) ${FB_BASE}/cores/esp32 ${FB_BASE}/variants/firebeetle32 ${FB_BASE}/libraries/SPI/src ${FB_BASE}/libraries/WiFi/src
+ESP32_INCL=$(ESP32_INCL_FILES:%=-isystem%)
+
+
+#
+# Compiler Flag Configuration
+#
+CCXXFLAGS =-Os -g3 -flto -Wall -pedantic -Wextra -Wpointer-arith
+CCXXFLAGS+=-nostdlib -ffunction-sections -fdata-sections -fstrict-volatile-bitfields -mlongcalls
+CCXXFLAGS+=-DESP_PLATFORM -DMBEDTLS_CONFIG_FILE=\"mbedtls/esp_config.h\" -DHAVE_CONFIG_H
+CCXXFLAGS+=-DF_CPU=120000000L -DARDUINO=10809 -DARDUINO_ESP32_DEV -DARDUINO_BOARD=\"ESP32_DEV\" -DARDUINO_VARIANT=\"firebeetle32\" -DESP32 -DCORE_DEBUG_LEVEL=0
+# CCXXFLAGS+=-DARDUINO_ARCH_DFROBOT_FIREBEETLE-ESP32 # invalid define emitted by arduino; omitted here
+CCXXFLAGS+=${ESP32_INCL}
+
+CFLAGS=${CCXXFLAGS} -std=gnu11
+CXXFLAGS=${CCXXFLAGS} -std=gnu++11 -fno-rtti
+
+
+#
+# find source files for core files and libraries
+#
+SRC_CORE=$(shell find ${FB_BASE}/cores/esp32/ -type f)
+SRC_FB=  $(shell find ${FB_BASE}/variants/firebeetle32/ -type f)
+SRC_SPI= $(shell find ${FB_BASE}/libraries/SPI/src/ -type f)
+SRC_WIFI=$(shell find ${FB_BASE}/libraries/WiFi/src/ -type f)
+
+SRC_CORE_C=$(filter %.c,${SRC_CORE})
+SRC_FB_C=  $(filter %.c,${SRC_FB})
+SRC_SPI_C= $(filter %.c,${SRC_SPI})
+SRC_WIFI_C=$(filter %.c,${SRC_WIFI})
+
+SRC_CORE_CXX=$(filter %.cpp,${SRC_CORE})
+SRC_FB_CXX=  $(filter %.cpp,${SRC_FB})
+SRC_SPI_CXX= $(filter %.cpp,${SRC_SPI})
+SRC_WIFI_CXX=$(filter %.cpp,${SRC_WIFI})
+
+OBJ_CORE=$(SRC_CORE_C:%.c=%.o) $(SRC_CORE_CXX:%.cpp=%.o)
+OBJ_FB=  $(SRC_FB_C:%.c=%.o)   $(SRC_FB_CXX:%.cpp=%.o)
+OBJ_SPI= $(SRC_SPI_C:%.c=%.o)  $(SRC_SPI_CXX:%.cpp=%.o)
+OBJ_WIFI=$(SRC_WIFI_C:%.c=%.o) $(SRC_WIFI_CXX:%.cpp=%.o)
+
+ALL_OBJ=${OBJ_CORE} ${OBJ_FB} ${OBJ_SPI} ${OBJ_WIFI}
+
+
+#
+# Precompiled libs to link against (default: all)
+#
+LIBS=gcc openssl btdm_app fatfs wps coexist wear_levelling hal newlib driver bootloader_support pp mesh smartconfig jsmn wpa ethernet phy app_trace console ulp wpa_supplicant freertos bt micro-ecc cxx xtensa-debug-module mdns vfs soc core sdmmc coap tcpip_adapter c_nano rtc spi_flash wpa2 esp32 app_update nghttp spiffs espnow nvs_flash esp_adc_cal log expat m c heap mbedtls lwip net80211 pthread json stdc++
+
+#
+# Linker scripts to use
+#
+LSCRIPTS=esp32_out.ld esp32.common.ld esp32.rom.ld esp32.peripherals.ld esp32.rom.spiram_incompatible_fns.ld
+
+#
+# Rules
+#
+
+all: sketch_timecube.bin
+
+sketch_timecube.elf: sketch_timecube.o accelerometer.o ${ALL_OBJ}
+	@echo LD $@
+	@$(CC) -nostdlib -flto -L${FB_BASE}/tools/sdk/lib -L${FB_BASE}/tools/sdk/ld $(LSCRIPTS:%=-T %) \
+		-Wl,--gc-sections -Wl,-static -Wl,--undefined=uxTopUsedPriority -u ld_include_panic_highint_hdl -u call_user_start_cpu0 -u __cxa_guard_dummy -u __cxx_fatal_exception \
+		-Wl,--start-group $^ $(LIBS:%=-l%) -Wl,--end-group -Wl,-EL -o $@
+
+%.o: %.cpp
+	@echo CXX $<
+	@$(CXX) $(CXXFLAGS) -c $< -o $@
+
+%.o: %.c
+	@echo CC $<
+	@$(CC) $(CFLAGS) -c $< -o $@
+
+partitions.bin: ${FB_BASE}/tools/partitions/no_ota.csv
+	${ESPPART} --disable-md5sum -q ${FB_BASE}/tools/partitions/no_ota.csv partitions.bin
+
+%.bin: %.elf
+	${ESPTOOL} --chip esp32 elf2image --flash_mode dio --flash_freq 80m --flash_size 4MB -o $@ $<
+
+flash: sketch_timecube.bin partitions.bin ${FB_BASE}/tools/sdk/bin/bootloader.bin ${FB_BASE}/tools/partitions/boot_app0.bin
+	@echo FLASH $< to ${TTY}
+	@${ESPTOOL} --chip esp32 --port ${TTY} --baud 460800 --before default_reset --after hard_reset write_flash -z --flash_freq 80m --flash_mode dio --flash_size 4MB 0x1000 ${FB_BASE}/tools/sdk/bin/bootloader.bin 0x8000 partitions.bin 0xe000 ${FB_BASE}/tools/partitions/boot_app0.bin 0x10000 sketch_timecube.bin
+
+print-%:
+	@echo $* = $($*)
diff --git a/sketch_timecube/sketch_timecube.cpp b/sketch_timecube/sketch_timecube.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..975488a24b88d7c761e743ee1efd99ca0acaa013
--- /dev/null
+++ b/sketch_timecube/sketch_timecube.cpp
@@ -0,0 +1,441 @@
+#include <Arduino.h>
+#include <WiFi.h>
+#include <esp_bt.h>
+#include <esp_wifi.h>
+#include <esp_wpa2.h>
+#include <esp_sleep.h>
+#include <driver/gpio.h>
+#include <driver/rtc_io.h>
+#include <driver/adc.h>
+
+#include "accelerometer.h"
+#include "config.h"
+
+#ifdef SERIAL_DEBUG
+#define SDBG(MSG) Serial.print(MSG)
+#define SDBGF(MSG, ...) Serial.printf(MSG, __VA_ARGS__)
+#define SDBGLN(MSG) Serial.println(MSG)
+#else
+#define SDBG(MSG)
+#define SDBGF(MSG, ...)
+#define SDBGLN(MSG)
+#endif
+
+
+void resetSystem();
+
+
+const uint8_t side_translate[6] = SIDE_MAPPING;
+RTC_DATA_ATTR uint8_t timelog_entry = 0;
+RTC_DATA_ATTR time_t timelog[TIMELOG_MAX];
+RTC_DATA_ATTR time_t wakeup = SYNC_INTERVAL;
+
+RTC_DATA_ATTR unsigned deep_sleep = 0;
+RTC_DATA_ATTR unsigned sync_counter = 0;
+RTC_DATA_ATTR unsigned bug_counter = 0;
+
+RTC_DATA_ATTR bool wifi_active = false;
+
+static_assert(sizeof(time_t) == 4, "time_t Size");
+
+static Accelerometer accel = Accelerometer(ACCEL_CS_PIN);
+static hw_timer_t *timer = nullptr;
+
+const uint8_t UNKNOWN_BATTERY = 0xFF;
+static uint8_t getBattery() {
+  static uint8_t battery = UNKNOWN_BATTERY;
+
+  if(UNKNOWN_BATTERY == battery) {
+    SDBGLN("Reading Battery State via ADC:");
+
+    SDBGLN(" * Starting ADC...");
+    adc_power_on();
+    analogSetAttenuation(ADC_11db);
+    analogReadResolution(12);
+
+    SDBGLN(" * Read from ADC...");
+    int val = analogRead(A0);
+
+    SDBGLN(" * Stopping ADC...");
+    adc_power_off();
+
+    SDBGF(" * Voltage from ADC: %d\n", val);
+    if (val > BATTERY_MAX) {
+      battery = 100;
+    } else if (val < BATTERY_MIN) {
+      battery = 0;
+    } else {
+      battery = (val - BATTERY_MIN) * 100 / (BATTERY_MAX - BATTERY_MIN);
+    }
+    SDBGF(" * Battery State from ADC: %d%%\n", battery);
+  } else {
+    SDBGF("Using Battery State from Previous Call: %d%%\n", battery);
+  }
+
+  return battery;
+}
+
+static uint8_t getSide() {
+  uint8_t state = accel.getMovement();
+  for (uint8_t p = 0; p < 6; p++){
+    if ((state & 0x3f) == (1 << p))
+      return side_translate[p];
+  }
+  return 0;
+}
+
+static uint8_t getStableSide(){
+  // Get current side
+  uint8_t side_last = getSide();
+  // try to save power during sleep
+  esp_sleep_enable_timer_wakeup(SIDE_DELAY * 1000);
+  // we need SIDE_COUNT stable reads
+  for (uint8_t n = 0 ; n < SIDE_COUNT ; n++){
+    // try light sleep, fall back to delay
+    if (esp_light_sleep_start() != ESP_OK){
+      SDBGLN("delay");
+      delay(SIDE_DELAY);
+    }
+    // Update Side
+    uint8_t side = getSide();
+    // check if stable or reset
+    if (side_last != side){
+      side_last = side;
+      n = 0;
+    }
+  }
+  return side_last;
+}
+
+
+/*! \brief Check active side (and create entry in timelog if changed)
+ *  \param forceNewEntry create a new entry in timelog even if the side hasnt changed
+ *  \return true if a new entry was created
+ */
+static bool checkSide(bool forceNewEntry = false){
+  uint8_t side = getStableSide();
+  if (timelog_entry < TIMELOG_MAX && (forceNewEntry || timelog_entry == 0 || side != (timelog[timelog_entry - 1] & 0x7))){
+    time_t timestamp;
+    time(&timestamp);
+    timestamp &= ~(0x7);
+    timestamp |= side;
+    timelog[timelog_entry++] = timestamp;
+    SDBGF("Derzeit akive Seite: %d\n", side);
+    return true;
+  }
+  return false;
+}
+
+/*! \brief Connect to WLAN using given credentials
+ */
+static void wlanSetup(){
+  // Disconnect previous WLAN session (although there shouldn't be any)
+  WiFi.disconnect(true);
+
+  SDBG("Connecting to WLAN " WLAN_SSID);
+  WiFi.mode(WIFI_STA);
+  #ifdef WLAN_IDENTITY
+  SDBGLN(" using EAP");
+  // Use EAP
+  esp_wifi_sta_wpa2_ent_set_identity((uint8_t *)WLAN_ANONYMOUS_IDENTITY, strlen(WLAN_ANONYMOUS_IDENTITY));
+  esp_wifi_sta_wpa2_ent_set_username((uint8_t *)WLAN_IDENTITY, strlen(WLAN_IDENTITY));
+  esp_wifi_sta_wpa2_ent_set_password((uint8_t *)WLAN_PASSWORD, strlen(WLAN_PASSWORD));
+  esp_wpa2_config_t wlan_config = WPA2_CONFIG_INIT_DEFAULT();
+  esp_wifi_sta_wpa2_ent_enable(&wlan_config);
+  WiFi.begin(WLAN_SSID);
+  #else
+  SDBGLN();
+  // Simple connection
+  WiFi.begin(WLAN_SSID, WLAN_PASSWORD);
+  #endif
+  wifi_active = true;
+}
+
+/*! \brief Wait for WLAN connection
+ *  \return true on success, false if timed out
+ */
+static bool wlanConnect(){
+  int stat, prev = 0;
+  for (int c = 0; (stat = WiFi.status()) != WL_CONNECTED ; c++) {
+    delay(WLAN_RECONNECT_DELAY);
+    if (stat != prev) {
+      prev = stat;
+      switch (stat) {
+        case WL_NO_SHIELD:       SDBG("[no WLAN Shield]");       break;
+        case WL_IDLE_STATUS:     SDBG("[WLAN Idle]");            break;
+        case WL_NO_SSID_AVAIL:   SDBG("[no WLAN SSID]");         break;
+        case WL_SCAN_COMPLETED:  SDBG("[WLAN scan completed]");  break;
+        case WL_CONNECT_FAILED:  SDBG("[WLAN connect failed]");  break;
+        case WL_CONNECTION_LOST: SDBG("[WLAN connection lost]"); break;
+        case WL_DISCONNECTED:    SDBG("[WLAN disconnected]");    break;
+        default: SDBG("[WLAN status unknown]");
+      }
+    }
+    SDBG(".");
+    if (c >= WLAN_RECONNECT_TRIES) {
+      SDBGLN("Keine WLAN Verbindung moeglich");
+      return false;
+    }
+  }
+  return true;
+}
+
+/*! \brief Update RTC using NTP
+ * \return false if no WLAN connection available
+ */
+static bool updateTime() {
+  // NTP
+  time_t old_ts;
+  time(&old_ts);
+
+  if (!wlanConnect()) {
+    return false;
+  }
+
+  configTime(0, 0, SYNC_NTP1, SYNC_NTP2, SYNC_NTP3);
+  delay(300);
+
+  time_t new_ts;
+  time(&new_ts);
+
+  // check if we have an initial update
+  if (old_ts < RTC_TIMESTAMP_THS && new_ts > RTC_TIMESTAMP_THS) {
+    SDBGLN("Aktualisiere Timelog mit neuer Uhrzeit");
+    uint32_t delta = new_ts - old_ts;
+    // Update entries
+    delta &= ~(0x7);
+    for (int i = 0; i < timelog_entry; i++)
+        timelog[i] += delta;
+  }
+
+  return true;
+}
+
+static bool uploadData(){
+  if(wlanConnect()) {
+    uint64_t mac = ESP.getEfuseMac();
+    uint8_t battery = getBattery();
+    time_t now;
+    time(&now);
+
+    // Debug status
+    const size_t content_length = (timelog_entry == 0) ? 15 : (17 + timelog_entry * 9);
+    #ifdef SERIAL_DEBUG
+    {
+      SDBGF("Trying to send %d timelog entries (Content-Length: %d Bytes) to " SYNC_HTTP_HOST "\n", timelog_entry, content_length);
+      SDBGF(" MAC: %04X%08X\n",(uint16_t)(mac>>32), (uint32_t)mac);
+      SDBGF(" Battery: %d%%\n", battery);
+      SDBGF(" Current Time: %ld\n", now);
+      SDBGLN(" Data:");
+      for (int i = 0; i < timelog_entry; i++){
+        const uint8_t  side = timelog[i] & 0x7;
+        const uint32_t ts   = timelog[i] & ~(0x7);
+        SDBGF("  [%d] = at %d -> side %d\n", i, ts, side);
+      }
+    }
+    #endif
+
+    WiFiClient client;
+    client.setTimeout(1500);
+    if (client.connect(SYNC_HTTP_HOST, 80)) {
+      client.printf("POST /%04X%08X/upload HTTP/1.1\r\n", (uint16_t)(mac>>32), (uint32_t)mac);
+      client.print ("Host: " SYNC_HTTP_HOST "\r\n");
+      client.print ("User-Agent: i4Zeitwuerfel\r\n");
+      client.print ("Content-Type: application/x-www-form-urlencoded\r\n");
+      client.printf("Content-Length: %d\r\n\r\n", content_length);
+
+      client.printf("v=%02X&t=%08X", battery, now);
+      if (timelog_entry > 0) {
+        client.printf("&d=%08X", timelog[0]);
+        for (int i = 1; i < timelog_entry; i++) {
+          client.printf("+%08X", timelog[i]);
+        }
+      }
+
+      SDBGLN(" Response from " SYNC_HTTP_HOST ":");
+      for (int t = 0; t<20 && client.connected();t++) {
+        String line = client.readStringUntil('\n');
+        SDBGF("  [line %d] %s\n", t, line.c_str());
+        if (line == "HTTP/1.1 200 OK\r" || line == "HTTP/1.0 200 OK\r") {
+          return true;
+        }
+        if (line == "\r") {
+          break;
+        }
+      }
+    } else
+      SDBGLN("Verbindungsprobleme");
+  }
+  return false;
+}
+
+static bool sync() {
+  wlanSetup();
+
+  if (!wlanConnect())
+    return false;
+
+  SDBGF("IP: %s\n", WiFi.localIP().toString().c_str());
+  delay(WLAN_RECONNECT_DELAY);
+
+  bool ret = true;
+  if (!updateTime()){
+    ret = false;
+    SDBGLN("NTP fehlgeschlagen");
+  }
+
+  if (uploadData()) {
+    // Reset entries
+    timelog[0] = timelog[timelog_entry - 1];
+    timelog_entry = 1;
+    SDBGLN("HTTP Upload erfolgreich");
+  } else {
+    ret = false;
+    SDBGLN("HTTP Upload fehlgeschlagen");
+  }
+
+  WiFi.disconnect(true);
+
+  return ret;
+}
+
+static void gotoDeepSleep(unsigned long long wakeupTime, bool force = false) {
+  SDBGF("Preparing for Sleep #%d:\n", ++deep_sleep);
+
+  if(wifi_active && !force) {
+    SDBGLN(" * Powering down WiFi...");
+    esp_wifi_stop();
+    wifi_active = false;
+  }
+
+  esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
+  rtc_gpio_isolate(ACCEL_INT_PIN);
+
+  esp_sleep_enable_ext0_wakeup(ACCEL_INT_PIN, 1);
+  esp_sleep_enable_timer_wakeup(wakeupTime);
+
+  SDBGLN(" * Stopping Watchdog...");
+  timerAlarmDisable(timer);
+  timerEnd(timer);
+
+  SDBGLN(" * Entering deep sleep...");
+#ifdef SERIAL_DEBUG
+  Serial.flush();
+#endif
+  esp_deep_sleep_start();
+}
+
+void setup() {
+  #ifdef SERIAL_DEBUG
+  // Initialize Serial connection for debug output
+  Serial.begin(SERIAL_DEBUG);
+  #endif
+
+  // Wait 10 ms
+  delay(10);
+
+  SDBGF("Starting Watchdog (Bug Counter: %d)...\n", bug_counter);
+  #define DEINIT_TIMEOUT (60 * 1000 * 1000)
+  timer = timerBegin(0, 80, true);
+  timerAttachInterrupt(timer, &resetSystem, true);
+  timerAlarmWrite(timer, DEINIT_TIMEOUT, false);
+  timerAlarmEnable(timer);
+
+  // disable unused components on first start
+  if(0 == deep_sleep) {
+    SDBGLN("Powering down BT and ADC...");
+    esp_bt_controller_disable();
+    adc_power_off();
+  }
+
+
+  // Light blue LED (on FireBeetle)
+  pinMode(STATUS_LED_PIN, OUTPUT);
+  digitalWrite(STATUS_LED_PIN, HIGH);
+
+  // print current timestamp to serial (debugging)
+  {
+    time_t now;
+    time(&now);
+    SDBGF("Wakeup at %ld\n", now);
+  }
+
+  // Set up Accelerometer
+  if (!accel.begin()) {
+    SDBGLN("Beschleunigungssensor antwortet nicht.");
+  } else {
+    accel.setClickInterrupt(3, ACCEL_CLICK_THS);
+    accel.setMovementInterrupt();
+  }
+
+  // Get Wakeup source
+  esp_sleep_wakeup_cause_t wakeup_reason = esp_sleep_get_wakeup_cause();
+  SDBG("Wakeup reason: ");
+  switch(wakeup_reason) {
+    // Valid
+    case 0: SDBGLN("Reboot"); break;
+    case ESP_SLEEP_WAKEUP_EXT0:  SDBGLN("EXT0");  break;
+    case ESP_SLEEP_WAKEUP_TIMER: SDBGLN("Timer"); break;
+
+    // Invalid
+    case ESP_SLEEP_WAKEUP_EXT1:     SDBGLN("EXT1 (should not happen)");        break;
+    case ESP_SLEEP_WAKEUP_TOUCHPAD: SDBGLN("Touchpad (should not happen)");    break;
+    case ESP_SLEEP_WAKEUP_ULP:      SDBGLN("ULP (should not happen)");         break;
+    default : SDBGF("Unknown reason %d (should not happen)\n", wakeup_reason); break;
+  }
+
+  // Do we need an WLAN synchronization?
+  bool update = (wakeup_reason == ESP_SLEEP_WAKEUP_TIMER) || (wakeup_reason == ESP_SLEEP_WAKEUP_UNDEFINED) || (timelog_entry > TIMELOG_MAX);
+
+  // check tap
+  uint8_t click = accel.getClick();
+  if (click != 0 && (click & 0x30)){
+    SDBGLN("Synchronisiere aufgrund von Klopfen");
+    update = true;
+  }
+
+  // Timer wakeup
+  time_t now;
+  time(&now);
+  if (now >= wakeup) {
+    update = true;
+  }
+
+  // check side
+  checkSide(update);
+
+  // do update
+  if (update){
+     SDBGF("Sync #%d\n", ++sync_counter);
+     sync();
+
+     // New Timer Wakeup
+     time(&now);
+     wakeup = now + SYNC_INTERVAL;
+
+     // safety - if wlan connection was slow, lets check current side again, maybe it has been flipped meanwhile
+     checkSide();
+  }
+
+  // calculate next wakeup
+  if (wakeup - now < 1) {
+    wakeup = now + 1;
+  }
+  gotoDeepSleep((wakeup - now) * 1000000ULL);
+}
+
+void resetSystem() {
+  ++bug_counter;
+
+  SDBGLN("-=================-");
+  SDBGLN("|~~~    BUG    ~~~|");
+  SDBGLN("-=================-");
+
+  SDBGF("[BUG %d] Watchdog triggered; Resetting System\n", bug_counter);
+#ifdef SERIAL_DEBUG
+  Serial.flush();
+#endif
+  gotoDeepSleep(5 * 1000ULL * 1000ULL, /* force = */ true);
+}
+
+void loop() { /* This is never going to be called due to deep sleep. */ }
diff --git a/sketch_timecube/sketch_timecube.ino b/sketch_timecube/sketch_timecube.ino
index adddb5e4ede40068273d4ee87097dcfe78fed979..2f804299452188c83b372e54f4b2bca85493df2d 100644
--- a/sketch_timecube/sketch_timecube.ino
+++ b/sketch_timecube/sketch_timecube.ino
@@ -1,436 +1,4 @@
-#include <WiFi.h>
-#include <esp_bt.h>
-#include <esp_wifi.h>
-#include <esp_wpa2.h>
-#include <esp_sleep.h>
-#include <driver/gpio.h>
-#include <driver/rtc_io.h>
-#include <driver/adc.h>
-
-#include "accelerometer.h"
-#include "config.h"
-
-#ifdef SERIAL_DEBUG
-#define SDBG(MSG) Serial.print(MSG)
-#define SDBGF(MSG, ...) Serial.printf(MSG, __VA_ARGS__)
-#define SDBGLN(MSG) Serial.println(MSG)
-#else
-#define SDBG(MSG)
-#define SDBGF(MSG, ...)
-#define SDBGLN(MSG)
-#endif
-
-const uint8_t side_translate[6] = SIDE_MAPPING;
-RTC_DATA_ATTR uint8_t timelog_entry = 0;
-RTC_DATA_ATTR time_t timelog[TIMELOG_MAX];
-RTC_DATA_ATTR time_t wakeup = SYNC_INTERVAL;
-
-RTC_DATA_ATTR unsigned deep_sleep = 0;
-RTC_DATA_ATTR unsigned sync_counter = 0;
-RTC_DATA_ATTR unsigned bug_counter = 0;
-
-RTC_DATA_ATTR bool wifi_active = false;
-
-static_assert(sizeof(time_t) == 4, "time_t Size");
-
-static Accelerometer accel = Accelerometer(ACCEL_CS_PIN);
-static hw_timer_t *timer = nullptr;
-
-const uint8_t UNKNOWN_BATTERY = 0xFF;
-static uint8_t getBattery() {
-  static uint8_t battery = UNKNOWN_BATTERY;
-
-  if(UNKNOWN_BATTERY == battery) {
-    SDBGLN("Reading Battery State via ADC:");
-
-    SDBGLN(" * Starting ADC...");
-    adc_power_on();
-    analogSetAttenuation(ADC_11db);
-    analogReadResolution(12);
-
-    SDBGLN(" * Read from ADC...");
-    int val = analogRead(A0);
-
-    SDBGLN(" * Stopping ADC...");
-    adc_power_off();
-
-    SDBGF(" * Voltage from ADC: %d\n", val);
-    if (val > BATTERY_MAX) {
-      battery = 100;
-    } else if (val < BATTERY_MIN) {
-      battery = 0;
-    } else {
-      battery = (val - BATTERY_MIN) * 100 / (BATTERY_MAX - BATTERY_MIN);
-    }
-    SDBGF(" * Battery State from ADC: %d%%\n", battery);
-  } else {
-    SDBGF("Using Battery State from Previous Call: %d%%\n", battery);
-  }
-
-  return battery;
-}
-
-static uint8_t getSide() {
-  uint8_t state = accel.getMovement();
-  for (uint8_t p = 0; p < 6; p++){
-    if ((state & 0x3f) == (1 << p))
-      return side_translate[p];
-  }
-  return 0;
-}
-
-static uint8_t getStableSide(){
-  // Get current side
-  uint8_t side_last = getSide();
-  // try to save power during sleep
-  esp_sleep_enable_timer_wakeup(SIDE_DELAY * 1000);
-  // we need SIDE_COUNT stable reads
-  for (uint8_t n = 0 ; n < SIDE_COUNT ; n++){
-    // try light sleep, fall back to delay
-    if (esp_light_sleep_start() != ESP_OK){
-      SDBGLN("delay");
-      delay(SIDE_DELAY);
-    }
-    // Update Side
-    uint8_t side = getSide();
-    // check if stable or reset
-    if (side_last != side){
-      side_last = side;
-      n = 0;
-    }
-  }
-  return side_last;
-}
-
-
-/*! \brief Check active side (and create entry in timelog if changed)
- *  \param forceNewEntry create a new entry in timelog even if the side hasnt changed
- *  \return true if a new entry was created
- */
-static bool checkSide(bool forceNewEntry = false){
-  uint8_t side = getStableSide();
-  if (timelog_entry < TIMELOG_MAX && (forceNewEntry || timelog_entry == 0 || side != (timelog[timelog_entry - 1] & 0x7))){
-    time_t timestamp;
-    time(&timestamp);
-    timestamp &= ~(0x7);
-    timestamp |= side;
-    timelog[timelog_entry++] = timestamp;
-    SDBGF("Derzeit akive Seite: %d\n", side);
-    return true;
-  }
-  return false;
-}
-
-/*! \brief Connect to WLAN using given credentials
- */
-static void wlanSetup(){
-  // Disconnect previous WLAN session (although there shouldn't be any)
-  WiFi.disconnect(true);
-
-  SDBG("Connecting to WLAN " WLAN_SSID);
-  WiFi.mode(WIFI_STA);
-  #ifdef WLAN_IDENTITY
-  SDBGLN(" using EAP");
-  // Use EAP
-  esp_wifi_sta_wpa2_ent_set_identity((uint8_t *)WLAN_ANONYMOUS_IDENTITY, strlen(WLAN_ANONYMOUS_IDENTITY));
-  esp_wifi_sta_wpa2_ent_set_username((uint8_t *)WLAN_IDENTITY, strlen(WLAN_IDENTITY));
-  esp_wifi_sta_wpa2_ent_set_password((uint8_t *)WLAN_PASSWORD, strlen(WLAN_PASSWORD));
-  esp_wpa2_config_t wlan_config = WPA2_CONFIG_INIT_DEFAULT();
-  esp_wifi_sta_wpa2_ent_enable(&wlan_config);
-  WiFi.begin(WLAN_SSID);
-  #else
-  SDBGLN();
-  // Simple connection
-  WiFi.begin(WLAN_SSID, WLAN_PASSWORD);
-  #endif
-  wifi_active = true;
-}
-
-/*! \brief Wait for WLAN connection
- *  \return true on success, false if timed out
- */
-static bool wlanConnect(){
-  int stat, prev = 0;
-  for (int c = 0; (stat = WiFi.status()) != WL_CONNECTED ; c++) {
-    delay(WLAN_RECONNECT_DELAY);
-    if (stat != prev) {
-      prev = stat;
-      switch (stat) {
-        case WL_NO_SHIELD:       SDBG("[no WLAN Shield]");       break;
-        case WL_IDLE_STATUS:     SDBG("[WLAN Idle]");            break;
-        case WL_NO_SSID_AVAIL:   SDBG("[no WLAN SSID]");         break;
-        case WL_SCAN_COMPLETED:  SDBG("[WLAN scan completed]");  break;
-        case WL_CONNECT_FAILED:  SDBG("[WLAN connect failed]");  break;
-        case WL_CONNECTION_LOST: SDBG("[WLAN connection lost]"); break;
-        case WL_DISCONNECTED:    SDBG("[WLAN disconnected]");    break;
-        default: SDBG("[WLAN status unknown]");
-      }
-    }
-    SDBG(".");
-    if (c >= WLAN_RECONNECT_TRIES) {
-      SDBGLN("Keine WLAN Verbindung moeglich");
-      return false;
-    }
-  }
-  return true;
-}
-
-/*! \brief Update RTC using NTP
- * \return false if no WLAN connection available
- */
-static bool updateTime() {
-  // NTP
-  time_t old_ts;
-  time(&old_ts);
-
-  if (!wlanConnect()) {
-    return false;
-  }
-
-  configTime(0, 0, SYNC_NTP1, SYNC_NTP2, SYNC_NTP3);
-  delay(300);
-
-  time_t new_ts;
-  time(&new_ts);
-
-  // check if we have an initial update
-  if (old_ts < RTC_TIMESTAMP_THS && new_ts > RTC_TIMESTAMP_THS) {
-    SDBGLN("Aktualisiere Timelog mit neuer Uhrzeit");
-    uint32_t delta = new_ts - old_ts;
-    // Update entries
-    delta &= ~(0x7);
-    for (int i = 0; i < timelog_entry; i++)
-        timelog[i] += delta;
-  }
-
-  return true;
-}
-
-static bool uploadData(){
-  if(wlanConnect()) {
-    uint64_t mac = ESP.getEfuseMac();
-    uint8_t battery = getBattery();
-    time_t now;
-    time(&now);
-
-    // Debug status
-    const size_t content_length = (timelog_entry == 0) ? 15 : (17 + timelog_entry * 9);
-    #ifdef SERIAL_DEBUG
-    {
-      SDBGF("Trying to send %d timelog entries (Content-Length: %d Bytes) to " SYNC_HTTP_HOST "\n", timelog_entry, content_length);
-      SDBGF(" MAC: %04X%08X\n",(uint16_t)(mac>>32), (uint32_t)mac);
-      SDBGF(" Battery: %d%%\n", battery);
-      SDBGF(" Current Time: %ld\n", now);
-      SDBGLN(" Data:");
-      for (int i = 0; i < timelog_entry; i++){
-        const uint8_t  side = timelog[i] & 0x7;
-        const uint32_t ts   = timelog[i] & ~(0x7);
-        SDBGF("  [%d] = at %d -> side %d\n", i, ts, side);
-      }
-    }
-    #endif
-
-    WiFiClient client;
-    client.setTimeout(1500);
-    if (client.connect(SYNC_HTTP_HOST, 80)) {
-      client.printf("POST /%04X%08X/upload HTTP/1.1\r\n", (uint16_t)(mac>>32), (uint32_t)mac);
-      client.print ("Host: " SYNC_HTTP_HOST "\r\n");
-      client.print ("User-Agent: i4Zeitwuerfel\r\n");
-      client.print ("Content-Type: application/x-www-form-urlencoded\r\n");
-      client.printf("Content-Length: %d\r\n\r\n", content_length);
-
-      client.printf("v=%02X&t=%08X", battery, now);
-      if (timelog_entry > 0) {
-        client.printf("&d=%08X", timelog[0]);
-        for (int i = 1; i < timelog_entry; i++) {
-          client.printf("+%08X", timelog[i]);
-        }
-      }
-
-      SDBGLN(" Response from " SYNC_HTTP_HOST ":");
-      for (int t = 0; t<20 && client.connected();t++) {
-        String line = client.readStringUntil('\n');
-        SDBGF("  [line %d] %s\n", t, line.c_str());
-        if (line == "HTTP/1.1 200 OK\r" || line == "HTTP/1.0 200 OK\r") {
-          return true;
-        }
-        if (line == "\r") {
-          break;
-        }
-      }
-    } else
-      SDBGLN("Verbindungsprobleme");
-  }
-  return false;
-}
-
-static bool sync() {
-  wlanSetup();
-
-  if (!wlanConnect())
-    return false;
-
-  SDBGF("IP: %s\n", WiFi.localIP().toString().c_str());
-  delay(WLAN_RECONNECT_DELAY);
-
-  bool ret = true;
-  if (!updateTime()){
-    ret = false;
-    SDBGLN("NTP fehlgeschlagen");
-  }
-
-  if (uploadData()) {
-    // Reset entries
-    timelog[0] = timelog[timelog_entry - 1];
-    timelog_entry = 1;
-    SDBGLN("HTTP Upload erfolgreich");
-  } else {
-    ret = false;
-    SDBGLN("HTTP Upload fehlgeschlagen");
-  }
-
-  WiFi.disconnect(true);
-
-  return ret;
-}
-
-static void gotoDeepSleep(unsigned long long wakeupTime, bool force = false) {
-  SDBGF("Preparing for Sleep #%d:\n", ++deep_sleep);
-
-  if(wifi_active && !force) {
-    SDBGLN(" * Powering down WiFi...");
-    esp_wifi_stop();
-    wifi_active = false;
-  }
-
-  esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
-  rtc_gpio_isolate(ACCEL_INT_PIN);
-
-  esp_sleep_enable_ext0_wakeup(ACCEL_INT_PIN, 1);
-  esp_sleep_enable_timer_wakeup(wakeupTime);
-
-  SDBGLN(" * Stopping Watchdog...");
-  timerAlarmDisable(timer);
-  timerEnd(timer);
-
-  SDBGLN(" * Entering deep sleep...");
-#ifdef SERIAL_DEBUG
-  Serial.flush();
-#endif
-  esp_deep_sleep_start();
-}
-
-void setup() {
-  #ifdef SERIAL_DEBUG
-  // Initialize Serial connection for debug output
-  Serial.begin(SERIAL_DEBUG);
-  #endif
-
-  // Wait 10 ms
-  delay(10);
-
-  SDBGF("Starting Watchdog (Bug Counter: %d)...\n", bug_counter);
-  #define DEINIT_TIMEOUT (60 * 1000 * 1000)
-  timer = timerBegin(0, 80, true);
-  timerAttachInterrupt(timer, &resetSystem, true);
-  timerAlarmWrite(timer, DEINIT_TIMEOUT, false);
-  timerAlarmEnable(timer);
-
-  // disable unused components on first start
-  if(0 == deep_sleep) {
-    SDBGLN("Powering down BT and ADC...");
-    esp_bt_controller_disable();
-    adc_power_off();
-  }
-
-
-  // Light blue LED (on FireBeetle)
-  pinMode(STATUS_LED_PIN, OUTPUT);
-  digitalWrite(STATUS_LED_PIN, HIGH);
-
-  // print current timestamp to serial (debugging)
-  {
-    time_t now;
-    time(&now);
-    SDBGF("Wakeup at %ld\n", now);
-  }
-
-  // Set up Accelerometer
-  if (!accel.begin()) {
-    SDBGLN("Beschleunigungssensor antwortet nicht.");
-  } else {
-    accel.setClickInterrupt(3, ACCEL_CLICK_THS);
-    accel.setMovementInterrupt();
-  }
-
-  // Get Wakeup source
-  esp_sleep_wakeup_cause_t wakeup_reason = esp_sleep_get_wakeup_cause();
-  SDBG("Wakeup reason: ");
-  switch(wakeup_reason) {
-    // Valid
-    case 0: SDBGLN("Reboot"); break;
-    case ESP_SLEEP_WAKEUP_EXT0:  SDBGLN("EXT0");  break;
-    case ESP_SLEEP_WAKEUP_TIMER: SDBGLN("Timer"); break;
-
-    // Invalid
-    case ESP_SLEEP_WAKEUP_EXT1:     SDBGLN("EXT1 (should not happen)");        break;
-    case ESP_SLEEP_WAKEUP_TOUCHPAD: SDBGLN("Touchpad (should not happen)");    break;
-    case ESP_SLEEP_WAKEUP_ULP:      SDBGLN("ULP (should not happen)");         break;
-    default : SDBGF("Unknown reason %d (should not happen)\n", wakeup_reason); break;
-  }
-
-  // Do we need an WLAN synchronization?
-  bool update = (wakeup_reason == ESP_SLEEP_WAKEUP_TIMER) || (wakeup_reason == ESP_SLEEP_WAKEUP_UNDEFINED) || (timelog_entry > TIMELOG_MAX);
-
-  // check tap
-  uint8_t click = accel.getClick();
-  if (click != 0 && (click & 0x30)){
-    SDBGLN("Synchronisiere aufgrund von Klopfen");
-    update = true;
-  }
-
-  // Timer wakeup
-  time_t now;
-  time(&now);
-  if (now >= wakeup) {
-    update = true;
-  }
-
-  // check side
-  checkSide(update);
-
-  // do update
-  if (update){
-     SDBGF("Sync #%d\n", ++sync_counter);
-     sync();
-
-     // New Timer Wakeup
-     time(&now);
-     wakeup = now + SYNC_INTERVAL;
-
-     // safety - if wlan connection was slow, lets check current side again, maybe it has been flipped meanwhile
-     checkSide();
-  }
-
-  // calculate next wakeup
-  if (wakeup - now < 1) {
-    wakeup = now + 1;
-  }
-  gotoDeepSleep((wakeup - now) * 1000000ULL);
-}
-
-void resetSystem() {
-  ++bug_counter;
-
-  SDBGLN("-=================-");
-  SDBGLN("|~~~    BUG    ~~~|");
-  SDBGLN("-=================-");
-
-  SDBGF("[BUG %d] Watchdog triggered; Resetting System\n", bug_counter);
-#ifdef SERIAL_DEBUG
-  Serial.flush();
-#endif
-  gotoDeepSleep(5 * 1000ULL * 1000ULL, /* force = */ true);
-}
-
-void loop() { /* This is never going to be called due to deep sleep. */ }
+/***********************************************
+ * For compatibility with arduino only.        *
+ * Write your code to corresponding .cpp file. *
+ **********************************************/