From 130bd3bfb6052c0ad399d8ab0986b3d76bb20baf Mon Sep 17 00:00:00 2001
From: Zhiying Li <zhiyingli@g.ucla.edu>
Date: Thu, 21 Oct 2021 23:23:20 -0700
Subject: [PATCH] Upload latest code

---
 .../feather_main_test_PID_Lidar.ino           |  66 +-
 .../Laptop_Code/ESP32_slave/ESP32_slave.ino   | 637 +++++++++---------
 .../ESP32_slave/New Text Document.txt         |   0
 .../distance-detection-torch.cpython-38.pyc   | Bin 5957 -> 5957 bytes
 Code/Control/Laptop_Code/constants.py         |   7 +-
 Code/Control/Laptop_Code/main.py              |   7 +-
 .../main_zhiying_catchBall_test_2in1.py       | 371 ++++++++++
 .../main_zhiying_seeking_indv_test.py         |  12 +-
 8 files changed, 736 insertions(+), 364 deletions(-)
 create mode 100644 Code/Control/Laptop_Code/ESP32_slave/New Text Document.txt
 create mode 100644 Code/Control/Laptop_Code/main_zhiying_catchBall_test_2in1.py

diff --git a/Code/Control/Feather Code - Zhaoliang/feather_main_test_PID_Lidar/feather_main_test_PID_Lidar.ino b/Code/Control/Feather Code - Zhaoliang/feather_main_test_PID_Lidar/feather_main_test_PID_Lidar.ino
index d593541..c46f2f5 100644
--- a/Code/Control/Feather Code - Zhaoliang/feather_main_test_PID_Lidar/feather_main_test_PID_Lidar.ino	
+++ b/Code/Control/Feather Code - Zhaoliang/feather_main_test_PID_Lidar/feather_main_test_PID_Lidar.ino	
@@ -18,7 +18,7 @@ SFEVL53L1X distanceSensor;
 int budgetIndex = 4;
 int budgetValue[7] = {15, 20, 33, 50, 100, 200, 500};
 int LED = LED_BUILTIN;
-// 
+//
 
 //Identify all the global constants that will be used by the robot
 const int BAUD_RATE = 115200;
@@ -48,7 +48,7 @@ const int DEBUG_THRESHOLD_MAX = 25;
 const int DEBUG_VERTICALSPEED = 17;
 const int DEBUG_RSPEED = 16;
 const int DEBUG_LSPEED = 24;
-int lidar_thres = 300; // mm 
+int lidar_thres = 300; // mm
 
 //Create the interface that will be used by the camera
 openmv::rpc_scratch_buffer<256> scratch_buffer; // All RPC objects share this buffer.
@@ -57,7 +57,7 @@ openmv::rpc_i2c_master interface(0x12, 100000); //to make this more robust, cons
 // Create the motor shield object with the default I2C address
 Adafruit_MotorShield AFMS = Adafruit_MotorShield();
 // changed
-Adafruit_DCMotor *motorVertical_L = AFMS.getMotor(1); 
+Adafruit_DCMotor *motorVertical_L = AFMS.getMotor(1);
 Adafruit_DCMotor *motorVertical_R = AFMS.getMotor(2);
 Adafruit_DCMotor *motorLeft = AFMS.getMotor(3);
 Adafruit_DCMotor *motorRight = AFMS.getMotor(4);
@@ -79,7 +79,7 @@ void setup() {
   AFMS.begin();  // create with the default frequency 1.6KHz
   interface.begin(); //communication between ESP and OpenMV
   panel.beginPanel();
-  Setpointx = 160.0; 
+  Setpointx = 160.0;
   Setpointy = 120.0; //the values that the PID will try to reach
   PID_y.SetOutputLimits(-255, 255); //up positive
   PID_x.SetOutputLimits(-255, 255); //left positive
@@ -115,19 +115,19 @@ int goal_id[3] = {0, 1, 2};
 //  //do whatever we have been doing before to find a green balloon
 //}
 
-void loop() {  
+void loop() {
   panel.singleLED(DEBUG_BASESPEED, BASE_SPEED, BASE_SPEED, BASE_SPEED);
 
   //if the demo is still ongoing, check to see if there is a desired-color blob
   panel.singleLED(DEBUG_STATE, 10, 0, 0); //standby
-  
+
   //========== lidar part =========
   int dist = 0;
   int ball_cap = 0;
   dist = distanceSensor.getDistance();
   Serial.println(dist);
-  if ((dist < lidar_thres) && (dist > 0)){ // if we capture the ball 
-    ball_cap = 1; 
+  if ((dist < lidar_thres) && (dist > 0)){ // if we capture the ball
+    ball_cap = 1;
     Serial.println("find ball");
   }else{
     ball_cap = 2;
@@ -138,7 +138,7 @@ void loop() {
   int tx = 0; int ty = 0; int tz = 0;
   int rx = 0; int ry = 0; int rz = 0;
   int8_t goal[3] = {0,1,2};
-  
+
   if (ball_cap == 1){
   if(cam.exe_goalfinder(goal[0],goal[1],goal[2], id, tx, ty, tz, rx, ry, rz)){
     panel.singleLED(DEBUG_STATE, 0, 10, 0);
@@ -154,13 +154,13 @@ void loop() {
     moveVertical(Outputy);
     moveHorizontal(Outputx, BASE_SPEED);
   }else { // seeking
-      seeking(); 
+      seeking();
     }
   }else {
     moveVertical(0);
     moveHorizontal(0, 0);
     }
-  /*
+
   if(cam.exe_color_detection_biggestblob(threshold[0], threshold[1], threshold[2], threshold[3], threshold[4], threshold[5], x, y)){
     if (displayTracking > 0){
       displayTrackedObject(x, y, RESOLUTION_W, RESOLUTION_H); //THIS NEEDS WORK
@@ -174,7 +174,7 @@ void loop() {
     //actuate the vertical motor
     moveVertical(Outputy);
     moveHorizontal(Outputx, BASE_SPEED);
-    
+
   } else { //seeking algorithm
     //panel.resetPanel();
     panel.singleLED(DEBUG_STATE, 10, 10, 10);
@@ -183,7 +183,7 @@ void loop() {
     moveVertical(zero);
     moveHorizontal(SEEKING_SPEED, zero);
   }
-  */
+
 }
 // ============================== ^ main loop ^====================================
 
@@ -200,17 +200,17 @@ void seeking(){
 void moveVertical(int vel){
     if (vel > 0) { //up
       panel.singleLED(DEBUG_VERTICALSPEED, abs(vel), 0, 0);
-      // changed 
+      // changed
       motorVertical_L->setSpeed(abs((int) vel));
-      motorVertical_R->setSpeed(abs((int) vel)); 
-      motorVertical_L->run(BACKWARD); 
+      motorVertical_R->setSpeed(abs((int) vel));
+      motorVertical_L->run(BACKWARD);
       motorVertical_R->run(FORWARD);
       // changed
     } else if(vel < 0) { //down
       panel.singleLED(DEBUG_VERTICALSPEED, 0, 0, abs(vel));
       // changed
-      motorVertical_L->setSpeed(abs((int) vel));  
-      motorVertical_R->setSpeed(abs((int) vel)); 
+      motorVertical_L->setSpeed(abs((int) vel));
+      motorVertical_R->setSpeed(abs((int) vel));
             motorVertical_L->run(FORWARD);
       motorVertical_R->run(BACKWARD);
 
@@ -221,7 +221,7 @@ void moveVertical(int vel){
       //changed
       motorVertical_L->setSpeed(0);
       motorVertical_R->setSpeed(0);
-      //changed 
+      //changed
     }
 }
 
@@ -230,13 +230,13 @@ void moveHorizontal(int vel_hori,int base_speed){
   int lspeed = -1*vel_hori + base_speed;
   int rspeed = vel_hori + base_speed;
 
-  if (lspeed > 0){  
-    motorLeft->run(BACKWARD); // make it move forward 
+  if (lspeed > 0){
+    motorLeft->run(BACKWARD); // make it move forward
   } else {
-    motorLeft->run(FORWARD); 
+    motorLeft->run(FORWARD);
   }
   if (rspeed > 0){
-    motorRight-> run(FORWARD); 
+    motorRight-> run(FORWARD);
   } else {
     motorRight-> run(BACKWARD); // make it move backward
   }
@@ -262,7 +262,7 @@ void displaySpeed(int lspeed, int rspeed){
 
 //When using the camera to detect objects such as colored blobs or april tags. This function is
 //useful when only a single object is the target. The approximate position will be marked with an
-//led turning white in the 8*4 panel of the NeoPixel LED Panel. Therefore, this function can be 
+//led turning white in the 8*4 panel of the NeoPixel LED Panel. Therefore, this function can be
 //called assuming that you have created the LED panel object, which in this code is named "panel".
 //If the LED panel is called something else, just edit the code here
 void displayTrackedObject(int cx, int cy, int w_res, int h_res){
@@ -300,7 +300,7 @@ void translateCodetoThreshold(int code){
     case 1: //green old = (30, 100, -68, -13, 30, 127)
       //(30,100,-68,2,6,127) - detect the yellow wall as well
       // LAB: L[min] - L[max], A[min] - A[max], B[min] - B[max]
-      threshold[0] = 30; 
+      threshold[0] = 30;
       threshold[1] = 100;
       threshold[2] = -93;
       threshold[3] = -5;
@@ -326,11 +326,11 @@ void translateCodetoThreshold(int code){
 }
 
 
-//threshold array must have at least six elements. This function helps 
+//threshold array must have at least six elements. This function helps
 //translating a message with threshold values to ints. Example msg that would
-//be received by this function are "1 2 3 4 5 6" or "-100 70 9 -9 -50 128". 
+//be received by this function are "1 2 3 4 5 6" or "-100 70 9 -9 -50 128".
 //NOTE: - the threshold value should be between -128 to 128
-//      - the message should not include the command character used by the mesh  
+//      - the message should not include the command character used by the mesh
 //      - suggested command character: 'C'[olor]
 void setColorThreshold(String msg, int8_t thres[], int arraySize){
   int len = msg.length();
@@ -344,14 +344,14 @@ void setColorThreshold(String msg, int8_t thres[], int arraySize){
     }
     if (temp == 5){
       thres[temp] = msg.substring(startpoint).toInt();
-      break; 
+      break;
     }
   }
 }
 
-//This function translate a string of message into the constants for a PID controller. Ignoring the 
+//This function translate a string of message into the constants for a PID controller. Ignoring the
 //first command character, user can input any one, two, or all three parameter to be changed by identifying
-//the new parameter with the capital letter of that specific parameter, each separated with a space. 
+//the new parameter with the capital letter of that specific parameter, each separated with a space.
 //Some of the valid msg examples are:
 //  - "P0.02"
 //  - "D1.23"
@@ -366,7 +366,7 @@ void setPIDConstants(String msg, double &p_constant, double &i_constant, double
   double new_p = Kpx;
   double new_i = Kix;
   double new_d = Kdx;
-  
+
   int len = msg.length();
   int startpoint = 0;
   int endpoint = 0;
@@ -431,7 +431,7 @@ void setPIDConstants(String msg, double &p_constant, double &i_constant, double
   p_constant = new_p;
   i_constant = new_i;
   d_constant = new_d;
-  
+
   while(millis() < t+2000); //debugging LED will light up for 2 seconds
   panel.singleLED(DEBUG_KP, 0, 0, 0);
   panel.singleLED(DEBUG_KI, 0, 0, 0);
diff --git a/Code/Control/Laptop_Code/ESP32_slave/ESP32_slave.ino b/Code/Control/Laptop_Code/ESP32_slave/ESP32_slave.ino
index 34bf1ba..b661f45 100644
--- a/Code/Control/Laptop_Code/ESP32_slave/ESP32_slave.ino
+++ b/Code/Control/Laptop_Code/ESP32_slave/ESP32_slave.ino
@@ -1,319 +1,318 @@
-#include <esp_now.h>
-#include <WiFi.h>
-#include <Wire.h>
-#include <SparkFun_VL53L1X.h>
-#include <Arduino.h>
-
-#include "Camera.h"
-#include "utilities.h"
-#include <Adafruit_MotorShield.h>
-
-// REPLACE WITH THE MAC Address of your receiver (MASTER)
-// Slave: 40:F5:20:44:B6:4C
-// uint8_t broadcastAddress[] = {0x3C, 0x61, 0x05, 0x4A, 0xCF, 0x00};
-uint8_t broadcastAddress[] = {0x40, 0xF5, 0x20, 0x44, 0xB6, 0x4C}; // #4
-String success;
-
-// Define variables to store incoming readings
-String sentDebugM = "";
-int Rec_pwm1;
-int Rec_pwm2;
-int Rec_pwm3;
-int Rec_pwm4;
-String Rec_dir1;
-String Rec_dir2;
-String Rec_dir3;
-String Rec_dir4;
-
-int count = 0;
-int count_var = 0;
-int print_count = 0;
-int change_count =0;
-int Lidar_flag = 0;
-
-// Define variables to be sent;
-int Sent_tx = 0;
-int Sent_ty = 0;
-int Sent_tz = 0;
-int Sent_rx = 0;
-int Sent_ry = 0;
-int Sent_rz = 0;
-int Sent_dist = 0;
-
-int8_t g1 = 0,g2=1,g3=2;
-int8_t goal_id[3] = {g1, g2, g3};
-
-// Define Lidar variables
-SFEVL53L1X distanceSensor;
-int budgetIndex = 4;
-int budgetValue[7] = {15, 20, 33, 50, 100, 200, 500};
-
-// Define LED variable
-int LED = LED_BUILTIN;
-
-// ==================================== data structure =================================================
-//Structure the sending data
-//Must match the receiver structure
-typedef struct struct_message {
-  int Rtx;
-  int Rty;
-  int Rtz;
-  int Rrx;
-  int Rry;
-  int Rrz;
-  int Rdist;
-  String DebugM;
-  int Spwm1;
-  int Spwm2;
-  int Spwm3;
-  int Spwm4;
-  String Sdir1;
-  String Sdir2;
-  String Sdir3;
-  String Sdir4;
-} struct_message;
-// Create a struct_message to hold incoming sensor readings
-// struct_message incomingReadings;
-struct_message receivedData;
-
-// =================================== send and received function =====================================
-// Callback when data is sent
-void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) {
-  Serial.print("\r\nLast Packet Send Status:\t");
-  Serial.println(status == ESP_NOW_SEND_SUCCESS ? "Delivery Success" : "Delivery Fail");
-  if (status ==0){
-    success = "Delivery Success :)";
-  }
-  else{
-    success = "Delivery Fail :(";
-  }
-}
-
-// Callback when data is received
-void OnDataRecv(const uint8_t * mac, const uint8_t *incomingData, int len) {
-  memcpy(&receivedData, incomingData, sizeof(receivedData));
-  // the data format: 225 225 225 225 + + - -
-  // + up / forward 
-  // - down / backward
-  Rec_pwm1 = receivedData.Spwm1;
-  Rec_pwm2 = receivedData.Spwm2; 
-  Rec_pwm3 = receivedData.Spwm3;
-  Rec_pwm4 = receivedData.Spwm4;    
-  Rec_dir1 = receivedData.Sdir1;  
-  Rec_dir2 = receivedData.Sdir2; 
-  Rec_dir3 = receivedData.Sdir3; 
-  Rec_dir4 = receivedData.Sdir4;   
-  count_var = 0;
-  count = 0;
-  print_count=0;
-  
-  change_count = 0;  
-}
-
-// =============================== All the setup ===========================================
-//Create the interface that will be used by the camera
-openmv::rpc_scratch_buffer<256> scratch_buffer; // All RPC objects share this buffer.
-openmv::rpc_i2c_master interface(0x12, 100000); //to make this more robust, consider making address and rate as constructor argument
-Camera cam(&interface);
-// ========================== Motor part ====================================
-// Create the motor shield object with the default I2C address
-Adafruit_MotorShield AFMS = Adafruit_MotorShield();
-// changed
-Adafruit_DCMotor *motorVertical_L = AFMS.getMotor(1);  // pwm1
-Adafruit_DCMotor *motorVertical_R = AFMS.getMotor(2);  // pwm2
-Adafruit_DCMotor *motorLeft = AFMS.getMotor(3);        // pwm3
-Adafruit_DCMotor *motorRight = AFMS.getMotor(4);       // pwm4 
-// ==================================== Set up =================================================
-void setup() {
-  // Init Serial Monitor
-  Serial.begin(115200);
-  Wire.begin();
-  interface.begin(); //communication between ESP and OpenMV
-  AFMS.begin();  // create with the default frequency 1.6KHz
-  // -------------- LED part --------------------
-  pinMode(LED, OUTPUT);
-  digitalWrite(LED, HIGH);
-  digitalWrite(LED, LOW);
-  
-  // -------------- lidar part --------------------
-  if (distanceSensor.begin() == 0){
-    Serial.println("Sensor online!");
-    Lidar_flag = 1;
-  }else {
-    Lidar_flag = 0;
-  }
-     
-  distanceSensor.startRanging();
-  distanceSensor.setIntermeasurementPeriod(budgetValue[budgetIndex]);
-  
- // --------------------------- esp now ---------------------------
-  // Set device as a Wi-Fi Station
-  WiFi.mode(WIFI_STA);
-
-  // Init ESP-NOW
-  if (esp_now_init() != ESP_OK) {
-    Serial.println("Error initializing ESP-NOW");
-    return;
-  }
-  
-  // Once ESPNow is successfully Init, we will register for Send CB to
-  // get the status of Trasnmitted packet
-  esp_now_register_send_cb(OnDataSent);
-  
-  // Register peer
-  esp_now_peer_info_t peerInfo;
-  memcpy(peerInfo.peer_addr, broadcastAddress, 6);
-  peerInfo.channel = 0;  
-  peerInfo.encrypt = false;
-  
-  // Add peer        
-  if (esp_now_add_peer(&peerInfo) != ESP_OK){
-    Serial.println("Failed to add peer");
-    return;
-  }
-  // Register for a callback function that will be called when data is received
-  esp_now_register_recv_cb(OnDataRecv);
-  
-}
-
-// ================================== Main loop ===================================================
-void loop()
-{ 
-  //-------------------------------------------------------------------------------------
-  // ========== goal finder =========
-  int id = -1;
-  int tx = 0; int ty = 0; int tz = 0;
-  int rx = 0; int ry = 0; int rz = 0;
-  int x = 0;
-  int y = 0; 
-  bool goalfind_flag = 0;
-  
-  goalfind_flag = cam.exe_goalfinder(goal_id[0],goal_id[1],goal_id[2], id, tx, ty, tz, rx, ry, rz);
-  if (goalfind_flag){
-      Sent_tx = tx;
-      Sent_ty = ty;
-      Sent_tz = tz; // cm
-      Sent_rx = rx;
-      Sent_ry = ry;
-      Sent_rz = rz; 
-  }else{
-      Sent_tx = 0;
-      Sent_ty = 0;
-      Sent_tz = 0; // cm
-      Sent_rx = 0;
-      Sent_ry = 0;
-      Sent_rz = 0; 
-  }
-  if (Lidar_flag == 1){
-    Sent_dist = distanceSensor.getDistance(); // Lidar distance (use the real Lidar data)
-  }else {
-    Sent_dist = 0;
-  }
-  // ========== lidar state info =========
-  if (Sent_dist < 300 && Sent_dist < 0){
-    receivedData.DebugM = "found b";
-  }else{
-    receivedData.DebugM = "no b";
-  }
-  // ========== send info =========
-  receivedData.Rtx = Sent_tx;
-  receivedData.Rty = Sent_ty;
-  receivedData.Rtz = Sent_tz;  
-  receivedData.Rrx = Sent_rx;  
-  receivedData.Rry = Sent_ry; 
-  receivedData.Rrz = Sent_rz;
-  receivedData.Rdist = Sent_dist;
-  send_var_once();
-  print_received_Data();
-  
-  //-------------------------------------------------------------------------------------
-  control_motion();
-  //-------------------------------------------------------------------------------------
-}
-// ================================== ^ Main loop ^ ===================================================
-void control_motion(){
-  // vertical motor
-  motorVertical_L->setSpeed(abs(Rec_pwm1));
-  motorVertical_R->setSpeed(abs(Rec_pwm2));  
-  
-  if (Rec_dir1 == "+"){
-    motorVertical_L->run(BACKWARD); // up 
-  }else if (Rec_dir1 == "-"){
-    motorVertical_L->run(FORWARD); // down 
-  }
-
-  if (Rec_dir2 == "+"){ 
-    motorVertical_R->run(FORWARD);
-  }else if (Rec_dir2 == "-"){
-    motorVertical_R->run(BACKWARD);    
-  }
-
-  // horizontal motor
-  motorLeft->setSpeed(abs(Rec_pwm3));
-  motorRight->setSpeed(abs(Rec_pwm4));
-
-  if (Rec_dir3 == "+"){ 
-    motorLeft->run(BACKWARD); // make it move forward 
-  }else if (Rec_dir3 == "-"){
-    motorLeft->run(FORWARD);   // make it move backward  
-  }
-
-  if (Rec_dir4 == "+"){ 
-    motorRight-> run(FORWARD);  // make it move forward 
-  }else if (Rec_dir4 == "-"){
-    motorRight-> run(BACKWARD); // make it move backward 
-  }
-  
-}
-
-void print_received_Data(){
-  if (print_count == 0){
-  Serial.print("Rec_pwm1:");
-  Serial.println(Rec_pwm1);
-  Serial.print("Rec_pwm2:");
-  Serial.println(Rec_pwm2);
-  Serial.print("Rec_pwm3:");
-  Serial.println(Rec_pwm3);
-  Serial.print("Rec_pwm4:");
-  Serial.println(Rec_pwm4); 
-  Serial.print("Rec_dir1:");
-  Serial.println(Rec_dir1); 
-  Serial.print("Rec_dir2:");
-  Serial.println(Rec_dir2); 
-  Serial.print("Rec_dir3:");
-  Serial.println(Rec_dir3);
-  Serial.print("Rec_dir4:");
-  Serial.println(Rec_dir4);    
-Serial.println("_________________________");
-  }
-  print_count +=1;
-}
-
-void send_var_once(){
-  if(count_var==0){
-    send_message(); 
-    count_var+=1;
-  }
-}
-
-void send_message_once(){
-  if(count==0){
-    send_message(); 
-    count+=1;
-    receivedData.DebugM = "";
-  }
-}
-
-void send_message(){
-  esp_err_t result = esp_now_send(broadcastAddress, (uint8_t *) &receivedData, sizeof(receivedData));
-  // esp_now_send(RxMACaddress, (uint8_t *) &sentData, sizeof(sentData));
-  //-------------------------------------------------------------------------------------
-  if (result == ESP_OK) {
-    Serial.println("Sent with success");
-  }
-  else {
-    Serial.println("Error sending the data");
-  }
-  //-------------------------------------------------------------------------------------
-  delay(50); // delay 50 ms after send out the message 
-}
+#include <esp_now.h>
+#include <WiFi.h>
+#include <Wire.h>
+#include <SparkFun_VL53L1X.h>
+#include <Arduino.h>
+
+#include "Camera.h"
+#include "utilities.h"
+#include <Adafruit_MotorShield.h>
+
+// REPLACE WITH THE MAC Address of your receiver (MASTER)
+// Slave: 40:F5:20:44:B6:4C
+// uint8_t broadcastAddress[] = {0x3C, 0x61, 0x05, 0x4A, 0xCF, 0x00};
+uint8_t broadcastAddress[] = {0x40, 0xF5, 0x20, 0x44, 0xB6, 0x4C}; // #4
+String success;
+
+// Define variables to store incoming readings
+String sentDebugM = "";
+int Rec_pwm1;
+int Rec_pwm2;
+int Rec_pwm3;
+int Rec_pwm4;
+String Rec_dir1;
+String Rec_dir2;
+String Rec_dir3;
+String Rec_dir4;
+
+int count = 0;
+int count_var = 0;
+int print_count = 0;
+int change_count =0;
+int Lidar_flag = 0;
+
+// Define variables to be sent;
+int Sent_tx = 0;
+int Sent_ty = 0;
+int Sent_tz = 0;
+int Sent_rx = 0;
+int Sent_ry = 0;
+int Sent_rz = 0;
+int Sent_dist = 0;
+
+int8_t g1 = 0,g2=1,g3=2;
+int8_t goal_id[3] = {g1, g2, g3};
+
+// Define Lidar variables
+SFEVL53L1X distanceSensor;
+int budgetIndex = 4;
+int budgetValue[7] = {15, 20, 33, 50, 100, 200, 500};
+
+// Define LED variable
+int LED = LED_BUILTIN;
+
+// ==================================== data structure =================================================
+//Structure the sending data
+//Must match the receiver structure
+typedef struct struct_message {
+  int Rtx;
+  int Rty;
+  int Rtz;
+  int Rrx;
+  int Rry;
+  int Rrz;
+  int Rdist;
+  String DebugM;
+  int Spwm1;
+  int Spwm2;
+  int Spwm3;
+  int Spwm4;
+  String Sdir1;
+  String Sdir2;
+  String Sdir3;
+  String Sdir4;
+} struct_message;
+// Create a struct_message to hold incoming sensor readings
+// struct_message incomingReadings;
+struct_message receivedData;
+
+// =================================== send and received function =====================================
+// Callback when data is sent
+void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) {
+  Serial.print("\r\nLast Packet Send Status:\t");
+  Serial.println(status == ESP_NOW_SEND_SUCCESS ? "Delivery Success" : "Delivery Fail");
+  if (status ==0){
+    success = "Delivery Success :)";
+  }
+  else{
+    success = "Delivery Fail :(";
+  }
+}
+
+// Callback when data is received
+void OnDataRecv(const uint8_t * mac, const uint8_t *incomingData, int len) {
+  memcpy(&receivedData, incomingData, sizeof(receivedData));
+  // the data format: 225 225 225 225 + + - -
+  // + up / forward 
+  // - down / backward
+  Rec_pwm1 = receivedData.Spwm1;
+  Rec_pwm2 = receivedData.Spwm2; 
+  Rec_pwm3 = receivedData.Spwm3;
+  Rec_pwm4 = receivedData.Spwm4;    
+  Rec_dir1 = receivedData.Sdir1;  
+  Rec_dir2 = receivedData.Sdir2; 
+  Rec_dir3 = receivedData.Sdir3; 
+  Rec_dir4 = receivedData.Sdir4;   
+  count_var = 0;
+  count = 0;
+  print_count=0;
+  change_count = 0;  
+}
+
+// =============================== All the setup ===========================================
+//Create the interface that will be used by the camera
+openmv::rpc_scratch_buffer<256> scratch_buffer; // All RPC objects share this buffer.
+openmv::rpc_i2c_master interface(0x12, 100000); //to make this more robust, consider making address and rate as constructor argument
+Camera cam(&interface);
+// ========================== Motor part ====================================
+// Create the motor shield object with the default I2C address
+Adafruit_MotorShield AFMS = Adafruit_MotorShield();
+// changed
+Adafruit_DCMotor *motorVertical_L = AFMS.getMotor(1);  // pwm1
+Adafruit_DCMotor *motorVertical_R = AFMS.getMotor(2);  // pwm2
+Adafruit_DCMotor *motorLeft = AFMS.getMotor(3);        // pwm3
+Adafruit_DCMotor *motorRight = AFMS.getMotor(4);       // pwm4 
+// ==================================== Set up =================================================
+void setup() {
+  // Init Serial Monitor
+  Serial.begin(115200);
+  Wire.begin();
+  interface.begin(); //communication between ESP and OpenMV
+  AFMS.begin();  // create with the default frequency 1.6KHz
+  // -------------- LED part --------------------
+  pinMode(LED, OUTPUT);
+  digitalWrite(LED, HIGH);
+  digitalWrite(LED, LOW);
+  
+  // -------------- lidar part --------------------
+  if (distanceSensor.begin() == 0){
+    Serial.println("Sensor online!");
+    Lidar_flag = 1;
+  }else {
+    Lidar_flag = 0;
+  }
+     
+  distanceSensor.startRanging();
+  distanceSensor.setIntermeasurementPeriod(budgetValue[budgetIndex]);
+  
+ // --------------------------- esp now ---------------------------
+  // Set device as a Wi-Fi Station
+  WiFi.mode(WIFI_STA);
+
+  // Init ESP-NOW
+  if (esp_now_init() != ESP_OK) {
+    Serial.println("Error initializing ESP-NOW");
+    return;
+  }
+  
+  // Once ESPNow is successfully Init, we will register for Send CB to
+  // get the status of Trasnmitted packet
+  esp_now_register_send_cb(OnDataSent);
+  
+  // Register peer
+  esp_now_peer_info_t peerInfo;
+  memcpy(peerInfo.peer_addr, broadcastAddress, 6);
+  peerInfo.channel = 0;  
+  peerInfo.encrypt = false;
+  
+  // Add peer        
+  if (esp_now_add_peer(&peerInfo) != ESP_OK){
+    Serial.println("Failed to add peer");
+    return;
+  }
+  // Register for a callback function that will be called when data is received
+  esp_now_register_recv_cb(OnDataRecv);
+  
+}
+
+// ================================== Main loop ===================================================
+void loop()
+{ 
+  //-------------------------------------------------------------------------------------
+  // ========== goal finder =========
+  int id = -1;
+  int tx = 0; int ty = 0; int tz = 0;
+  int rx = 0; int ry = 0; int rz = 0;
+  int x = 0;
+  int y = 0; 
+  bool goalfind_flag = 0;
+  
+  goalfind_flag = cam.exe_goalfinder(goal_id[0],goal_id[1],goal_id[2], id, tx, ty, tz, rx, ry, rz);
+  if (goalfind_flag){
+      Sent_tx = tx;
+      Sent_ty = ty;
+      Sent_tz = tz; // cm
+      Sent_rx = rx;
+      Sent_ry = ry;
+      Sent_rz = rz; 
+  }else{
+      Sent_tx = 0;
+      Sent_ty = 0;
+      Sent_tz = 0; // cm
+      Sent_rx = 0;
+      Sent_ry = 0;
+      Sent_rz = 0; 
+  }
+  if (Lidar_flag == 1){
+    Sent_dist = distanceSensor.getDistance(); // Lidar distance (use the real Lidar data)
+  }else {
+    Sent_dist = 0;
+  }
+  // ========== lidar state info =========
+  if (Sent_dist < 300 && Sent_dist < 0){
+    receivedData.DebugM = "found b";
+  }else{
+    receivedData.DebugM = "no b";
+  }
+  // ========== send info =========
+  receivedData.Rtx = Sent_tx;
+  receivedData.Rty = Sent_ty;
+  receivedData.Rtz = Sent_tz;  
+  receivedData.Rrx = Sent_rx;  
+  receivedData.Rry = Sent_ry; 
+  receivedData.Rrz = Sent_rz;
+  receivedData.Rdist = Sent_dist;
+  send_var_once();
+  print_received_Data();
+  
+  //-------------------------------------------------------------------------------------
+  control_motion();
+  //-------------------------------------------------------------------------------------
+}
+// ================================== ^ Main loop ^ ===================================================
+void control_motion(){
+  // vertical motor
+  motorVertical_L->setSpeed(abs(Rec_pwm1));
+  motorVertical_R->setSpeed(abs(Rec_pwm2));  
+  
+  if (Rec_dir1 == "+"){
+    motorVertical_L->run(BACKWARD); // up 
+  }else if (Rec_dir1 == "-"){
+    motorVertical_L->run(FORWARD); // down 
+  }
+
+  if (Rec_dir2 == "+"){ 
+    motorVertical_R->run(FORWARD);
+  }else if (Rec_dir2 == "-"){
+    motorVertical_R->run(BACKWARD);    
+  }
+
+  // horizontal motor
+  motorLeft->setSpeed(abs(Rec_pwm3));
+  motorRight->setSpeed(abs(Rec_pwm4));
+
+  if (Rec_dir3 == "+"){ 
+    motorLeft->run(BACKWARD); // make it move forward 
+  }else if (Rec_dir3 == "-"){
+    motorLeft->run(FORWARD);   // make it move backward  
+  }
+
+  if (Rec_dir4 == "+"){ 
+    motorRight-> run(FORWARD);  // make it move forward 
+  }else if (Rec_dir4 == "-"){
+    motorRight-> run(BACKWARD); // make it move backward 
+  }
+  
+}
+
+void print_received_Data(){
+  if (print_count == 0){
+  Serial.print("Rec_pwm1:");
+  Serial.println(Rec_pwm1);
+  Serial.print("Rec_pwm2:");
+  Serial.println(Rec_pwm2);
+  Serial.print("Rec_pwm3:");
+  Serial.println(Rec_pwm3);
+  Serial.print("Rec_pwm4:");
+  Serial.println(Rec_pwm4); 
+  Serial.print("Rec_dir1:");
+  Serial.println(Rec_dir1); 
+  Serial.print("Rec_dir2:");
+  Serial.println(Rec_dir2); 
+  Serial.print("Rec_dir3:");
+  Serial.println(Rec_dir3);
+  Serial.print("Rec_dir4:");
+  Serial.println(Rec_dir4);    
+Serial.println("_________________________");
+  }
+  print_count +=1;
+}
+
+void send_var_once(){
+  if(count_var==0){
+    send_message(); 
+    count_var+=1;
+  }
+}
+
+void send_message_once(){
+  if(count==0){
+    send_message(); 
+    count+=1;
+    receivedData.DebugM = "";
+  }
+}
+
+void send_message(){
+  esp_err_t result = esp_now_send(broadcastAddress, (uint8_t *) &receivedData, sizeof(receivedData));
+  // esp_now_send(RxMACaddress, (uint8_t *) &sentData, sizeof(sentData));
+  //-------------------------------------------------------------------------------------
+  if (result == ESP_OK) {
+    Serial.println("Sent with success");
+  }
+  else {
+    Serial.println("Error sending the data");
+  }
+  //-------------------------------------------------------------------------------------
+  delay(50); // delay 50 ms after send out the message 
+}
diff --git a/Code/Control/Laptop_Code/ESP32_slave/New Text Document.txt b/Code/Control/Laptop_Code/ESP32_slave/New Text Document.txt
new file mode 100644
index 0000000..e69de29
diff --git a/Code/Control/Laptop_Code/ball_detection/distance-detection-torch/__pycache__/distance-detection-torch.cpython-38.pyc b/Code/Control/Laptop_Code/ball_detection/distance-detection-torch/__pycache__/distance-detection-torch.cpython-38.pyc
index 27224b96dea1a0e479427d1d2c7098432f587093..06f3a4090cab1824747125e7eb748088c17a673f 100644
GIT binary patch
delta 19
ZcmX@AcT|rnl$V!_0SNRyZsf8S2LLh(1eO2*

delta 19
ZcmX@AcT|rnl$V!_0SJU%Zsf8S2LLfT1abfX

diff --git a/Code/Control/Laptop_Code/constants.py b/Code/Control/Laptop_Code/constants.py
index c4aae16..be949ed 100644
--- a/Code/Control/Laptop_Code/constants.py
+++ b/Code/Control/Laptop_Code/constants.py
@@ -30,13 +30,12 @@ Bmin = 31
 Bmax = 127
 threshold = [Lmin, Lmax, Amin, Amax, Bmin, Bmax]
 
-base_speed    = 70
+base_speed    = 30
 seeking_speed = 70
 LIDAR_Thres   = 300 # mm
 
 
-base_speed = 70
 
 # PID Control
-kdx,kix,kpx = 2,0.1,0.25
-kdy,kiy,kpy = 1,0.1,0.25
+kpx,kix,kdx = 0.7, 0.01, 0.25
+kpy,kiy,kdy = 0.5, 0.01, 0.25
diff --git a/Code/Control/Laptop_Code/main.py b/Code/Control/Laptop_Code/main.py
index afc2681..2a51fa0 100644
--- a/Code/Control/Laptop_Code/main.py
+++ b/Code/Control/Laptop_Code/main.py
@@ -158,9 +158,10 @@ def seeking():
         pwm1, pwm2, pwm3, pwm4
         dir1, dir2, dir3, dir4
     """
-    pass
-    # return int(pwm1), int(pwm2), int(pwm3), int(pwm4), dir1, dir2, dir3, dir4
+    pwm1, pwm2, pwm3, pwm4 = 0 , 0 , seeking_speed , seeking_speed
+    dir1, dir2, dir3, dir4 = '+', '+', '+', '-'
 
+    return int(pwm1), int(pwm2), int(pwm3), int(pwm4), dir1, dir2, dir3, dir4
 
 def move2ball(gbx,gby,gb_dist):
     """
@@ -258,7 +259,7 @@ def main_control(gbx, gby, gb_dist, tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM):
 
         if goalDetect:  # Goal detected
             pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = move2goal(tx, ty)
-        else:  # Goal not detectedpwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = 
+        else:  # Goal not detectedpwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 =
             pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = seeking()
     else:  # Ball not captured
         if ballDetect:  # Ball detected
diff --git a/Code/Control/Laptop_Code/main_zhiying_catchBall_test_2in1.py b/Code/Control/Laptop_Code/main_zhiying_catchBall_test_2in1.py
new file mode 100644
index 0000000..175bdc2
--- /dev/null
+++ b/Code/Control/Laptop_Code/main_zhiying_catchBall_test_2in1.py
@@ -0,0 +1,371 @@
+import time
+import serial
+import ball_detection.ball_detection as ball_detection
+import simple_pid.PID as PID
+import timeit
+
+
+from constants import *
+
+# ========= Serial Port I/O ===========
+
+def serial_port_in(serial_port):
+    '''
+    Description:
+        Take all ESP32_Master serial port's printIn and take all necessary input object
+
+    Input:
+        serial_port     :    serial.Serail object
+
+    Output:
+        tx, ty, tz, rx, ry, rz, LIDAR_dist, DebugM
+    '''
+
+    # DEBUG Verbose
+    print("initiating one round of serial in ...")
+
+    for i in range(7):
+        line = serial_port.readline()
+        val = int(line.decode())
+
+        if   i == 0:
+            tx = val
+        elif i == 1:
+            ty = val
+        elif i == 2:
+            tz = val
+        elif i == 3:
+            rx = val
+        elif i == 4:
+            ry = val
+        elif i == 5:
+            rz = val
+        elif i == 6:
+            LIDAR_dist = val
+
+    line = serial_port.readline()
+    debugM = line.decode()
+
+    # DEBUG Verbose
+    print("tx:{}".format(tx))
+    print("ty:{}".format(ty))
+    print("tz:{}".format(tz))
+    print("rx:{}".format(rx))
+    print("ry:{}".format(ry))
+    print("rz:{}".format(rz))
+    print("dist:{}".format(LIDAR_dist))
+    print(debugM)
+
+    return tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM
+
+
+def serial_port_out(serial_port, pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4):
+    '''
+    Description:
+        Feed to ESP32_Master to send ESP32_Slave necessary information
+        the format of sending is pwm are 3 digit space
+
+    Input:
+        serial_port                                     :   serial.Serail object
+        pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4  :   variables to send
+
+    Output:
+        None
+    '''
+
+    output_message = ''
+
+    for pwm_itr in [pwm1, pwm2, pwm3, pwm4]:
+        # print(pwm_itr)
+        if len(str(pwm_itr)) == 2:
+            output_message += '0'
+        elif len(str(pwm_itr)) == 1:
+            output_message += '00'
+        output_message += str(pwm_itr)
+        print(pwm_itr)
+
+    output_message = output_message + dir1 + dir2 +  dir3 +  dir4 + '\n'
+    print("serial out ...")
+    print(output_message)
+    serial_port.write(output_message.encode())
+
+    # DEBUG Verbose
+
+
+
+
+
+# ====== supporting function in main control ====
+def ball_detect(gbx, gby):
+    '''
+    return True if green ball is detected
+    '''
+    if gbx == -1 and gby == -1:
+        return False
+    else:
+        return True
+
+def goal_detect(tx,ty):
+    '''
+    return True if April Tag is detected
+    '''
+    if tx == 0 and ty == 0:
+        return False
+    else:
+        return True
+
+def ball_capture(LIDAR_dist):
+    '''
+    return True if April Tag is detected
+    '''
+    if (LIDAR_dist < LIDAR_Thres) and (LIDAR_dist > 0):  # Ball captured
+        return True
+    else:
+        return False
+
+def stop_all():
+    pwm1, pwm2, pwm3, pwm4 = 0 , 0 , 0 , 0
+    dir1, dir2, dir3, dir4 = '+', '-', '+', '-'
+    return pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4
+
+def move2goal(tx, ty):
+    """
+    Description:
+        Given the center of the AT tx, ty. Call PID control to output the blimp
+        motor to manuver to the goal
+
+    Input:
+        tx    :    x component, center of April Tag
+        ty    :    y component, center of Aprol Tag
+
+    Output:
+        pwm1, pwm2, pwm3, pwm4
+        dir1, dir2, dir3, dir4
+    """
+    pass
+
+    # return pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4
+
+
+def seeking():
+    """
+    Description:
+        By default, when there ball is not determined capture, the manuver of the
+        motors to have it scan its surronding 360 degrees
+
+    Input:
+        none
+
+    Output:
+        pwm1, pwm2, pwm3, pwm4
+        dir1, dir2, dir3, dir4
+    """
+    pwm1, pwm2, pwm3, pwm4 = 0 , 0 , seeking_speed , seeking_speed
+    dir1, dir2, dir3, dir4 = '+', '+', '+', '-'
+
+    return int(pwm1), int(pwm2), int(pwm3), int(pwm4), dir1, dir2, dir3, dir4
+
+
+def move2ball(gbx, gby, gb_dist):
+    """
+    Description:
+        Given the center of x y dist of green ball detected. Call PID control to
+        output the blimp motor to manuver to the green ball
+
+    Input:
+        gbx     :  x component, center of green ball
+        gby     :  y component, center of green ball
+        gb_dist :  distance to green ball
+
+    Output:
+        pwm1, pwm2, pwm3, pwm4
+        dir1, dir2, dir3, dir4
+    """
+    inputx = gbx / 1.00
+    inputy = gby / 1.00
+
+    setpoint_x = 400
+    setpoint_y = 300  # ESP 32 Cam Center
+
+    pid_x = PID(kpx,kix,kdx,setpoint=setpoint_x)
+    pid_y = PID(kpy,kiy,kdy,setpoint=setpoint_y)
+
+
+    pid_x.auto_mode = True
+    pid_x.set_auto_mode(True, last_output=8.0)
+    pid_x.output_limits = (-255,255)
+    pid_y.output_limits = (-255,255)
+
+
+    outputx = pid_x(inputx)
+    outputy = pid_y(inputy)
+
+    # vertical
+    pwm1 = abs(outputy)
+    pwm2 = abs(outputy)
+
+    if(outputy > 0):
+        dir1 = '+'
+        dir2 = '+'
+    else:
+        dir1 = '-'
+        dir2 = '-'
+
+    # horizontal
+    lspeed = -1 * outputx + base_speed
+    rspeed =  1 * outputx + base_speed
+    pwm3 = min( abs(lspeed), 255)
+    pwm4 = min( abs(rspeed), 255)
+    if (lspeed > 0):
+        dir3 = '+'
+    else:
+        dir3 = '-'
+
+    if (rspeed > 0):
+        dir4 = '+'
+    else:
+        dir4 = '-'
+
+
+    return int(pwm1), int(pwm2), int(pwm3), int(pwm4), dir1, dir2, dir3, dir4
+
+
+
+#  =========== main control ===========
+
+def main_control(gbx, gby, gb_dist, tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM):
+    '''
+    Description:
+        Given green ball information and AT information, the main control logic
+        to manuver the blimp motors
+
+    Input:
+        gbx, gby, gb_dist                   :   green ball information
+        tx, ty, tz, rx, ry, rz, LIDAR_dist  :   AirTag information
+        debugM                              :   Debug Message
+
+    Output:
+        pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4  :   Blimp motor manuver parameters
+    '''
+
+    # placeholder
+    pwm1, pwm2, pwm3, pwm4 = 0 , 0 , 0 , 0
+    dir1, dir2, dir3, dir4 = '+', '-', '+', '-'
+
+    ballDetect  = ball_detect(gbx, gby)
+    ballCapture = ball_capture(LIDAR_dist)
+    goalDetect  = goal_detect(tx,ty)
+    # debug
+    ballCapture = 0
+    if ballCapture: # Ball captured
+        if goalDetect:  # Goal detected
+            stop_all()
+            #pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = move2goal(tx, ty)
+        else:  # Goal not detected
+            stop_all()
+            #pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = seeking()
+    else:  # Ball not captured
+        if ballDetect:  # Ball detected
+            pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = move2ball(gbx,gby,gb_dist)
+        else:  # Ball not detected
+            pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = seeking()
+
+    return pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4
+
+
+
+# ===== Main Functions =====
+
+if __name__ == '__main__':
+    # =========== SET UP ============
+    # Defining Variables for ESP 32 Serial I/O
+    PORT = "COM6" # for Alienware
+    serial_port = serial.Serial(PORT, 115200)
+    serial_port.close()
+    serial_port.open()
+
+    # Weit Time
+    waitTime = 0.1
+
+    # Loading the PyTorch ML model for ball detection
+    model = ball_detection.returnModel(device, labelSet, modelLoc, modelFile)
+    #model = ball_detection.returnModel(modelAction, device, trainLoc, labelSet, modelLoc, modelFile)
+
+
+    # =========== DECLARE VARIABLES ===========
+    # ESP CAM In
+    gbx, gby  = -1, -1   # by default (-1 means no found green ball)
+    gb_dist = -1         # by default (-1 means no found green ball)
+
+    # Serial Port In
+    tx, ty, tz = 0, 0, 0  # by default (0 means no found AirTag)
+    rx, ry, rz = 0, 0, 0
+    LIDAR_dist = 0
+    debugM = 'Testing'
+
+    # Serial Port Out
+    pwm1, pwm2, pwm3, pwm4 = 0 , 0 , 0 , 0   # Not moving
+    dir1, dir2, dir3, dir4 = '+', '+', '+', '+'
+
+    count = 0
+    flg = 0
+    # =========== LOOP FOREVER===========
+    while True:
+
+        gbx, gby, gb_dist = ball_detection.detectLive(model, minDetectionScore, showSight = True)
+        # print("gbx,gby:{},{}".format(gbx,gby))
+        # tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM = serial_port_in(serial_port)
+
+        # ===== STEP 2: MAIN CONTROL LOOP =====
+        pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = main_control(gbx, gby, gb_dist, tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM)
+
+        # ===== STEP 3: FEED ALL OUTPUT =====
+        serial_port_out(serial_port, pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4)
+
+        time.sleep(0.1)
+
+        """
+        line = serial_port.readline()
+        if line == b'SERIAL_IN_START\r\n':
+            # start = time.time()
+            # print('I have been there')
+            # ===== STEP 1: TAKE ALL INPUT =====
+            gbx, gby, gb_dist = ball_detection.detectLive(model, minDetectionScore, showSight = True)
+            # print("gbx,gby:{},{}".format(gbx,gby))
+            tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM = serial_port_in(serial_port)
+
+            # ===== STEP 2: MAIN CONTROL LOOP =====
+            pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = main_control(gbx, gby, gb_dist, tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM)
+
+            # ===== STEP 3: FEED ALL OUTPUT =====
+            serial_port_out(serial_port, pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4)
+
+
+            # end = time.time()
+            # print("time:")
+            # print(end - start)
+        if count == 0:
+            # first time calling (call once)
+            print("bbb")
+            pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = main_control(gbx, gby, gb_dist, tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM)
+            serial_port_out(serial_port, pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4)
+            count +=1
+        """
+
+        """
+        if flg == 1:
+            print("1")
+            output_message = '100100000000+-++' + '\n'
+            serial_port.write(output_message.encode())
+
+            flg = 0
+            time.sleep(0.3)
+        elif flg == 0:
+            print("2")
+            output_message = '000000000000+-++' + '\n'
+            serial_port.write(output_message.encode())
+            flg = 1
+            time.sleep(0.3)
+        """
+
+        # time.sleep(waitTime)
diff --git a/Code/Control/Laptop_Code/main_zhiying_seeking_indv_test.py b/Code/Control/Laptop_Code/main_zhiying_seeking_indv_test.py
index 461b8ca..cfd5faa 100644
--- a/Code/Control/Laptop_Code/main_zhiying_seeking_indv_test.py
+++ b/Code/Control/Laptop_Code/main_zhiying_seeking_indv_test.py
@@ -157,8 +157,11 @@ def seeking():
         pwm1, pwm2, pwm3, pwm4
         dir1, dir2, dir3, dir4
     """
-    pass
-    # return pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4
+    #pwm1, pwm2, pwm3, pwm4 = 0 , 0 , seeking_speed , seeking_speed
+    pwm1, pwm2, pwm3, pwm4 = 0 , 0 , 70, 70
+    dir1, dir2, dir3, dir4 = '+', '+', '+', '-'
+
+    return int(pwm1), int(pwm2), int(pwm3), int(pwm4), dir1, dir2, dir3, dir4
 
 
 def move2ball(gbx, gby, gb_dist):
@@ -268,8 +271,7 @@ def main_control(gbx, gby, gb_dist, tx, ty, tz, rx, ry, rz, LIDAR_dist, debugM):
         if ballDetect:  # Ball detected
             pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = move2ball(gbx,gby,gb_dist)
         else:  # Ball not detected
-            stop_all()
-            #pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = seeking()
+            pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4 = seeking()
 
     return pwm1, pwm2, pwm3, pwm4, dir1, dir2, dir3, dir4
 
@@ -311,7 +313,7 @@ if __name__ == '__main__':
     count = 0
     # =========== LOOP FOREVER===========
     while True:
-        gbx, gby, gb_dist = ball_detection.detectLive(model, minDetectionScore, showSight = True)
+        #gbx, gby, gb_dist = ball_detection.detectLive(model, minDetectionScore, showSight = True)
         print("gbx,gby:{},{}".format(gbx,gby))
 
         line = serial_port.readline()
-- 
GitLab