#include "BLEDevice.h"
#include "BLEScan.h"
//#include <Wire.h>
//#include <LiquidCrystal.h>
//LiquidCrystal lcd(0);
#include <FastLED.h>
#include <IRremote.h>
#include <Ticker.h>  //Call the ticker. H Library
#include <U8g2lib.h>
#ifdef U8X8_HAVE_HW_I2C
#include <Wire.h>
#endif
#include <freertos/FreeRTOS.h>
#include <freertos/message_buffer.h>
#include <freertos/projdefs.h>
U8G2_SSD1306_128X32_UNIVISION_F_SW_I2C u8g2(U8G2_R0, /* clock=*/21, /* data=*/22, /* reset=*/U8X8_PIN_NONE);  // Adafruit Feather ESP8266/32u4 Boards + FeatherWing OLED
Ticker ticker;
Ticker ticker1;
#define RECV_PIN 19       //Infrared receiving pin
IRrecv irrecv(RECV_PIN);  //Definition of infrared remote control pin
decode_results results;   //Define infrared remote control function
CRGB leds[4];               //Bottom RGB light
CRGB RGBleds[6];            //Ultrasonic RGB lamp
CRGB myRGBcolor(0, 0, 0);   //Bottom RGB
CRGB myRGBcolor6(0, 0, 0);  //Ultrasonic RGB
BLEScan* pBLEScan = NULL;
// The remote service we wish to connect to.
static BLEUUID serviceUUID("FFE0");  //Host service UUID
static BLEUUID charUUID("FFE1");
static boolean doConnect = false;                        //Connection sign
static boolean connected = false;                        //Connection success flag
static boolean doSacn = true;                            //Scan flag
static BLERemoteCharacteristic* pRemoteCharacteristic;   //Characteristic value sent by handle
static BLEAdvertisedDevice* pServer;
//Arduino docs It is emphasized that volatile must be used in variable declaration in case of concurrent threads (such as interrupts)
volatile int pwm_value = 0;  //Low level duration --- interruption
volatile int prev_time = 0;  //Record ultrasonic time --- interruption
volatile int distance = 0;   //Ultrasonic distance
int Close_Flag = 0;          //Turn off task flag
int BLE_Close = 0;           //Bluetooth off flag
int Ce_shi_Flag = 0;         //Test program flag
static int IR_Flag = 88;     //Infrared remote control sign
int shock_Flag = 0;          //Vibration sign
char CloseData;              //Receive serial port data during test
static int L = 0;            //Number of switch light signs
int num_L = 0;               //Save the left light seeking value
int num_R = 0;               //Save the right light seeking value
int i = 0;
static int rgb = 0;   //Bottom RGB
static int rgb6 = 0;  //Ultrasonic RGB
const int leftgo_Pin = 12;
const int lefttrun_Pin = 13;
const int rightgo_Pin = 14;
const int righttrun_Pin = 15;
const int Photodiode_R = 34, Photodiode_L = 35;  //Light seeking pin
int Ultrasonic_Pin = 27, Button_pin = 18;        //Ultrasonic and switch key pins
int QTI_Max, QTI_L = 39, QTI_R = 36;             //Line patrol pin
static int state_L;
uint32_t state_N;                     //Infrared remote control data recording
char LU[10];                                     //Save ultrasonic distance data
std::string value;
BLEClient* pClient = NULL;
BLERemoteService* pRemoteService = NULL;
#define  G4 392
#define  A4 440
#define  B4 494
#define  C5 523
#define  D5 587
#define  E5 659
#define  F5 698
#define  G5 784
#define C4 262
#define D4 294
#define E4 330
#define F4 349
int Tone[] = { 
             };
float Time[] = {
               }; 
int Tone_length = sizeof(Tone) / sizeof(Tone[0]);
SemaphoreHandle_t xPlayMusicSemaphore;
SemaphoreHandle_t xDisconnectedSemaphore;
MessageBufferHandle_t xGrcCmdBuffer;
typedef struct {
  const int* tones;     
  const float* times;   
  int length;           
} Melody;
const int happy_tones[] = {
  G4, G4, A4, G4, C5, B4,
  G4, G4, A4, G4, D5, C5,
  G4, G4, G5, E5, C5, B4, A4,
  F5, F5, E5, C5, D5, C5
};
const float happy_times[] = {
  0.5,0.5,1.0,1.0,1.0,2.0,
  0.5,0.5,1.0,1.0,1.0,2.0,
  0.5,0.5,1.0,1.0,1.0,1.0,2.0,
  0.5,0.5,1.0,1.0,1.0,2.0
};
const int twinkle_tones[] = {
  C4,C4,G4,G4,A4,A4,G4,
  F4,F4,E4,E4,D4,D4,C4
};
const float twinkle_times[] = {
  0.5,0.5,0.5,0.5,0.5,0.5,1.0,
  0.5,0.5,0.5,0.5,0.5,0.5,1.0
};
const int main_tones[] = {
    B4, B4, B4, B4, B4, B4,
    B4, D5, G4, A4, B4, C5,
    C5, C5, C5, C5, B4, B4, B4, D5,
    D5, C5, A4, G4, G5
};
const float main_times[] = {
    0.25, 0.25, 0.5, 0.25, 0.25, 0.5,
    0.25, 0.25, 0.375, 0.125, 1, 0.25,
    0.25, 0.25, 0.25, 0.25, 0.25, 0.25, 0.25, 0.25,
    0.25, 0.25, 0.25, 0.5, 0.5
};
Melody melodies[] = {
  { happy_tones, happy_times, sizeof(happy_tones)/sizeof(happy_tones[0]) },
  { twinkle_tones, twinkle_times, sizeof(twinkle_tones)/sizeof(twinkle_tones[0]) },
  {main_tones, main_times, sizeof(main_tones)/sizeof(main_tones[0])}
};
// ====== music -> dance communication ======
typedef struct {
  int freq;          
  int duration_ms;   
} MusicNoteEvent;
const int melodyCount = sizeof(melodies) / sizeof(melodies[0]);
QueueHandle_t xMusicQueue;
#define MAX_GRC_MSG_LEN 20
#define MOTOR_MIN_VALUE 15
#define MOTOR_MAX_VALUE 255
// --------- Racing tuning API ----------
struct RaceParams {
  float max_speed_scale = 1.0f;    
  float turn_scale = 1.0f;         
  float accel_coeff = 1.0f;        
};
RaceParams race;
// ---------- ADD AFTER RaceParams definition ----------
constexpr float MAX_SPEED_MIN = 0.5f;
constexpr float MAX_SPEED_MAX = 1.6f;
constexpr float TURN_MIN = 0.6f;
constexpr float TURN_MAX = 2.0f;
constexpr float ACCEL_MIN = 0.5f;
constexpr float ACCEL_MAX = 2.0f;
void presetSpeedDemon() {
  race.max_speed_scale = 1.4f;
  race.turn_scale = 1.05f;
  race.accel_coeff = 1.5f;
}
void presetDriftKing() {
  race.max_speed_scale = 1.1f;
  race.turn_scale = 1.6f;
  race.accel_coeff = 1.2f;
}
void presetSmoothRacer() {
  race.max_speed_scale = 0.9f;
  race.turn_scale = 0.9f;
  race.accel_coeff = 0.8f;
}
void presetEcoMode() {
  race.max_speed_scale = 0.7f;
  race.turn_scale = 1.0f;
  race.accel_coeff = 0.6f;
}
template<typename T>
T clampVal(T v, T lo, T hi) {
  return (v < lo) ? lo : (v > hi ? hi : v);
}
void initRaceDefaults() {
  race.max_speed_scale = 1.0f;
  race.turn_scale = 1.0f;
  race.accel_coeff = 1.0f;
}
SemaphoreHandle_t xSerialSemaphore;
void safePrint(const char* format, ...) {
  if (xSerialSemaphore != NULL) {
    if (xSemaphoreTake(xSerialSemaphore, portMAX_DELAY) == pdTRUE) {
      va_list args;
      va_start(args, format);
      vprintf(format, args);
      va_end(args);
      xSemaphoreGive(xSerialSemaphore);
    }
  }
}
void safePrintln(const char* message) {
  if (xSerialSemaphore != NULL) {
    if (xSemaphoreTake(xSerialSemaphore, portMAX_DELAY) == pdTRUE) {
      Serial.println(message);
      xSemaphoreGive(xSerialSemaphore);
    }
  }
}
static int target_lf=0, target_lb=0, target_rf=0, target_rb=0;
static int cur_lf=0, cur_lb=0, cur_rf=0, cur_rb=0;
static unsigned long last_ramp_ts = 0;
const int RAMP_INTERVAL_MS = 20; 
void setTargetMotor(int lf, int lb, int rf, int rb) {
  target_lf = lf;
  target_lb = lb;
  target_rf = rf;
  target_rb = rb;
  last_ramp_ts = millis();
}
void updateMotorRamp() {
  unsigned long now = millis();
  if (now - last_ramp_ts >= RAMP_INTERVAL_MS) {
    float step = race.accel_coeff * (MOTOR_MAX_VALUE / 10.0f);
    cur_lf += (target_lf > cur_lf) ? step : -step;
    cur_lb += (target_lb > cur_lb) ? step : -step;
    cur_rf += (target_rf > cur_rf) ? step : -step;
    cur_rb += (target_rb > cur_rb) ? step : -step;
    cur_lf = clampVal(cur_lf, 0, MOTOR_MAX_VALUE);
    cur_lb = clampVal(cur_lb, 0, MOTOR_MAX_VALUE);
    cur_rf = clampVal(cur_rf, 0, MOTOR_MAX_VALUE);
    cur_rb = clampVal(cur_rb, 0, MOTOR_MAX_VALUE);
    Motor(cur_lf, cur_lb, cur_rf, cur_rb);
    last_ramp_ts = now;
  }
}
template<class T>
constexpr const T& clamp(const T& v, const T& lo, const T& hi)
{
    return std::less<T>{}(v, lo) ? lo : std::less<T>{}(hi, v) ? hi : v;
}
void poly_transform(const float params[12], float x, float y, float *_x, float *_y) {
  *_x = params[0] + params[1] * x + params[2] * y +
              params[3] * powf(x, 2) + params[4] * x * y +
              params[5] * powf(y, 2);
  *_y = params[6 + 0] + params[6 + 1] * x + params[6 + 2] * y +
              params[6 + 3] * powf(x, 2) + params[6 + 4] * x * y +
              params[6 + 5] * powf(y, 2);
}
void led_callback()  //Callback function
{
  FastLED.show();
}
static bool moving_backwards = false;
void buzzer_callback()  //Callback function
{
  if (moving_backwards) {
    ledcWriteTone(2, G4);  //Buzzer
    delay(150);
    ledcWrite(2, 0);
  }
}
void adjustRaceFloat(float &field, float delta, float lo, float hi, const char *name) {
  field = clampVal(field + delta, lo, hi);
  Serial.printf("%s -> %.3f\n", name, field);
}
void adjustRaceInt(int &field, int delta, int lo, int hi, const char *name) {
  field = clampVal(field + delta, lo, hi);
  Serial.printf("%s -> %d\n", name, field);
}
void play_music_task(void *pvParameters) {
  while (true) {
    if (xSemaphoreTake(xPlayMusicSemaphore, portMAX_DELAY) == pdTRUE) {
      int index = random(0, melodyCount);
      Melody m = melodies[index];
      for (int i = 0; i < m.length; i++) {
        int freq = m.tones[i];
        int dur_ms = int(m.times[i] * 1000.0f);
        MusicNoteEvent ev = { freq, dur_ms };
        if (xMusicQueue != NULL) {
          xQueueSend(xMusicQueue, &ev, pdMS_TO_TICKS(10)); 
        }
        ledcWriteTone(33, freq);
        vTaskDelay(pdMS_TO_TICKS(dur_ms));
      }
      ledcWriteTone(33, 0); 
      if (xMusicQueue != NULL) {
        MusicNoteEvent evEnd = { 0, 0 };
        xQueueSend(xMusicQueue, &evEnd, pdMS_TO_TICKS(10));
      }
    }
  }
}
void distance_log_task(void *pvParameters) {
  (void) pvParameters;
  for (;;) {
    Get_Distance();
    vTaskDelay(pdMS_TO_TICKS(60)); 
    int d = distance; 
    vTaskDelay(pdMS_TO_TICKS(940)); 
  }
}
// ------------------- TURN HELPERS & SIMPLE BOX-BYPASS ALGORITHM -------------------
// ---------- TUNABLE PARAMETERS ----------
int TURN_DEG = 46;                      // empirical "check" angle (adjust)
constexpr int TURN_LARGE_MS = 350;      // ms for ~90° (calibrate)
constexpr int BASE_TURN_POWER = 120;    // base turning power (0..MOTOR_MAX_VALUE)
constexpr int TURN_POST_MS = 200;      
constexpr int TURN_MIN_MS = 40;      
static portMUX_TYPE bypassMux = portMUX_INITIALIZER_UNLOCKED;
enum ActionType : uint8_t { ACT_FORWARD = 0, ACT_TURN = 1 };
enum TurnDir : int8_t { DIR_LEFT = -1, DIR_RIGHT = 1 };
struct LearnedAction {
  ActionType type;
  int duration_ms; // for ACT_FORWARD
  int deg;         // for ACT_TURN
  int8_t dir;      // DIR_LEFT / DIR_RIGHT
};
static constexpr int MAX_LEARNED_ACTIONS = 32;
static LearnedAction learnedActionsRight[MAX_LEARNED_ACTIONS];
static int learnedCountRight = 0;
static bool learnedAvailableRight = false;
static LearnedAction learnedActionsLeft[MAX_LEARNED_ACTIONS];
static int learnedCountLeft = 0;
static bool learnedAvailableLeft = false;
static TaskHandle_t learnRightTaskHandle = NULL;
static bool learnRightActive = false;
static TaskHandle_t learnLeftTaskHandle = NULL;
static bool learnLeftActive = false;
static TaskHandle_t replayRightTaskHandle = NULL;
static bool replayRightActive = false;
static TaskHandle_t replayLeftTaskHandle = NULL;
static bool replayLeftActive = false;
static void clearLearnedTrajectoryRight() {
  taskENTER_CRITICAL(&bypassMux);
  learnedCountRight = 0;
  learnedAvailableRight = false;
  taskEXIT_CRITICAL(&bypassMux);
}
static void clearLearnedTrajectoryLeft() {
  taskENTER_CRITICAL(&bypassMux);
  learnedCountLeft = 0;
  learnedAvailableLeft = false;
  taskEXIT_CRITICAL(&bypassMux);
}
static void addLearnedTurnRight(int8_t dir, int deg) {
  taskENTER_CRITICAL(&bypassMux);
  if (learnedCountRight < MAX_LEARNED_ACTIONS) {
    learnedActionsRight[learnedCountRight].type = ACT_TURN;
    learnedActionsRight[learnedCountRight].dir = dir;
    learnedActionsRight[learnedCountRight].deg = deg;
    learnedActionsRight[learnedCountRight].duration_ms = 0;
    learnedCountRight++;
  } else {
    safePrintln("[LEARN RIGHT] buffer full, can't add TURN");
  }
  taskEXIT_CRITICAL(&bypassMux);
}
static void addLearnedForwardRight(int ms) {
  taskENTER_CRITICAL(&bypassMux);
  if (learnedCountRight < MAX_LEARNED_ACTIONS) {
    learnedActionsRight[learnedCountRight].type = ACT_FORWARD;
    learnedActionsRight[learnedCountRight].duration_ms = ms;
    learnedActionsRight[learnedCountRight].deg = 0;
    learnedActionsRight[learnedCountRight].dir = 0;
    learnedCountRight++;
  } else {
    safePrintln("[LEARN RIGHT] buffer full, can't add FORWARD");
  }
  taskEXIT_CRITICAL(&bypassMux);
}
static void markLearnedAvailableRight() {
  taskENTER_CRITICAL(&bypassMux);
  learnedAvailableRight = (learnedCountRight > 0);
  taskEXIT_CRITICAL(&bypassMux);
}
static void addLearnedTurnLeft(int8_t dir, int deg) {
  taskENTER_CRITICAL(&bypassMux);
  if (learnedCountLeft < MAX_LEARNED_ACTIONS) {
    learnedActionsLeft[learnedCountLeft].type = ACT_TURN;
    learnedActionsLeft[learnedCountLeft].dir = dir;
    learnedActionsLeft[learnedCountLeft].deg = deg;
    learnedActionsLeft[learnedCountLeft].duration_ms = 0;
    learnedCountLeft++;
  } else {
    safePrintln("[LEARN LEFT] buffer full, can't add TURN");
  }
  taskEXIT_CRITICAL(&bypassMux);
}
static void addLearnedForwardLeft(int ms) {
  taskENTER_CRITICAL(&bypassMux);
  if (learnedCountLeft < MAX_LEARNED_ACTIONS) {
    learnedActionsLeft[learnedCountLeft].type = ACT_FORWARD;
    learnedActionsLeft[learnedCountLeft].duration_ms = ms;
    learnedActionsLeft[learnedCountLeft].deg = 0;
    learnedActionsLeft[learnedCountLeft].dir = 0;
    learnedCountLeft++;
  } else {
    safePrintln("[LEARN LEFT] buffer full, can't add FORWARD");
  }
  taskEXIT_CRITICAL(&bypassMux);
}
static void markLearnedAvailableLeft() {
  taskENTER_CRITICAL(&bypassMux);
  learnedAvailableLeft = (learnedCountLeft > 0);
  taskEXIT_CRITICAL(&bypassMux);
}
static int computeTurnPowerFromRace() {
  float ts = clampVal(race.turn_scale, TURN_MIN, TURN_MAX);
  int p = int(BASE_TURN_POWER * ts + 0.5f);
  if (p < 0) p = 0;
  if (p > MOTOR_MAX_VALUE) p = MOTOR_MAX_VALUE;
  return p;
}
void turnRightMs(int ms, int power) {
  if (ms <= 0) return;
  setTargetMotor(power, 0, 0, power);
  vTaskDelay(pdMS_TO_TICKS(ms));
  setTargetMotor(0,0,0,0);
  vTaskDelay(pdMS_TO_TICKS(TURN_POST_MS));
}
void turnLeftMs(int ms, int power) {
  if (ms <= 0) return;
  setTargetMotor(0, power, power, 0);
  vTaskDelay(pdMS_TO_TICKS(ms));
  setTargetMotor(0,0,0,0);
  vTaskDelay(pdMS_TO_TICKS(TURN_POST_MS));
}
void turnRightDeg(int deg) {
  if (deg <= 0) return;
  int ms = (deg * TURN_LARGE_MS) / 90;
  if (ms < TURN_MIN_MS) ms = TURN_MIN_MS;
  int power = computeTurnPowerFromRace();
  turnRightMs(ms, power);
}
void turnLeftDeg(int deg) {
  if (deg <= 0) return;
  int ms = (deg * TURN_LARGE_MS) / 90;
  if (ms < TURN_MIN_MS) ms = TURN_MIN_MS;
  int power = computeTurnPowerFromRace();
  turnLeftMs(ms, power);
}
// ------------------ LEARN BYPASS RIGHT (learning, uses front sensor) ------------------
void learn_bypass_right_task(void *pvParameters) {
  (void) pvParameters;
  taskENTER_CRITICAL(&bypassMux);
  if (learnRightActive) {
    safePrintln("LEARN RIGHT: start requested but already active -> exiting task");
    learnRightTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    vTaskDelete(NULL);
    return;
  }
  learnRightActive = true;
  learnRightTaskHandle = xTaskGetCurrentTaskHandle();
  taskEXIT_CRITICAL(&bypassMux);
  clearLearnedTrajectoryRight();
  const int STOP_THRESHOLD_CM = 13;
  const int SAFE_CLEAR_CM = 35;
  const int MOVE_SPEED = 60;
  const int FORWARD_STEP_MS = 700;
  const int FORWARD_AFTER_PASS_MS = 300;
  const int DIST_CHECK_DELAY_MS = 120;
  const float SAME_DISTANCE_MULT = 1.5f;
  const int MAX_TOTAL_ATTEMPTS = 200;
  safePrintln("LEARN RIGHT: simple box bypass learning started");
  int sides_passed = 0;
  bool obstacle_detected = false;
  // approach
  while (learnRightActive && !obstacle_detected) {
    Get_Distance();
    vTaskDelay(pdMS_TO_TICKS(DIST_CHECK_DELAY_MS));
    int front = distance;
    safePrint("[LEARN RIGHT] approaching: front=%d cm, sides_passed=%d\n", front, sides_passed);
    if (front > STOP_THRESHOLD_CM) {
      setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
      vTaskDelay(pdMS_TO_TICKS(80));
      continue;
    }
    obstacle_detected = true;
    safePrintln("[LEARN RIGHT] obstacle detected -> start bypassing");
    int initial_front = (front > 0) ? front : 1;
    setTargetMotor(0,0,0,0);
    vTaskDelay(pdMS_TO_TICKS(200));
    safePrint("[LEARN RIGHT] turning RIGHT (TURN_DEG=%d) to become parallel\n", TURN_DEG);
    turnRightDeg(TURN_DEG);
    vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
    int attempts = 0;
    int acc_forward_ms = 0;
    while (learnRightActive && sides_passed < 4 && attempts < MAX_TOTAL_ATTEMPTS) {
      attempts++;
      safePrint("[LEARN RIGHT] bypass attempt %d\n", attempts);
      setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
      vTaskDelay(pdMS_TO_TICKS(FORWARD_STEP_MS));
      setTargetMotor(0,0,0,0);
      acc_forward_ms += FORWARD_STEP_MS;
      vTaskDelay(pdMS_TO_TICKS(100));
      safePrint("[LEARN RIGHT] turning LEFT (TURN_DEG=%d) to check forward distance\n", TURN_DEG);
      turnLeftDeg(TURN_DEG);
      vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
      Get_Distance();
      vTaskDelay(pdMS_TO_TICKS(DIST_CHECK_DELAY_MS));
      int check = distance;
      safePrint("[LEARN RIGHT] check after left turn: %d cm (initial=%d)\n", check, initial_front);
      if ((float)check <= SAME_DISTANCE_MULT * (float)initial_front) {
        safePrintln("[LEARN RIGHT] still close -> return to parallel and continue");
        turnRightDeg(TURN_DEG);
        vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
        continue;
      }
      if (check >= SAFE_CLEAR_CM || (float)check >= 2.0f * (float)initial_front) {
        safePrint("[LEARN RIGHT] side appears cleared (check=%d) -> passing corner\n", check);
        int total_forward_ms = acc_forward_ms + FORWARD_AFTER_PASS_MS;
        addLearnedForwardRight(total_forward_ms);
        addLearnedTurnRight(DIR_LEFT, TURN_DEG);
        acc_forward_ms = 0;
        sides_passed++;
        setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
        vTaskDelay(pdMS_TO_TICKS(FORWARD_AFTER_PASS_MS));
        setTargetMotor(0,0,0,0);
        vTaskDelay(pdMS_TO_TICKS(100));
        safePrint("[LEARN RIGHT] side cleared. total sides_passed=%d\n", sides_passed);
        continue;
      }
      safePrint("[LEARN RIGHT] ambiguous result (check=%d) -> return to parallel and try again\n", check);
      turnRightDeg(TURN_DEG);
      vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
    }
    if (sides_passed < 4) {
      safePrint("[LEARN RIGHT] failed to clear all sides after %d attempts -> aborting\n", attempts);
      ledcWriteTone(2, 400);
      vTaskDelay(pdMS_TO_TICKS(600));
      ledcWrite(2, 0);
      taskENTER_CRITICAL(&bypassMux);
      learnRightActive = false;
      taskEXIT_CRITICAL(&bypassMux);
    } else {
      safePrintln("[LEARN RIGHT] learning complete - sides_passed == 4");
      markLearnedAvailableRight();
    }
  }
  setTargetMotor(0,0,0,0);
  safePrint("LEARN RIGHT: finished simple box bypass; sides_passed=%d\n", sides_passed);
  if (sides_passed >= 4) {
    ledcWriteTone(2, 900);
    vTaskDelay(pdMS_TO_TICKS(200));
    ledcWrite(2, 0);
  } else {
    ledcWriteTone(2, 400);
    vTaskDelay(pdMS_TO_TICKS(200));
    ledcWrite(2, 0);
  }
  taskENTER_CRITICAL(&bypassMux);
  learnRightActive = false;
  learnRightTaskHandle = NULL;
  taskEXIT_CRITICAL(&bypassMux);
  vTaskDelete(NULL);
}
// ------------------ LEARN BYPASS LEFT (mirror of right) ------------------
void learn_bypass_left_task(void *pvParameters) {
  (void) pvParameters;
  taskENTER_CRITICAL(&bypassMux);
  if (learnLeftActive) {
    safePrintln("LEARN LEFT: start requested but already active -> exiting task");
    learnLeftTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    vTaskDelete(NULL);
    return;
  }
  learnLeftActive = true;
  learnLeftTaskHandle = xTaskGetCurrentTaskHandle();
  taskEXIT_CRITICAL(&bypassMux);
  clearLearnedTrajectoryLeft();
  const int STOP_THRESHOLD_CM = 13;
  const int SAFE_CLEAR_CM = 35;
  const int MOVE_SPEED = 60;
  const int FORWARD_STEP_MS = 700;
  const int FORWARD_AFTER_PASS_MS = 300;
  const int DIST_CHECK_DELAY_MS = 120;
  const float SAME_DISTANCE_MULT = 1.5f;
  const int MAX_TOTAL_ATTEMPTS = 200;
  safePrintln("LEARN LEFT: simple box bypass learning started");
  int sides_passed = 0;
  bool obstacle_detected = false;
  while (learnLeftActive && !obstacle_detected) {
    Get_Distance();
    vTaskDelay(pdMS_TO_TICKS(DIST_CHECK_DELAY_MS));
    int front = distance;
    safePrint("[LEARN LEFT] approaching: front=%d cm, sides_passed=%d\n", front, sides_passed);
    if (front > STOP_THRESHOLD_CM) {
      setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
      vTaskDelay(pdMS_TO_TICKS(80));
      continue;
    }
    obstacle_detected = true;
    safePrintln("[LEARN LEFT] obstacle detected -> start bypassing");
    int initial_front = (front > 0) ? front : 1;
    setTargetMotor(0,0,0,0);
    vTaskDelay(pdMS_TO_TICKS(200));
    safePrint("[LEARN LEFT] turning LEFT (TURN_DEG=%d) to become parallel\n", TURN_DEG);
    turnLeftDeg(TURN_DEG);
    vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
    int attempts = 0;
    int acc_forward_ms = 0;
    while (learnLeftActive && sides_passed < 4 && attempts < MAX_TOTAL_ATTEMPTS) {
      attempts++;
      safePrint("[LEARN LEFT] bypass attempt %d\n", attempts);
      setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
      vTaskDelay(pdMS_TO_TICKS(FORWARD_STEP_MS));
      setTargetMotor(0,0,0,0);
      acc_forward_ms += FORWARD_STEP_MS;
      vTaskDelay(pdMS_TO_TICKS(100));
      safePrint("[LEARN LEFT] turning RIGHT (TURN_DEG=%d) to check forward distance\n", TURN_DEG);
      turnRightDeg(TURN_DEG);
      vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
      Get_Distance();
      vTaskDelay(pdMS_TO_TICKS(DIST_CHECK_DELAY_MS));
      int check = distance;
      safePrint("[LEARN LEFT] check after right turn: %d cm (initial=%d)\n", check, initial_front);
      if ((float)check <= SAME_DISTANCE_MULT * (float)initial_front) {
        safePrintln("[LEARN LEFT] still close -> return to parallel and continue");
        turnLeftDeg(TURN_DEG); 
        vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
        continue;
      }
      if (check >= SAFE_CLEAR_CM || (float)check >= 2.0f * (float)initial_front) {
        safePrint("[LEARN LEFT] side appears cleared (check=%d) -> passing corner\n", check);
        int total_forward_ms = acc_forward_ms + FORWARD_AFTER_PASS_MS;
        addLearnedForwardLeft(total_forward_ms);
        addLearnedTurnLeft(DIR_RIGHT, TURN_DEG);
        acc_forward_ms = 0;
        sides_passed++;
        setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
        vTaskDelay(pdMS_TO_TICKS(FORWARD_AFTER_PASS_MS));
        setTargetMotor(0,0,0,0);
        vTaskDelay(pdMS_TO_TICKS(100));
        safePrint("[LEARN LEFT] side cleared. total sides_passed=%d\n", sides_passed);
        continue;
      }
      safePrint("[LEARN LEFT] ambiguous result (check=%d) -> return to parallel and try again\n", check);
      turnLeftDeg(TURN_DEG);
      vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
    }
    if (sides_passed < 4) {
      safePrint("[LEARN LEFT] failed to clear all sides after %d attempts -> aborting\n", attempts);
      ledcWriteTone(2, 400);
      vTaskDelay(pdMS_TO_TICKS(600));
      ledcWrite(2, 0);
      taskENTER_CRITICAL(&bypassMux);
      learnLeftActive = false;
      taskEXIT_CRITICAL(&bypassMux);
    } else {
      safePrintln("[LEARN LEFT] learning complete - sides_passed == 4");
      markLearnedAvailableLeft();
    }
  }
  setTargetMotor(0,0,0,0);
  safePrint("LEARN LEFT: finished simple box bypass; sides_passed=%d\n", sides_passed);
  if (sides_passed >= 4) {
    ledcWriteTone(2, 900);
    vTaskDelay(pdMS_TO_TICKS(200));
    ledcWrite(2, 0);
  } else {
    ledcWriteTone(2, 400);
    vTaskDelay(pdMS_TO_TICKS(200));
    ledcWrite(2, 0);
  }
  taskENTER_CRITICAL(&bypassMux);
  learnLeftActive = false;
  learnLeftTaskHandle = NULL;
  taskEXIT_CRITICAL(&bypassMux);
  vTaskDelete(NULL);
}
// ------------------ REPLAY RIGHT (replay learned right trajectory, no sensors) ------------------
void replay_learned_right_task(void *pvParameters) {
  (void) pvParameters;
  taskENTER_CRITICAL(&bypassMux);
  if (replayRightActive) {
    safePrintln("REPLAY RIGHT: already active -> exiting");
    replayRightTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    vTaskDelete(NULL);
    return;
  }
  if (!learnedAvailableRight || learnedCountRight == 0) {
    safePrintln("REPLAY RIGHT: no learned right trajectory available -> exiting");
    replayRightTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    vTaskDelete(NULL);
    return;
  }
  replayRightActive = true;
  replayRightTaskHandle = xTaskGetCurrentTaskHandle();
  taskEXIT_CRITICAL(&bypassMux);
  safePrintln("REPLAY RIGHT: replaying learned right trajectory (no sensor checks)");
  LearnedAction* localActions = nullptr;
  int localCount = 0;
  taskENTER_CRITICAL(&bypassMux);
  localCount = learnedCountRight;
  if (localCount > 0) {
    localActions = (LearnedAction*) pvPortMalloc(sizeof(LearnedAction) * localCount);
    if (localActions != nullptr) {
      for (int i = 0; i < localCount; ++i) localActions[i] = learnedActionsRight[i];
    }
  }
  taskEXIT_CRITICAL(&bypassMux);
  if (localActions == nullptr || localCount == 0) {
    safePrintln("REPLAY RIGHT: failed to allocate/copy learned trajectory -> aborting");
    taskENTER_CRITICAL(&bypassMux);
    replayRightActive = false;
    replayRightTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    if (localActions) vPortFree(localActions);
    vTaskDelete(NULL);
    return;
  }
  const int MOVE_SPEED = 60;
  for (int i = 0; i < localCount && replayRightActive; ++i) {
    LearnedAction a = localActions[i];
    if (a.type == ACT_FORWARD) {
      safePrint("[REPLAY RIGHT] FORWARD %d ms\n", a.duration_ms);
      setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
      vTaskDelay(pdMS_TO_TICKS(a.duration_ms));
      setTargetMotor(0,0,0,0);
      vTaskDelay(pdMS_TO_TICKS(100));
    } else if (a.type == ACT_TURN) {
      if (a.dir == DIR_LEFT) {
        safePrint("[REPLAY RIGHT] TURN LEFT %d deg\n", a.deg);
        turnLeftDeg(a.deg);
      } else {
        safePrint("[REPLAY RIGHT] TURN RIGHT %d deg\n", a.deg);
        turnRightDeg(a.deg);
      }
      vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
    }
  }
  setTargetMotor(0,0,0,0);
  ledcWriteTone(2, 900);
  vTaskDelay(pdMS_TO_TICKS(200));
  ledcWrite(2, 0);
  vPortFree(localActions);
  taskENTER_CRITICAL(&bypassMux);
  replayRightActive = false;
  replayRightTaskHandle = NULL;
  taskEXIT_CRITICAL(&bypassMux);
  safePrintln("REPLAY RIGHT: finished replay");
  vTaskDelete(NULL);
}
// ------------------ REPLAY LEFT (replay learned left trajectory, no sensors) ------------------
void replay_learned_left_task(void *pvParameters) {
  (void) pvParameters;
  taskENTER_CRITICAL(&bypassMux);
  if (replayLeftActive) {
    safePrintln("REPLAY LEFT: already active -> exiting");
    replayLeftTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    vTaskDelete(NULL);
    return;
  }
  if (!learnedAvailableLeft || learnedCountLeft == 0) {
    safePrintln("REPLAY LEFT: no learned left trajectory available -> exiting");
    replayLeftTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    vTaskDelete(NULL);
    return;
  }
  replayLeftActive = true;
  replayLeftTaskHandle = xTaskGetCurrentTaskHandle();
  taskEXIT_CRITICAL(&bypassMux);
  safePrintln("REPLAY LEFT: replaying learned left trajectory (no sensor checks)");
  LearnedAction* localActions = nullptr;
  int localCount = 0;
  taskENTER_CRITICAL(&bypassMux);
  localCount = learnedCountLeft;
  if (localCount > 0) {
    localActions = (LearnedAction*) pvPortMalloc(sizeof(LearnedAction) * localCount);
    if (localActions != nullptr) {
      for (int i = 0; i < localCount; ++i) localActions[i] = learnedActionsLeft[i];
    }
  }
  taskEXIT_CRITICAL(&bypassMux);
  if (localActions == nullptr || localCount == 0) {
    safePrintln("REPLAY LEFT: failed to allocate/copy learned trajectory -> aborting");
    taskENTER_CRITICAL(&bypassMux);
    replayLeftActive = false;
    replayLeftTaskHandle = NULL;
    taskEXIT_CRITICAL(&bypassMux);
    if (localActions) vPortFree(localActions);
    vTaskDelete(NULL);
    return;
  }
  const int MOVE_SPEED = 60;
  for (int i = 0; i < localCount && replayLeftActive; ++i) {
    LearnedAction a = localActions[i];
    if (a.type == ACT_FORWARD) {
      safePrint("[REPLAY LEFT] FORWARD %d ms\n", a.duration_ms);
      setTargetMotor(MOVE_SPEED, 0, MOVE_SPEED, 0);
      vTaskDelay(pdMS_TO_TICKS(a.duration_ms));
      setTargetMotor(0,0,0,0);
      vTaskDelay(pdMS_TO_TICKS(100));
    } else if (a.type == ACT_TURN) {
      if (a.dir == DIR_LEFT) {
        safePrint("[REPLAY LEFT] TURN LEFT %d deg\n", a.deg);
        turnLeftDeg(a.deg);
      } else {
        safePrint("[REPLAY LEFT] TURN RIGHT %d deg\n", a.deg);
        turnRightDeg(a.deg);
      }
      vTaskDelay(pdMS_TO_TICKS(80 + TURN_POST_MS / 2));
    }
  }
  setTargetMotor(0,0,0,0);
  ledcWriteTone(2, 900);
  vTaskDelay(pdMS_TO_TICKS(200));
  ledcWrite(2, 0);
  vPortFree(localActions);
  taskENTER_CRITICAL(&bypassMux);
  replayLeftActive = false;
  replayLeftTaskHandle = NULL;
  taskEXIT_CRITICAL(&bypassMux);
  safePrintln("REPLAY LEFT: finished replay");
  vTaskDelete(NULL);
}
void grc_cmd_task(void*arg)
{
  const float d_speed = 0.5;
  float speed = 1;
  bool imu_control_mode = false;
  auto init_imu_control_state = [&imu_control_mode]() {
    Serial.printf("Enable imu control mode\n");
    imu_control_mode = true;
    ticker.attach_ms(300, led_callback);  //lighting task
    ticker1.attach_ms(900, buzzer_callback);  //buzzer task
  };
  auto release_imu_control_state = [&imu_control_mode, &moving_backwards]() {
    Serial.printf("Disable imu control mode\n");
    imu_control_mode = false;
    moving_backwards = false;
    Motor(0, 0, 0, 0);
    ledcWrite(2, 0);
    fill_solid(leds, 4, CRGB::Black);
    FastLED.show();
    ticker.detach();
    ticker1.detach();
  };
  auto front_lights_cmd = [](bool front_lights_en) {
    uint8_t val = 0; 
    if (front_lights_en) {
      FastLED.setBrightness(255);  //RGB lamp brightness range: 0-255
      val = 255;
    }
    myRGBcolor6.r = val;
    myRGBcolor6.g = val;
    myRGBcolor6.b = val;
    fill_solid(RGBleds, 6, myRGBcolor6);
    FastLED.show();
  };
  char msg[MAX_GRC_MSG_LEN];
    for (;;) {
    size_t length = xMessageBufferReceive(xGrcCmdBuffer, &msg, MAX_GRC_MSG_LEN, portMAX_DELAY);
    std::string value(msg, length);
    const std::string::size_type coords_offset = value.find("XY"); 
    const bool recv_imu_coords = coords_offset != std::string::npos;
    if (recv_imu_coords && !imu_control_mode) {
      init_imu_control_state();
    }
    //********************************GRC voice command******************************************
    if (!imu_control_mode) {
      if (value == "GO FORWARD" || value == "xiang qian zou")  //forward
...
This file has been truncated, please download it to see its full contents.
Comments