distribution-201229

Dependencies:   mbed FastPWM

Files at this revision

API Documentation at this revision

Comitter:
Lightvalve
Date:
Mon Dec 28 14:27:11 2020 +0000
Parent:
223:e26830fbaffd
Commit message:
distribution

Changed in this revision

CAN/function_CAN.cpp Show annotated file Show diff for this revision Revisions of this file
SPI_EEP_ENC/SPI_EEP_ENC.h Show annotated file Show diff for this revision Revisions of this file
function_utilities/function_utilities.cpp Show annotated file Show diff for this revision Revisions of this file
function_utilities/function_utilities.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
setting.h Show annotated file Show diff for this revision Revisions of this file
--- a/CAN/function_CAN.cpp	Mon Dec 28 12:10:50 2020 +0000
+++ b/CAN/function_CAN.cpp	Mon Dec 28 14:27:11 2020 +0000
@@ -62,8 +62,6 @@
         }
         case CRX_SET_BNO: {
             BNO = (int16_t) msg.data[1];
-
-            //ROM_RESET_DATA();
             spi_eeprom_write(RID_BNO, (int16_t) BNO);
             CAN_ID_INIT(); // can id init
             break;
@@ -77,7 +75,6 @@
             SENSING_MODE = (uint8_t) msg.data[2];
             CURRENT_CONTROL_MODE = (uint8_t) msg.data[3];
             FLAG_VALVE_DEADZONE = (uint8_t) msg.data[4];
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_OPERATING_MODE, (int16_t) OPERATING_MODE);
             spi_eeprom_write(RID_SENSING_MODE, (int16_t) SENSING_MODE);
             spi_eeprom_write(RID_CURRENT_CONTROL_MODE, (int16_t) CURRENT_CONTROL_MODE);
@@ -113,7 +110,6 @@
 
         case CRX_SET_CAN_FREQ: {
             CAN_FREQ = (int16_t) (msg.data[1] | msg.data[2] << 8);
-            ROM_RESET_DATA();
             spi_eeprom_write(RID_CAN_FREQ, (int16_t) CAN_FREQ);
             break;
         }
@@ -125,7 +121,6 @@
         }
 
         case CRX_SET_CONTROL_MODE: {
-            //CONTROL_MODE = (int16_t) (msg.data[1]);
             CONTROL_UTILITY_MODE = (int16_t) (msg.data[1]);
             if (CONTROL_MODE == 22) {    //MODE_FIND_HOME
                 FLAG_FIND_HOME = true;
@@ -136,7 +131,6 @@
         case CRX_SET_DATA_REQUEST: {
             int request_type = msg.data[2];
             flag_data_request[request_type] = msg.data[1];
-            //pc.printf("can middle %d\n", request_type);
 
 //            if (flag_data_request[1] == HIGH) SPI_VREF_DAC_WRITE(PRES_A_VREF, PRES_B_VREF, TORQUE_VREF, 0); // set DAC
             //if (flag_data_request[1] == HIGH) dac_1 = PRES_A_VREF/3.3;
@@ -159,8 +153,6 @@
             else
                 DIR_JOINT_ENC = -1;
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_JOINT_ENC_DIR, (int16_t) DIR_JOINT_ENC);
 
             break;
@@ -179,8 +171,6 @@
             else
                 DIR_VALVE = -1;
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_VALVE_DIR, (int16_t) DIR_VALVE);
 
             break;
@@ -199,8 +189,6 @@
             else
                 DIR_VALVE_ENC = -1;
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_VALVE_ENC_DIR, (int16_t) DIR_VALVE_ENC);
 
             break;
@@ -215,7 +203,6 @@
         case CRX_SET_VOLTAGE_SUPPLY: {
             SUPPLY_VOLTAGE = (double) ((int16_t) (msg.data[1] | msg.data[2] << 8)) / 10.0f;
 
-//            ROM_RESET_DATA();
 
             spi_eeprom_write(RID_VOLATGE_SUPPLY, (int16_t) (SUPPLY_VOLTAGE * 10.0f));
 
@@ -231,8 +218,6 @@
         case CRX_SET_VOLTAGE_VALVE: {
             VALVE_VOLTAGE_LIMIT = (double) ((int16_t) (msg.data[1] | msg.data[2] << 8)) / 10.0f;
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_VOLTAGE_VALVE, (int16_t) (VALVE_VOLTAGE_LIMIT * 10.0f));
 
 
@@ -240,7 +225,6 @@
         }
 
         case CRX_SET_HOMEPOS: {
-            //CONTROL_MODE = 22;
             CONTROL_UTILITY_MODE = 22;
             break;
         }
@@ -257,7 +241,6 @@
                 I_GAIN_VALVE_POSITION = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_VALVE_POSITION = (int16_t) (msg.data[6] | msg.data[7] << 8);
 
-//                ROM_RESET_DATA();
                 spi_eeprom_write(RID_P_GAIN_VALVE_POSITION, (int16_t) P_GAIN_VALVE_POSITION);
                 spi_eeprom_write(RID_I_GAIN_VALVE_POSITION, (int16_t) I_GAIN_VALVE_POSITION);
                 spi_eeprom_write(RID_D_GAIN_VALVE_POSITION, (int16_t) D_GAIN_VALVE_POSITION);
@@ -267,7 +250,6 @@
                 I_GAIN_JOINT_POSITION = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_JOINT_POSITION = (int16_t) (msg.data[6] | msg.data[7] << 8);
 
-//                ROM_RESET_DATA();
                 spi_eeprom_write(RID_P_GAIN_JOINT_POSITION, (int16_t) P_GAIN_JOINT_POSITION);
                 spi_eeprom_write(RID_I_GAIN_JOINT_POSITION, (int16_t) I_GAIN_JOINT_POSITION);
                 spi_eeprom_write(RID_D_GAIN_JOINT_POSITION, (int16_t) D_GAIN_JOINT_POSITION);
@@ -277,7 +259,6 @@
                 I_GAIN_JOINT_TORQUE = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_JOINT_TORQUE = (int16_t) (msg.data[6] | msg.data[7] << 8);
 
-//                ROM_RESET_DATA();
                 spi_eeprom_write(RID_P_GAIN_JOINT_TORQUE, (int16_t) P_GAIN_JOINT_TORQUE);
                 spi_eeprom_write(RID_I_GAIN_JOINT_TORQUE, (int16_t) I_GAIN_JOINT_TORQUE);
                 spi_eeprom_write(RID_D_GAIN_JOINT_TORQUE, (int16_t) D_GAIN_JOINT_TORQUE);
@@ -286,7 +267,6 @@
                 K_SPRING = (float) (((float) ((int16_t) (msg.data[2] | msg.data[3] << 8))) * 0.1f);
                 D_DAMPER = (float) (((float) ((int16_t) (msg.data[4] | msg.data[5] << 8))) * 0.01f);
 
-//                ROM_RESET_DATA();     //For Real-time changing
 //                spi_eeprom_write(RID_K_SPRING, (int16_t) K_SPRING);
 //                spi_eeprom_write(RID_D_DAMPER, (int16_t) D_DAMPER);
 
@@ -295,7 +275,6 @@
                 I_GAIN_JOINT_TORQUE_FF = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_JOINT_TORQUE_FF = (int16_t) (msg.data[6] | msg.data[7] << 8);
 
-//                ROM_RESET_DATA();
             }
 
             break;
@@ -312,7 +291,6 @@
             VALVE_DEADZONE_PLUS = (int16_t) (msg.data[3] | msg.data[4] << 8);
             VALVE_DEADZONE_MINUS = (int16_t) (msg.data[5] | msg.data[6] << 8);
 
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_VALVE_CNETER, (int16_t) VALVE_CENTER);
             spi_eeprom_write(RID_VALVE_DEADZONE_PLUS, (int16_t) (VALVE_DEADZONE_PLUS*10.0f));
             spi_eeprom_write(RID_VALVE_DEADZONE_MINUS, (int16_t) (VALVE_DEADZONE_MINUS*10.0f));
@@ -329,7 +307,6 @@
         case CRX_SET_VELOCITY_COMP_GAIN: {
             VELOCITY_COMP_GAIN = (int16_t) (msg.data[1] | msg.data[2] << 8);
 
-//            ROM_RESET_DATA();
 
             spi_eeprom_write(RID_VELOCITY_COMP_GAIN, (int16_t) VELOCITY_COMP_GAIN);
 
@@ -345,7 +322,6 @@
         case CRX_SET_COMPLIANCE_GAIN: {
             COMPLIANCE_GAIN = (int16_t) (msg.data[1] | msg.data[2] << 8);
 
-//            ROM_RESET_DATA();
 
             spi_eeprom_write(RID_COMPLIANCE_GAIN, (int16_t) COMPLIANCE_GAIN);
 
@@ -361,8 +337,6 @@
         case CRX_SET_VALVE_FF: {
             VALVE_FF = (int16_t) (msg.data[1] | msg.data[2] << 8);
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_VALVE_FF, (int16_t) VALVE_FF);
 
             break;
@@ -376,9 +350,6 @@
 
         case CRX_SET_BULK_MODULUS: {
             BULK_MODULUS = (int16_t) (msg.data[1] | msg.data[2] << 8);
-
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_BULK_MODULUS, (int16_t) BULK_MODULUS);
 
             break;
@@ -394,8 +365,6 @@
             CHAMBER_VOLUME_A = (int16_t) (msg.data[1] | msg.data[2] << 8);
             CHAMBER_VOLUME_B = (int16_t) (msg.data[3] | msg.data[4] << 8);
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_CHAMBER_VOLUME_A, (int16_t) CHAMBER_VOLUME_A);
             spi_eeprom_write(RID_CHAMBER_VOLUME_B, (int16_t) CHAMBER_VOLUME_B);
 
@@ -414,8 +383,6 @@
             PISTON_AREA_alpha = (double)PISTON_AREA_A/(double)PISTON_AREA_B;
             alpha3 = PISTON_AREA_alpha * PISTON_AREA_alpha*PISTON_AREA_alpha;
 
-//            ROM_RESET_DATA();
-
             spi_eeprom_write(RID_PISTON_AREA_A, (int16_t) PISTON_AREA_A);
             spi_eeprom_write(RID_PISTON_AREA_B, (int16_t) PISTON_AREA_B);
             break;
@@ -433,7 +400,6 @@
         case CRX_SET_PRES: {
             PRES_SUPPLY = (int16_t) (msg.data[1] | msg.data[2] << 8);
             PRES_RETURN = (int16_t) (msg.data[3] | msg.data[4] << 8);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_PRES_SUPPLY, (int16_t) PRES_SUPPLY);
             spi_eeprom_write(RID_PRES_RETURN, (int16_t) PRES_RETURN);
 
@@ -450,7 +416,6 @@
         case CRX_SET_ENC_LIMIT: {
             ENC_LIMIT_MINUS = (int16_t) (msg.data[1] | msg.data[2] << 8);
             ENC_LIMIT_PLUS = (int16_t) (msg.data[3] | msg.data[4] << 8);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_ENC_LIMIT_MINUS, (int16_t) ENC_LIMIT_MINUS);
             spi_eeprom_write(RID_ENC_LIMIT_PLUS, (int16_t) ENC_LIMIT_PLUS);
 
@@ -464,7 +429,6 @@
 
         case CRX_SET_STROKE: {
             STROKE = (int16_t) (msg.data[1] | msg.data[2] << 8);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_STROKE, (int16_t) STROKE);
 
             break;
@@ -479,7 +443,6 @@
         case CRX_SET_VALVE_LIMIT: {
             VALVE_MIN_POS = (int16_t) (msg.data[1] | msg.data[2] << 8);
             VALVE_MAX_POS = (int16_t) (msg.data[3] | msg.data[4] << 8);
-//            ROM_RESET_DATA();
 
             spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
             spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
@@ -495,7 +458,6 @@
 
         case CRX_SET_ENC_PULSE_PER_POSITION: {
             ENC_PULSE_PER_POSITION = (int16_t) (msg.data[1] | msg.data[2] << 8);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_ENC_PULSE_PER_POSITION, (int16_t) (ENC_PULSE_PER_POSITION));
 
             break;
@@ -509,7 +471,6 @@
 
         case CRX_SET_TORQUE_SENSOR_PULSE_PER_TORQUE: {
             TORQUE_SENSOR_PULSE_PER_TORQUE = (float) ((int16_t) (msg.data[1] | msg.data[2] << 8) * 0.0001f);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_TORQUE_SENSOR_PULSE_PER_TORQUE, (int16_t) (TORQUE_SENSOR_PULSE_PER_TORQUE*10000.0f));
 
             break;
@@ -524,7 +485,6 @@
         case CRX_SET_PRES_SENSOR_PULSE_PER_PRES: {
             PRES_SENSOR_A_PULSE_PER_BAR = (double) ((int16_t) (msg.data[1] | msg.data[2] << 8)) * 0.01f;
             PRES_SENSOR_B_PULSE_PER_BAR = (double) ((int16_t) (msg.data[3] | msg.data[4] << 8)) * 0.01f;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_PRES_SENSOR_A_PULSE_PER_BAR, (int16_t) (PRES_SENSOR_A_PULSE_PER_BAR * 100.0f));
             spi_eeprom_write(RID_PRES_SENSOR_B_PULSE_PER_BAR, (int16_t) (PRES_SENSOR_B_PULSE_PER_BAR * 100.0f));
 
@@ -539,7 +499,6 @@
 
         case CRX_SET_FRICTION: {
             FRICTION = (double) ((int16_t) (msg.data[1] | msg.data[2] << 8)) / 10.0f;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_FRICTION, (int16_t) (FRICTION * 10.0f));
 
             break;
@@ -556,7 +515,6 @@
             VALVE_GAIN_LPM_PER_V[4] = (double) msg.data[3] / 50.0f;
             VALVE_GAIN_LPM_PER_V[6] = (double) msg.data[4] / 50.0f;
             VALVE_GAIN_LPM_PER_V[8] = (double) msg.data[5] / 50.0f;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_VALVE_GAIN_PLUS_1, (int16_t) (VALVE_GAIN_LPM_PER_V[0] * 100.0f));
             spi_eeprom_write(RID_VALVE_GAIN_PLUS_2, (int16_t) (VALVE_GAIN_LPM_PER_V[2] * 100.0f));
             spi_eeprom_write(RID_VALVE_GAIN_PLUS_3, (int16_t) (VALVE_GAIN_LPM_PER_V[4] * 100.0f));
@@ -577,7 +535,6 @@
             VALVE_GAIN_LPM_PER_V[5] = (double) msg.data[3] / 50.0f;
             VALVE_GAIN_LPM_PER_V[7] = (double) msg.data[4] / 50.0f;
             VALVE_GAIN_LPM_PER_V[9] = (double) msg.data[5] / 50.0f;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_VALVE_GAIN_MINUS_1, (int16_t) (VALVE_GAIN_LPM_PER_V[1] * 100.0f));
             spi_eeprom_write(RID_VALVE_GAIN_MINUS_2, (int16_t) (VALVE_GAIN_LPM_PER_V[3] * 100.0f));
             spi_eeprom_write(RID_VALVE_GAIN_MINUS_3, (int16_t) (VALVE_GAIN_LPM_PER_V[5] * 100.0f));
@@ -628,7 +585,6 @@
         }
         case CRX_SET_HOMEPOS_OFFSET: {
             HOMEPOS_OFFSET = (int16_t) (msg.data[1] | msg.data[2] << 8);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_HOMEPOS_OFFSET, (int16_t) HOMEPOS_OFFSET);
             break;
         }
@@ -639,7 +595,6 @@
         }
         case CRX_SET_HOMEPOS_VALVE_OPENING: {
             HOMEPOS_VALVE_OPENING = (int16_t) (msg.data[1] | msg.data[2] << 8);
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_HOMEPOS_VALVE_OPENING, (int16_t) HOMEPOS_VALVE_OPENING);
             break;
         }
@@ -660,13 +615,11 @@
         }
 
         case CRX_SET_ROM: {
-            ROM_RESET_DATA();
             break;
         }
         case CRX_SET_VALVE_CENTER_OFFSET: {
             VALVE_CENTER_OFFSET = ((float) ((int16_t) (msg.data[1] | msg.data[2] << 8))) * 0.1f;
             VALVE_CENTER = VALVE_CENTER + VALVE_CENTER_OFFSET;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_VALVE_CNETER, (int16_t) VALVE_CENTER);
 
             break;
@@ -674,7 +627,6 @@
         case CRX_SET_VALVE_DZ_MINUS_OFFSET: {
             VALVE_DZ_MINUS_OFFSET = ((float) ((int16_t) (msg.data[1] | msg.data[2] << 8))) * 0.1f;
             VALVE_DEADZONE_MINUS = VALVE_DEADZONE_MINUS + VALVE_DZ_MINUS_OFFSET;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_VALVE_DEADZONE_MINUS, (int16_t) (VALVE_DEADZONE_MINUS*10.0f));
 
             break;
@@ -682,7 +634,6 @@
         case CRX_SET_VALVE_DZ_PLUS_OFFSET: {
             VALVE_DZ_PLUS_OFFSET = ((float) ((int16_t) (msg.data[1] | msg.data[2] << 8))) * 0.1f;
             VALVE_DEADZONE_PLUS = VALVE_DEADZONE_PLUS + VALVE_DZ_PLUS_OFFSET;
-//            ROM_RESET_DATA();
             spi_eeprom_write(RID_VALVE_DEADZONE_PLUS, (int16_t) (VALVE_DEADZONE_PLUS*10.0f));
             break;
         }
@@ -691,21 +642,13 @@
                 P_GAIN_VALVE_POSITION = (int16_t) (msg.data[2] | msg.data[3] << 8);
                 I_GAIN_VALVE_POSITION = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_VALVE_POSITION = (int16_t) (msg.data[6] | msg.data[7] << 8);
-
-//                ROM_RESET_DATA();
-
                 //spi_eeprom_write(RID_P_GAIN_VALVE_POSITION, (int16_t) P_GAIN_VALVE_POSITION);
                 //spi_eeprom_write(RID_I_GAIN_VALVE_POSITION, (int16_t) I_GAIN_VALVE_POSITION);
                 //spi_eeprom_write(RID_D_GAIN_VALVE_POSITION, (int16_t) D_GAIN_VALVE_POSITION);
-
-
             } else if (msg.data[1] == 1) {
                 P_GAIN_JOINT_POSITION = (int16_t) (msg.data[2] | msg.data[3] << 8);
                 I_GAIN_JOINT_POSITION = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_JOINT_POSITION = (int16_t) (msg.data[6] | msg.data[7] << 8);
-
-//                ROM_RESET_DATA();
-
                 //spi_eeprom_write(RID_P_GAIN_JOINT_POSITION, (int16_t) P_GAIN_JOINT_POSITION);
                 //spi_eeprom_write(RID_I_GAIN_JOINT_POSITION, (int16_t) I_GAIN_JOINT_POSITION);
                 //spi_eeprom_write(RID_D_GAIN_JOINT_POSITION, (int16_t) D_GAIN_JOINT_POSITION);
@@ -713,9 +656,6 @@
                 P_GAIN_JOINT_TORQUE = (int16_t) (msg.data[2] | msg.data[3] << 8);
                 I_GAIN_JOINT_TORQUE = (int16_t) (msg.data[4] | msg.data[5] << 8);
                 D_GAIN_JOINT_TORQUE = (int16_t) (msg.data[6] | msg.data[7] << 8);
-
-//                ROM_RESET_DATA();
-
                 //spi_eeprom_write(RID_P_GAIN_JOINT_TORQUE, (int16_t) P_GAIN_JOINT_TORQUE);
                 //spi_eeprom_write(RID_I_GAIN_JOINT_TORQUE, (int16_t) I_GAIN_JOINT_TORQUE);
                 //spi_eeprom_write(RID_D_GAIN_JOINT_TORQUE, (int16_t) D_GAIN_JOINT_TORQUE);
@@ -723,7 +663,6 @@
             break;
         }
         case CRX_ASK_VALVE_MAX_MIN_POS: {
-            //CAN_TX_DDV_VALVE_DEADZONE();
             CAN_TX_DDV_VALVE_MAX_MIN_POS();
             break;
         }
@@ -789,44 +728,9 @@
 
         torq.ref = (double)temp_torq * 0.1f / TORQUE_SENSOR_PULSE_PER_TORQUE;   //N
         torq.ref_diff = torq.ref - torq.ref_old;
-        torq_dot.sen = torq.sen-totq_sen_past;
+        torq_dot.sen = torq.sen-torq_sen_past;
         torq.ref_old = torq.ref;
-        totq_sen_past = torq.sen;
-
-        ///////////////Make Data///////////////////
-        for(int i=0; i<num_array_u_past-1; i++) {
-            u_past[i] = u_past[i+1];
-        }
-        u_past[num_array_u_past-1] = output_normalized;
-
-        for(int i=0; i<num_array_x_past-1; i++) {
-            x_past[i] = x_past[i+1];
-        }
-        x_past[num_array_x_past-1] = pos.sen / ENC_PULSE_PER_POSITION;   //mm
-
-//        for(int i=0;i<num_array_x_future-1;i++){
-//            x_future[i] = x_future[i+1];
-//        }
-//        x_future[num_array_x_future-1] = pos.sen / ENC_PULSE_PER_POSITION;  //mm
-
-        for(int i=0; i<num_array_f_past-1; i++) {
-            f_past[i] = f_past[i+1];
-        }
-        f_past[num_array_f_past-1] = torq.sen;  //N
-
-        f_future[0] = torq.sen;  //N
-
-        if(flag_every_reference == 1) {
-            for(int i=1; i<num_array_f_future-1; i++) {
-                f_future[i] = 500.0f;
-            }
-            f_future[num_array_f_future-1] = 500.0f;  //N
-        } else {
-            for(int i=1; i<num_array_f_future-1; i++) {
-                f_future[i] = f_future[i+1];
-            }
-            f_future[num_array_f_future-1] = torq.ref;  //N
-        }
+        torq_sen_past = torq.sen;
 
 
     } else if(address==CID_RX_REF_VALVE_POS) {
@@ -1271,8 +1175,6 @@
     float temp_valve_deadzone_plus = 0.0f;
     float temp_ddv_center = 0.0f;
 
-    //temp_valve_deadzone_plus = 10000.0f*((double)VALVE_DEADZONE_PLUS-(double)VALVE_CENTER)/((double)VALVE_MAX_POS-(double)VALVE_CENTER);
-    //temp_valve_deadzone_minus = -10000.0f*((double)VALVE_DEADZONE_MINUS-(double)VALVE_CENTER)/((double)VALVE_MIN_POS-(double)VALVE_CENTER);
     temp_valve_deadzone_plus = (double)VALVE_DEADZONE_PLUS;
     temp_valve_deadzone_minus = (double)VALVE_DEADZONE_MINUS;
     temp_ddv_center = (double)VALVE_CENTER;
@@ -1356,7 +1258,6 @@
 {
     CANMessage temp_msg;
     int16_t valve_pos_vs_pwm;
-//    valve_pos_vs_pwm = (int16_t) (VALVE_POS_VS_PWM[canindex]);
 
     if(VALVE_POS_VS_PWM[canindex]>= (float) VALVE_CENTER) {
         valve_pos_vs_pwm = 10000.0f*((double)VALVE_POS_VS_PWM[canindex]-(double)VALVE_CENTER)/((double)VALVE_MAX_POS-(double)VALVE_CENTER);
@@ -1504,18 +1405,6 @@
     can.write(temp_msg);
 }
 
-//void CAN_TX_TORQUE(int16_t t_valve_pos, int16_t t_vout) {
-//    CANMessage temp_msg;
-//
-//    temp_msg.id = CID_TX_TORQUE;
-//    temp_msg.len = 4;
-//    temp_msg.data[0] = (uint8_t) t_valve_pos;
-//    temp_msg.data[1] = (uint8_t) (t_valve_pos >> 8);
-//    temp_msg.data[2] = (uint8_t) t_vout;
-//    temp_msg.data[3] = (uint8_t) (t_vout >> 8);
-//
-//    can.write(temp_msg);
-//}
 
 void CAN_TX_TORQUE(int16_t t_valve_pos)
 {
--- a/SPI_EEP_ENC/SPI_EEP_ENC.h	Mon Dec 28 12:10:50 2020 +0000
+++ b/SPI_EEP_ENC/SPI_EEP_ENC.h	Mon Dec 28 14:27:11 2020 +0000
@@ -21,8 +21,8 @@
  * ROM DATA ADDRESS ID
  ******************************************************************************/
 
-#define             RID_BNO                             0 
-#define             RID_OPERATING_MODE                  1 
+#define             RID_BNO                             0
+#define             RID_OPERATING_MODE                  1
 #define             RID_CAN_FREQ                        2
 #define             RID_JOINT_ENC_DIR                   3
 #define             RID_VALVE_DIR                       4
--- a/function_utilities/function_utilities.cpp	Mon Dec 28 12:10:50 2020 +0000
+++ b/function_utilities/function_utilities.cpp	Mon Dec 28 14:27:11 2020 +0000
@@ -5,9 +5,6 @@
 #include "stm32f4xx_flash.h"
 #include "FlashWriter.h"
 
-int Rom_Sector = 6;
-//FlashWriter writer(6);//2부터 7까지 되는듯 아마 sector
-
 /*******************************************************************************
  * VARIABLE
  ******************************************************************************/
@@ -249,7 +246,6 @@
 int one_period_end = 0;
 float Ref_Vel_Test = 0.0f;
 long TMR2_FOR_SLOW_LOGGING = 0;
-//int velcount = 0;
 char max_check = 0;
 char min_check = 0;
 
@@ -351,71 +347,10 @@
 float K_LPF = 0.0f;
 float D_LPF = 0.0f;
 
-float totq_sen_past = 0.0f;
+float torq_sen_past = 0.0f;
 float torq_ref_past = 0.0f;
 float output_normalized = 0.0f;
 
-int batch = 0;
-float train_set_x[batch_size] = {0.0f};
-float train_set_error[batch_size] = {0.0f};
-float train_set_count[batch_size] = {0.0f};
-float state_array[batch_size][num_input_RL] = {0.0f};
-float V[batch_size] = {0.0f};
-float r[batch_size] = {0.0f};
-float td_target[batch_size] = {0.0f};
-float delta[batch_size] = {0.0f};
-float advantage[batch_size] = {0.0f};
-float return_G[batch_size] = {0.0f};
-float mean = 0.0f;
-float deviation = 0.0f;
-float mean_old = 0.0f;
-float deviation_old = 0.0f;
-float mean_before_SP = 0.0f;
-float deviation_before_SP = 0.0f;
-float mean_before_SP_array[batch_size] = {0.0f};
-float deviation_before_SP_array[batch_size] = {0.0f};
-float mean_array[batch_size] = {0.0f};
-float mean_array_old[batch_size] = {0.0f};
-float deviation_array[batch_size] = {0.0f};
-float deviation_array_old[batch_size] = {0.0f};
-
-float hx_c_sum[num_hidden_unit1] = {0.0f};
-float hx_c_sum_array[batch_size][num_hidden_unit1] = {0.0f};
-float hxh_c_sum[num_hidden_unit2] = {0.0f};
-float hxh_c_sum_array[batch_size][num_hidden_unit2] = {0.0f};
-float hxhh_c_sum = 0.0f;
-float hxhh_c_sum_array[batch_size] = {0.0f};
-
-float hx_a_sum[num_hidden_unit1] = {0.0f};
-float hx_a_sum_array[batch_size][num_hidden_unit1] = {0.0f};
-float hxh_a_sum[num_hidden_unit2] = {0.0f};
-float hxh_a_sum_array[batch_size][num_hidden_unit2] = {0.0f};
-float hxhh_a_sum[2] = {0.0f};
-float hxhh_a_sum_array[batch_size][2] = {0.0f};
-
-float action = 0.0f;
-float action_array[batch_size] = {0.0f};
-float ratio[batch_size] = {1.0f};
-float pi[batch_size] = {0.0f};
-float pi_old[batch_size] = {0.0f};
-float epsilon = 0.2f;
-float surr1[batch_size] = {0.0f};
-float surr2[batch_size] = {0.0f};
-float loss[batch_size] = {0.0f};
-float loss_batch = 0.0f;
-float gamma = 0.996f;
-float lmbda = 0.95f;
-char Update_Done_Flag = 1;
-char Update_Case = 0;
-float reward_sum = 0.0f;
-
-float virt_pos = 0.0f;
-float logging1 = 0.0f;
-float logging2 = 0.0f;
-float logging3 = 0.0f;
-float logging4 = 0.0f;
-float logging5 = 0.0f;
-
 
 /*******************************************************************************
  * General math functions
@@ -460,87 +395,6 @@
 /*******************************************************************************
  * ROM functions
  ******************************************************************************/
-void ROM_RESET_DATA(void)
-{
-    FlashWriter writer(6);//2부터 7까지 되는듯 아마 sector
-    if (!writer.ready()) writer.open();
-    writer.write(RID_BNO,(int) BNO);           // write at address, 쓸때도 4byte씩 씀
-    writer.write(RID_OPERATING_MODE,(int) OPERATING_MODE);
-    writer.write(RID_SENSING_MODE, (int) SENSING_MODE);
-    writer.write(RID_CURRENT_CONTROL_MODE, (int) CURRENT_CONTROL_MODE);
-    writer.write(RID_FLAG_VALVE_DEADZONE, (int) FLAG_VALVE_DEADZONE);
-    writer.write(RID_CAN_FREQ,(int) CAN_FREQ);
-    writer.write(RID_JOINT_ENC_DIR,(int) DIR_JOINT_ENC);
-    writer.write(RID_VALVE_DIR,(int) DIR_VALVE);
-    writer.write(RID_VALVE_ENC_DIR,(int) DIR_VALVE_ENC);
-    writer.write(RID_VOLATGE_SUPPLY,(int) (SUPPLY_VOLTAGE * 10.0f));
-    writer.write(RID_VOLTAGE_VALVE,(int) (VALVE_VOLTAGE_LIMIT * 10.0f));
-    writer.write(RID_P_GAIN_VALVE_POSITION,(int) P_GAIN_VALVE_POSITION);
-    writer.write(RID_I_GAIN_VALVE_POSITION,(int) I_GAIN_VALVE_POSITION);
-    writer.write(RID_D_GAIN_VALVE_POSITION,(int) D_GAIN_VALVE_POSITION);
-    writer.write(RID_P_GAIN_JOINT_POSITION,(int) P_GAIN_JOINT_POSITION);
-    writer.write(RID_I_GAIN_JOINT_POSITION,(int) I_GAIN_JOINT_POSITION);
-    writer.write(RID_D_GAIN_JOINT_POSITION,(int) D_GAIN_JOINT_POSITION);
-    writer.write(RID_P_GAIN_JOINT_TORQUE,(int) P_GAIN_JOINT_TORQUE);
-    writer.write(RID_I_GAIN_JOINT_TORQUE,(int) I_GAIN_JOINT_TORQUE);
-    writer.write(RID_D_GAIN_JOINT_TORQUE,(int) D_GAIN_JOINT_TORQUE);
-    writer.write(RID_VALVE_DEADZONE_PLUS,(int) (VALVE_DEADZONE_PLUS * 10.0f));
-    writer.write(RID_VALVE_DEADZONE_MINUS,(int) (VALVE_DEADZONE_MINUS * 10.0f));
-    writer.write(RID_VELOCITY_COMP_GAIN,(int) VELOCITY_COMP_GAIN);
-    writer.write(RID_COMPLIANCE_GAIN,(int) COMPLIANCE_GAIN);
-    writer.write(RID_VALVE_CNETER,(int) VALVE_CENTER);
-    writer.write(RID_VALVE_FF,(int) VALVE_FF);
-    writer.write(RID_BULK_MODULUS,(int) BNO);
-    writer.write(RID_CHAMBER_VOLUME_A,(int) CHAMBER_VOLUME_A);
-    writer.write(RID_CHAMBER_VOLUME_B,(int) CHAMBER_VOLUME_B);
-    writer.write(RID_PISTON_AREA_A,(int) PISTON_AREA_A);
-    writer.write(RID_PISTON_AREA_B,(int) PISTON_AREA_B);
-    writer.write(RID_PRES_SUPPLY,(int) PRES_SUPPLY);
-    writer.write(RID_PRES_RETURN,(int) PRES_RETURN);
-    writer.write(RID_ENC_LIMIT_MINUS,(int) ENC_LIMIT_MINUS);
-    writer.write(RID_ENC_LIMIT_PLUS,(int) ENC_LIMIT_PLUS);
-    writer.write(RID_STROKE,(int) STROKE);
-    //writer.write(RID_VALVE_LIMIT_MINUS,(int) VALVE_LIMIT_MINUS);
-    //writer.write(RID_VALVE_LIMIT_PLUS,(int) VALVE_LIMIT_PLUS);
-    //writer.write(RID_ENC_PULSE_PER_POSITION,(int) (ENC_PULSE_PER_POSITION*10.0f));
-    writer.write(RID_ENC_PULSE_PER_POSITION,(int) (ENC_PULSE_PER_POSITION));
-    writer.write(RID_TORQUE_SENSOR_PULSE_PER_TORQUE,(int) (TORQUE_SENSOR_PULSE_PER_TORQUE * 10000.0f));
-    writer.write(RID_PRES_SENSOR_A_PULSE_PER_BAR,(int) (PRES_SENSOR_A_PULSE_PER_BAR * 100.0f));
-    writer.write(RID_PRES_SENSOR_B_PULSE_PER_BAR,(int) (PRES_SENSOR_B_PULSE_PER_BAR * 100.0f));
-    writer.write(RID_FRICTION,(int) (FRICTION * 10.0f));
-    writer.write(RID_HOMEPOS_OFFSET,(int) HOMEPOS_OFFSET);
-    writer.write(RID_HOMEPOS_VALVE_OPENING,(int) HOMEPOS_VALVE_OPENING);
-    writer.write(RID_TORQUE_SENSOR_VREF,(int) (TORQUE_VREF * 1000.0f));
-    writer.write(RID_PRES_A_SENSOR_VREF, (int) (PRES_A_VREF * 1000.0f));
-    writer.write(RID_PRES_B_SENSOR_VREF, (int) (PRES_B_VREF * 1000.0f));
-    writer.write(RID_VALVE_GAIN_PLUS_1,(int) (VALVE_GAIN_LPM_PER_V[0] * 100.0f));
-    writer.write(RID_VALVE_GAIN_PLUS_2,(int) (VALVE_GAIN_LPM_PER_V[2] * 100.0f));
-    writer.write(RID_VALVE_GAIN_PLUS_3,(int) (VALVE_GAIN_LPM_PER_V[4] * 100.0f));
-    writer.write(RID_VALVE_GAIN_PLUS_4,(int) (VALVE_GAIN_LPM_PER_V[6] * 100.0f));
-    writer.write(RID_VALVE_GAIN_PLUS_5,(int) (VALVE_GAIN_LPM_PER_V[8] * 100.0f));
-    writer.write(RID_VALVE_GAIN_MINUS_1,(int) (VALVE_GAIN_LPM_PER_V[1] * 100.0f));
-    writer.write(RID_VALVE_GAIN_MINUS_2,(int) (VALVE_GAIN_LPM_PER_V[3] * 100.0f));
-    writer.write(RID_VALVE_GAIN_MINUS_3,(int) (VALVE_GAIN_LPM_PER_V[5] * 100.0f));
-    writer.write(RID_VALVE_GAIN_MINUS_4,(int) (VALVE_GAIN_LPM_PER_V[7] * 100.0f));
-    writer.write(RID_VALVE_GAIN_MINUS_5,(int) (VALVE_GAIN_LPM_PER_V[9] * 100.0f));
-    for(int i=0; i<25; i++) {
-        writer.write(RID_VALVE_POS_VS_PWM_0 + i, (int) VALVE_POS_VS_PWM[i]);
-    }
-    for(int i=0; i<100; i++) {
-        writer.write(RID_VALVE_POS_VS_FLOWRATE_0 + i, (int) (JOINT_VEL[i] & 0xFFFF));
-        writer.write(RID_VALVE_POS_VS_FLOWRATE_0_1 + i, (int) ((JOINT_VEL[i] >> 16) & 0xFFFF));
-    }
-    writer.write(RID_VALVE_MAX_POS, (int) VALVE_MAX_POS);
-    writer.write(RID_VALVE_MIN_POS, (int) VALVE_MIN_POS);
-    //writer.write(RID_DDV_CENTER, (int) (DDV_CENTER * 10.0f));
-    writer.write(RID_VALVE_POS_NUM, (int) VALVE_POS_NUM);
-
-    writer.write(RID_K_SPRING, (int) K_SPRING);
-    writer.write(RID_D_DAMPER, (int) D_DAMPER);
-
-    writer.close();
-
-}
 
 void ROM_CALL_DATA(void)
 {
@@ -548,12 +402,9 @@
     BNO = 1;
     OPERATING_MODE = spi_eeprom_read(RID_OPERATING_MODE);
     SENSING_MODE = spi_eeprom_read(RID_SENSING_MODE);
-//    SENSING_MODE = 1;
     CURRENT_CONTROL_MODE = spi_eeprom_read(RID_CURRENT_CONTROL_MODE);
-//    CURRENT_CONTROL_MODE = 1;
     FLAG_VALVE_DEADZONE = spi_eeprom_read(RID_FLAG_VALVE_DEADZONE);
     CAN_FREQ = spi_eeprom_read(RID_CAN_FREQ);
-//    CAN_FREQ = 500;
     DIR_JOINT_ENC = spi_eeprom_read(RID_JOINT_ENC_DIR);
     DIR_VALVE = spi_eeprom_read(RID_VALVE_DIR);
     DIR_VALVE_ENC = spi_eeprom_read(RID_VALVE_ENC_DIR);
@@ -586,13 +437,8 @@
     ENC_LIMIT_MINUS = spi_eeprom_read(RID_ENC_LIMIT_MINUS);
     ENC_LIMIT_PLUS = spi_eeprom_read(RID_ENC_LIMIT_PLUS);
     STROKE = spi_eeprom_read(RID_STROKE);
-    //VALVE_LIMIT_MINUS = flashReadInt(Rom_Sector, RID_VALVE_LIMIT_MINUS);
-    //VALVE_LIMIT_PLUS = flashReadInt(Rom_Sector, RID_VALVE_LIMIT_PLUS);
-    //ENC_PULSE_PER_POSITION = (float) (spi_eeprom_read(RID_ENC_PULSE_PER_POSITION)) * 0.1f;
     ENC_PULSE_PER_POSITION = (float) (spi_eeprom_read(RID_ENC_PULSE_PER_POSITION));
     TORQUE_SENSOR_PULSE_PER_TORQUE = (float) (spi_eeprom_read(RID_TORQUE_SENSOR_PULSE_PER_TORQUE)) * 0.0001f;
-    //TORQUE_SENSOR_PULSE_PER_TORQUE = (float) 0.41928f; //for ankle
-//    TORQUE_SENSOR_PULSE_PER_TORQUE = (float) 10000.0f/2048.0f; //for knee
     PRES_SENSOR_A_PULSE_PER_BAR = (float) (spi_eeprom_read(RID_PRES_SENSOR_A_PULSE_PER_BAR)) * 0.01f;
 //    PRES_SENSOR_A_PULSE_PER_BAR = 4096.0f * 946.0f / 3.3f / 300.0f / 210.0f;
     PRES_SENSOR_B_PULSE_PER_BAR = (float) (spi_eeprom_read(RID_PRES_SENSOR_B_PULSE_PER_BAR)) * 0.01f;
@@ -621,109 +467,16 @@
     }
     VALVE_MAX_POS = spi_eeprom_read(RID_VALVE_MAX_POS);
     VALVE_MIN_POS = spi_eeprom_read(RID_VALVE_MIN_POS);
-    //DDV_CENTER = (float) (flashReadInt(Rom_Sector, RID_DDV_CENTER)) * 0.1f;
     VALVE_POS_NUM = spi_eeprom_read(RID_VALVE_POS_NUM);
 
-    K_SPRING = spi_eeprom_read(RID_K_SPRING);
-    D_DAMPER = spi_eeprom_read(RID_D_DAMPER);
-
-
-
-
-
-    /*
-
-    BNO = flashReadInt(Rom_Sector, RID_BNO);
-    //    BNO = 1;
-    OPERATING_MODE = flashReadInt(Rom_Sector, RID_OPERATING_MODE);
-    //    OPERATING_MODE = 5;
-    SENSING_MODE = flashReadInt(Rom_Sector, RID_SENSING_MODE);
-    //    SENSING_MODE = 0;
-    CURRENT_CONTROL_MODE = flashReadInt(Rom_Sector, RID_CURRENT_CONTROL_MODE);
-    //    CURRENT_CONTROL_MODE = 0;
-    FLAG_VALVE_DEADZONE = flashReadInt(Rom_Sector, RID_FLAG_VALVE_DEADZONE);
-    CAN_FREQ = flashReadInt(Rom_Sector, RID_CAN_FREQ);
-    DIR_JOINT_ENC = flashReadInt(Rom_Sector, RID_JOINT_ENC_DIR);
-    DIR_VALVE = flashReadInt(Rom_Sector, RID_VALVE_DIR);
-    DIR_VALVE_ENC = flashReadInt(Rom_Sector, RID_VALVE_ENC_DIR);
-    SUPPLY_VOLTAGE = (float) (flashReadInt(Rom_Sector, RID_VOLATGE_SUPPLY)) *0.1f;
-    VALVE_VOLTAGE_LIMIT = (float) (flashReadInt(Rom_Sector, RID_VOLTAGE_VALVE)) * 0.1f;
-    P_GAIN_VALVE_POSITION = flashReadInt(Rom_Sector, RID_P_GAIN_VALVE_POSITION);
-    I_GAIN_VALVE_POSITION = flashReadInt(Rom_Sector, RID_I_GAIN_VALVE_POSITION);
-    D_GAIN_VALVE_POSITION = flashReadInt(Rom_Sector, RID_D_GAIN_VALVE_POSITION);
-    P_GAIN_JOINT_POSITION = flashReadInt(Rom_Sector, RID_P_GAIN_JOINT_POSITION);
-    I_GAIN_JOINT_POSITION = flashReadInt(Rom_Sector, RID_I_GAIN_JOINT_POSITION);
-    D_GAIN_JOINT_POSITION = flashReadInt(Rom_Sector, RID_D_GAIN_JOINT_POSITION);
-    P_GAIN_JOINT_TORQUE = flashReadInt(Rom_Sector, RID_P_GAIN_JOINT_TORQUE);
-    I_GAIN_JOINT_TORQUE = flashReadInt(Rom_Sector, RID_I_GAIN_JOINT_TORQUE);
-    D_GAIN_JOINT_TORQUE = flashReadInt(Rom_Sector, RID_D_GAIN_JOINT_TORQUE);
-    VALVE_DEADZONE_PLUS = (float) (flashReadInt(Rom_Sector, RID_VALVE_DEADZONE_PLUS)) * 0.1f;
-    VALVE_DEADZONE_MINUS = (float) (flashReadInt(Rom_Sector, RID_VALVE_DEADZONE_MINUS)) * 0.1f;
-    VELOCITY_COMP_GAIN = flashReadInt(Rom_Sector, RID_VELOCITY_COMP_GAIN);
-    COMPLIANCE_GAIN = flashReadInt(Rom_Sector, RID_COMPLIANCE_GAIN);
-    VALVE_CENTER = flashReadInt(Rom_Sector, RID_VALVE_CNETER);
-    VALVE_FF = flashReadInt(Rom_Sector, RID_VALVE_FF);
-    BULK_MODULUS = flashReadInt(Rom_Sector, RID_BULK_MODULUS);
-    CHAMBER_VOLUME_A = flashReadInt(Rom_Sector, RID_CHAMBER_VOLUME_A);
-    CHAMBER_VOLUME_B = flashReadInt(Rom_Sector, RID_CHAMBER_VOLUME_B);
-    PISTON_AREA_A = flashReadInt(Rom_Sector, RID_PISTON_AREA_A);
-    PISTON_AREA_B = flashReadInt(Rom_Sector, RID_PISTON_AREA_B);
-    PISTON_AREA_alpha = (float)PISTON_AREA_A/(float)PISTON_AREA_B;
-    alpha3 = PISTON_AREA_alpha * PISTON_AREA_alpha*PISTON_AREA_alpha;
-    PRES_SUPPLY = flashReadInt(Rom_Sector, RID_PRES_SUPPLY);
-    PRES_RETURN = flashReadInt(Rom_Sector, RID_PRES_RETURN);
-    ENC_LIMIT_MINUS = flashReadInt(Rom_Sector, RID_ENC_LIMIT_MINUS);
-    ENC_LIMIT_PLUS = flashReadInt(Rom_Sector, RID_ENC_LIMIT_PLUS);
-    STROKE = flashReadInt(Rom_Sector, RID_STROKE);
-    //VALVE_LIMIT_MINUS = flashReadInt(Rom_Sector, RID_VALVE_LIMIT_MINUS);
-    //VALVE_LIMIT_PLUS = flashReadInt(Rom_Sector, RID_VALVE_LIMIT_PLUS);
-    ENC_PULSE_PER_POSITION = (float) (flashReadInt(Rom_Sector, RID_ENC_PULSE_PER_POSITION)) * 0.1f;
-    //    ENC_PULSE_PER_POSITION = (float) 1024.0f;
-    TORQUE_SENSOR_PULSE_PER_TORQUE = (float) (flashReadInt(Rom_Sector, RID_TORQUE_SENSOR_PULSE_PER_TORQUE)) * 0.0001f;
-    //TORQUE_SENSOR_PULSE_PER_TORQUE = (float) 0.41928f; //for ankle
-    //    TORQUE_SENSOR_PULSE_PER_TORQUE = (float) 10000.0f/2048.0f; //for knee
-    PRES_SENSOR_A_PULSE_PER_BAR = (float) (flashReadInt(Rom_Sector, RID_PRES_SENSOR_A_PULSE_PER_BAR)) * 0.01f;
-    //    PRES_SENSOR_A_PULSE_PER_BAR = 4096.0f / 200.0f;
-    PRES_SENSOR_B_PULSE_PER_BAR = (float) (flashReadInt(Rom_Sector, RID_PRES_SENSOR_B_PULSE_PER_BAR)) * 0.01f;
-    //    PRES_SENSOR_B_PULSE_PER_BAR = 4096.0f / 200.0f;
-    FRICTION = (float) (flashReadInt(Rom_Sector, RID_FRICTION)) * 0.1f;
-    HOMEPOS_OFFSET = flashReadInt(Rom_Sector, RID_HOMEPOS_OFFSET);
-    HOMEPOS_VALVE_OPENING = flashReadInt(Rom_Sector, RID_HOMEPOS_VALVE_OPENING);
-    TORQUE_VREF = (float) (flashReadInt(Rom_Sector, RID_TORQUE_SENSOR_VREF)) *0.001f;
-    PRES_A_VREF = (float) flashReadInt(Rom_Sector, RID_PRES_A_SENSOR_VREF) * 0.001f;
-    PRES_B_VREF = (float) flashReadInt(Rom_Sector, RID_PRES_B_SENSOR_VREF) * 0.001f;
-    VALVE_GAIN_LPM_PER_V[0] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_PLUS_1)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[2] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_PLUS_2)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[4] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_PLUS_3)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[6] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_PLUS_4)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[8] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_PLUS_5)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[1] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_MINUS_1)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[3] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_MINUS_2)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[5] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_MINUS_3)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[7] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_MINUS_4)) * 0.01f;
-    VALVE_GAIN_LPM_PER_V[9] = (float) (flashReadInt(Rom_Sector, RID_VALVE_GAIN_MINUS_5)) * 0.01f;
-    for(int i=0; i<25; i++) {
-        VALVE_POS_VS_PWM[i] = (float) (flashReadInt(Rom_Sector, RID_VALVE_POS_VS_PWM_0 + i));
-    }
-    for(int i=0; i<100; i++) {
-        JOINT_VEL[i] = ( ((flashReadInt(Rom_Sector, RID_VALVE_POS_VS_FLOWRATE_0 + i)) & 0xFFFF) | ((flashReadInt(Rom_Sector, RID_VALVE_POS_VS_FLOWRATE_0_1 + i)) & 0xFFFF) << 16 ) ;
-    }
-    VALVE_MAX_POS = flashReadInt(Rom_Sector, RID_VALVE_MAX_POS);
-    VALVE_MIN_POS = flashReadInt(Rom_Sector, RID_VALVE_MIN_POS);
-    //DDV_CENTER = (float) (flashReadInt(Rom_Sector, RID_DDV_CENTER)) * 0.1f;
-    VALVE_POS_NUM = flashReadInt(Rom_Sector, RID_VALVE_POS_NUM);
-
-    K_SPRING = flashReadInt(Rom_Sector, RID_K_SPRING);
-    D_DAMPER = flashReadInt(Rom_Sector, RID_D_DAMPER);
-
-    //    ROM_RESET_DATA();
-
-    */
+//    K_SPRING = spi_eeprom_read(RID_K_SPRING);
+//    D_DAMPER = spi_eeprom_read(RID_D_DAMPER);
 
 }
 
 /*******************************************************************************
  * ENCODER functions
+ 
  ******************************************************************************/
 // A-KHA
 #define     KF_G1_11    0.083920206005350f
@@ -751,17 +504,6 @@
     ENC_pos_cur = spi_enc_read();
     ENC_pos_diff = ENC_pos_cur - ENC_pos_old;
 
-    //Kalman Filter
-//    ENC_VEL_RAW = (int32_t) (ENC_pos_diff * TMR_FREQ_5k);
-//    KF_Y_11 = ENC_pos_cur;
-//    KF_Y_21 = ENC_VEL_RAW;
-//    KF_X_11 = KF_G1_11 * KF_X_11 + KF_G1_12 * KF_X_21 + KF_G2_11 * KF_Y_11 + KF_G2_12*KF_Y_21;
-//    KF_X_21 = KF_G1_21 * KF_X_11 + KF_G1_22 * KF_X_21 + KF_G2_21 * KF_Y_11 + KF_G2_22*KF_Y_21;
-//    ENC_VEL_KF = (int32_t) KF_X_21;
-//
-//    pos.sen = (DIR_JOINT_ENC) * ENC_pos_cur + enc_offset;
-//    vel.sen = (DIR_JOINT_ENC) * ENC_VEL_KF;
-
     //Low Pass Filter
 
     double NEW_POSITION = (double) ((DIR_JOINT_ENC) * ENC_pos_cur + enc_offset);
--- a/function_utilities/function_utilities.h	Mon Dec 28 12:10:50 2020 +0000
+++ b/function_utilities/function_utilities.h	Mon Dec 28 14:27:11 2020 +0000
@@ -24,7 +24,6 @@
 float   change_int_to_efloat(int input);
 void     make_delay(void);
 
-void     ROM_RESET_DATA(void);
 void     ROM_CALL_DATA(void);
 
 void     ENC_UPDATE(void);
--- a/main.cpp	Mon Dec 28 12:10:50 2020 +0000
+++ b/main.cpp	Mon Dec 28 14:27:11 2020 +0000
@@ -1,4 +1,13 @@
-//201228_2
+//Hydraulic Control Board
+//distributed by Sungwoo Kim
+//       2020/12/28
+
+
+// 유의사항
+// 소수 적을때 뒤에 f 꼭 붙이기
+// CAN 선은 ground까지 있는 3상 선으로 써야함.
+// 전원은 12~24V 인가.
+
 #include "mbed.h"
 #include "FastPWM.h"
 #include "INIT_HW.h"
@@ -16,8 +25,6 @@
 using namespace std;
 Timer t;
 
-///191008////
-
 // dac & check ///////////////////////////////////////////
 DigitalOut check(PC_2);
 DigitalOut check_2(PC_3);
@@ -27,20 +34,18 @@
 AnalogIn adc2(PB_0); //pressure_2
 AnalogIn adc3(PC_1); //current
 
-
 // PWM ///////////////////////////////////////////
 float dtc_v=0.0f;
 float dtc_w=0.0f;
 
 // I2C ///////////////////////////////////////////
 I2C i2c(PC_9,PA_8); // SDA, SCL (for K22F)
-const int i2c_slave_addr1 =  0x56;
+const int i2c_slave_addr1 =  0x56;  // AS5510 address
 unsigned int value; // 10bit output of reading sensor AS5510
 
 // SPI ///////////////////////////////////////////
 SPI eeprom(PB_15, PB_14, PB_13); // EEPROM //(SPI_MOSI, SPI_MISO, SPI_SCK);
 DigitalOut eeprom_cs(PB_12);
-//FlashWriter writer(6);//2부터 7까지 되는듯 아마 sector
 SPI enc(PC_12,PC_11,PC_10);
 DigitalOut enc_cs(PD_2);
 DigitalOut LED(PA_15);
@@ -85,22 +90,16 @@
 extern int CID_TX_VALVE_POSITION;
 
 
-
-
-// =============================================================================
-// =============================================================================
-// =============================================================================
-
 /*******************************************************************************
  *  REFERENCE MODE
  ******************************************************************************/
 enum _REFERENCE_MODE {
     MODE_REF_NO_ACT = 0,                                //0
-    MODE_REF_DIRECT,                                //1
-    MODE_REF_COS_INC,                                  //2
-    MODE_REF_LINE_INC,                                 //3
+    MODE_REF_DIRECT,                                    //1
+    MODE_REF_COS_INC,                                   //2
+    MODE_REF_LINE_INC,                                  //3
     MODE_REF_SIN_WAVE,                                  //4
-    MODE_REF_SQUARE_WAVE,                                  //5
+    MODE_REF_SQUARE_WAVE,                               //5
 };
 
 /*******************************************************************************
@@ -126,7 +125,7 @@
     MODE_CURRENT_CONTROL,                               //11
     MODE_JOINT_POSITION_TORQUE_CONTROL_CURRENT,         //12
     MODE_JOINT_POSITION_PRES_CONTROL_CURRENT,           //13
-    MODE_VALVE_POSITION_TORQUE_CONTROL_LEARNING,                                            //14
+    MODE_VALVE_POSITION_TORQUE_CONTROL_LEARNING,        //14
 
     //utility
     MODE_TORQUE_SENSOR_NULLING = 20,                    //20
@@ -137,7 +136,7 @@
     MODE_PRESSURE_SENSOR_CALIB,                         //25
     MODE_ROTARY_FRICTION_TUNING,                        //26
 
-    MODE_DDV_POS_VS_PWM_ID = 30,                           //30
+    MODE_DDV_POS_VS_PWM_ID = 30,                        //30
     MODE_DDV_DEADZONE_AND_CENTER,                       //31
     MODE_DDV_POS_VS_FLOWRATE,                           //32
     MODE_SYSTEM_ID,                                     //33
@@ -152,11 +151,11 @@
     RCC_OscInitTypeDef RCC_OscInitStruct = {0};
     RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
 
-    /** Configure the main internal regulator output voltage
+    /* Configure the main internal regulator output voltage
     */
     __HAL_RCC_PWR_CLK_ENABLE();
     __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
-    /** Initializes the CPU, AHB and APB busses clocks
+    /* Initializes the CPU, AHB and APB busses clocks
     */
     RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
     RCC_OscInitStruct.HSIState = RCC_HSI_ON;
@@ -190,687 +189,16 @@
     }
 }
 
-float u_past[num_array_u_past] = {0.0f};
-float x_past[num_array_x_past] = {0.0f};
-float x_future[num_array_x_future] = {0.0f};
-float f_past[num_array_f_past] = {0.0f};
-float f_future[num_array_f_future] = {0.0f};
-
-float input_NN[num_input] = { 0.0f };
-
-const float h1[num_input][16] = {
-    {-1.6017948389053345f,1.2721383571624756f,0.1310378611087799f,-0.9444252848625183f,-1.9589552879333496f,1.1329879760742188f,-0.17743819952011108f,-0.19157131016254425f,-0.39761483669281006f,0.02001183293759823f,0.5025057196617126f,-2.509382724761963f,-0.2675858736038208f,0.27560269832611084f,-0.2611466646194458f,-0.9627107977867126f},
-{-1.2710213661193848f,0.9135757684707642f,-0.3988758325576782f,-0.7979171872138977f,-1.4895585775375366f,0.5568610429763794f,-0.4116867780685425f,-0.261433482170105f,-0.22742684185504913f,0.2772603929042816f,0.118864506483078f,-1.5505203008651733f,0.23985113203525543f,-0.2809593081474304f,-0.21292872726917267f,-0.6193060874938965f},
-{-1.1586071252822876f,0.7516070604324341f,0.36955419182777405f,-0.9032031297683716f,-0.9722328782081604f,0.5363096594810486f,0.2916664779186249f,-0.016872992739081383f,-0.34971633553504944f,0.2836141288280487f,-0.054457396268844604f,-0.9038598537445068f,-0.0020234500989317894f,0.19621078670024872f,0.056768983602523804f,-1.1061573028564453f},
-{-0.7506084442138672f,0.1879994422197342f,0.40358296036720276f,0.12524257600307465f,-0.5177642107009888f,-0.18764258921146393f,-0.11764177680015564f,0.31180232763290405f,-0.20574431121349335f,0.42218565940856934f,0.16467393934726715f,0.3004089593887329f,-0.1665881872177124f,0.09486014395952225f,-0.3007376194000244f,-0.8816207051277161f},
-{0.7436127662658691f,-0.604726254940033f,-0.005224883556365967f,0.9320474863052368f,0.5615028142929077f,-0.8275365829467773f,0.13140985369682312f,0.018719080835580826f,-0.24859893321990967f,0.23700864613056183f,-0.41653650999069214f,1.252004861831665f,-0.0686110407114029f,0.23053120076656342f,-0.39249828457832336f,-0.6377205848693848f},
-{3.0718040466308594f,-3.262662887573242f,0.22110894322395325f,2.670456647872925f,2.9312491416931152f,-3.062858819961548f,0.16770240664482117f,-0.1752457618713379f,-0.304975301027298f,0.24974356591701508f,-2.912475347518921f,3.297006845474243f,-0.2682695984840393f,0.3757273256778717f,-0.4196912348270416f,1.0734145641326904f},
-{-1.2198433876037598f,1.5182578563690186f,-0.2540779709815979f,-1.8283756971359253f,-1.570626139640808f,1.7989088296890259f,0.06107431650161743f,-0.7636352777481079f,0.3089294731616974f,-0.09506343305110931f,2.775860548019409f,0.7932590246200562f,-0.17504744231700897f,0.2239564061164856f,-0.15860587358474731f,-0.7237789630889893f},
-{0.7539365291595459f,-0.9152541160583496f,-0.2703247666358948f,0.3871593773365021f,0.3573713004589081f,-0.712091326713562f,-0.18203827738761902f,-0.5724472999572754f,-0.17589353024959564f,-0.025821663439273834f,0.3012785017490387f,0.5540553331375122f,0.3776646554470062f,0.029355080798268318f,0.0436977744102478f,1.1350784301757812f},
-{0.6773941516876221f,-0.1407381296157837f,0.10406997799873352f,-0.31886449456214905f,0.2701631486415863f,-0.2895267903804779f,-0.07359349727630615f,-0.522844135761261f,-0.4761183261871338f,0.22720466554164886f,-0.11068277060985565f,0.17022143304347992f,0.23315370082855225f,0.15179778635501862f,-0.31029027700424194f,0.851940393447876f},
-{0.11661386489868164f,-0.3948979079723358f,0.18748918175697327f,-0.2878238558769226f,0.28554558753967285f,0.11674453318119049f,-0.3036908507347107f,-0.1508290320634842f,-0.14107836782932281f,-0.5925581455230713f,0.2786004841327667f,-1.0318316221237183f,0.37844526767730713f,-0.270053893327713f,0.35390153527259827f,0.38183316588401794f},
-{0.4711846709251404f,0.11557799577713013f,0.3775894343852997f,0.0314268134534359f,0.03386480361223221f,0.016547810286283493f,-0.20654654502868652f,-0.06258935481309891f,-0.4769713580608368f,-0.07612045109272003f,0.6390635967254639f,-0.8360038995742798f,-0.06711658090353012f,-0.030321964994072914f,0.2710213363170624f,-0.054686423391103745f},
-{-0.37094420194625854f,-0.2944038212299347f,-0.40945154428482056f,-0.18097494542598724f,0.14135384559631348f,0.021318335086107254f,0.15575703978538513f,0.29287639260292053f,-0.12214788794517517f,0.1086469367146492f,-0.14901117980480194f,-0.15198558568954468f,0.1470927745103836f,-0.03396562486886978f,0.10656675696372986f,0.06443876773118973f},
-{0.025174643844366074f,-0.12816596031188965f,0.2015570104122162f,0.1076304167509079f,0.45414742827415466f,0.19509439170360565f,-0.24415965378284454f,0.013022400438785553f,-0.10836649686098099f,-0.29661229252815247f,0.09127697348594666f,-0.21214918792247772f,0.09341105818748474f,0.01174785103648901f,-0.22613362967967987f,-0.3625008761882782f},
-{-0.04146391525864601f,-0.02673570066690445f,0.41918185353279114f,-0.1233106479048729f,-0.07927072793245316f,-0.1876136064529419f,-0.32497477531433105f,-0.4840133786201477f,-0.044291287660598755f,-0.3259299099445343f,0.04178468510508537f,-0.0003480979357846081f,-0.31783685088157654f,-0.05072624981403351f,0.04871204495429993f,-0.08137178421020508f},
-{0.1422140747308731f,0.18844546377658844f,0.20596781373023987f,-0.2328251153230667f,0.34344229102134705f,0.06260570883750916f,0.042680561542510986f,0.07508613914251328f,0.4000869691371918f,-0.010638000443577766f,0.13212932646274567f,-0.657844066619873f,0.10472581535577774f,-0.038563571870326996f,0.06784489750862122f,-0.2556094229221344f},
-{0.15386898815631866f,-0.49337783455848694f,-0.4106670916080475f,-0.4150790572166443f,-0.05264211446046829f,-0.05708514153957367f,-0.15809619426727295f,-0.20627009868621826f,0.27094385027885437f,-0.09812130033969879f,-0.3514001667499542f,-0.9586353898048401f,-0.275861918926239f,0.02052518166601658f,-0.08373728394508362f,-0.0018482634332031012f},
-};
-
-const float h2[16][16] = {
-    {-0.9739745259284973f,3.579744815826416f,-0.06966331601142883f,0.8622938990592957f,-0.21907491981983185f,2.2829554080963135f,-0.13155855238437653f,-0.014519207179546356f,-0.43008196353912354f,-0.1415480375289917f,0.17231711745262146f,-4.9480390548706055f,-0.02454538829624653f,-1.7999197244644165f,-0.38519009947776794f,1.4918317794799805f},
-{0.03609159216284752f,-0.6491178274154663f,0.057057321071624756f,-0.5475255846977234f,-0.35503754019737244f,-3.0916311740875244f,-0.5200656652450562f,-0.42126399278640747f,-0.33757925033569336f,0.2895788848400116f,-0.4909915030002594f,-1.1257127523422241f,0.18442146480083466f,1.348382830619812f,-0.5171104669570923f,-2.655162811279297f},
-{-0.22745239734649658f,0.003037691116333008f,-0.061119019985198975f,0.35696902871131897f,0.05568113923072815f,0.011741191148757935f,-0.20225946605205536f,-0.08465918898582458f,0.3489862382411957f,0.0687277615070343f,0.31964078545570374f,0.3004753887653351f,0.36063823103904724f,-0.42892736196517944f,0.08652284741401672f,0.027493387460708618f},
-{0.15409719944000244f,0.4271918833255768f,-0.2894435524940491f,0.4524352252483368f,0.08946844935417175f,-0.24254196882247925f,-0.5646932125091553f,0.2643083930015564f,0.26211628317832947f,0.2953031361103058f,0.0909804254770279f,0.8597109913825989f,-0.5144365429878235f,-2.37484073638916f,-0.026095986366271973f,0.29753774404525757f},
-{-0.7763098478317261f,2.959994316101074f,-0.25313520431518555f,0.5777999758720398f,0.036378175020217896f,0.7788732051849365f,-0.5079860091209412f,-0.20636579394340515f,-0.024399548768997192f,-0.39465832710266113f,-0.4901541471481323f,-3.3827083110809326f,-0.013386494480073452f,-1.876047134399414f,-0.6391417384147644f,0.6140359044075012f},
-{0.020159810781478882f,0.545926034450531f,-0.3519742488861084f,-0.17923703789710999f,-0.3015052080154419f,-1.5342668294906616f,-0.7026005387306213f,-0.12369749695062637f,-0.23047015070915222f,0.3579089343547821f,-0.2382185161113739f,-5.193862438201904f,-0.3443910777568817f,1.945488691329956f,0.014947117306292057f,-1.2414220571517944f},
-{-0.1828227937221527f,-0.02554568648338318f,-0.3260969817638397f,0.08422836661338806f,-0.38453540205955505f,-0.25432005524635315f,0.285016268491745f,0.12387624382972717f,-0.0982072651386261f,0.13111665844917297f,-0.03692615032196045f,-0.32796353101730347f,-0.21546880900859833f,0.049302369356155396f,-0.27088475227355957f,-0.4124959409236908f},
-{0.3839884400367737f,0.6259503960609436f,0.33083590865135193f,0.04438639059662819f,-0.14358049631118774f,0.12416914105415344f,-0.09043094515800476f,-0.3003333508968353f,0.2600560486316681f,-0.37898191809654236f,0.4972154498100281f,-0.2750113010406494f,-0.31673234701156616f,-0.015966646373271942f,-0.08780939131975174f,0.328056275844574f},
-{-0.4527643918991089f,0.3202667832374573f,-0.11379697918891907f,0.0684560090303421f,0.041274964809417725f,-0.40635451674461365f,-0.2745489478111267f,0.031847670674324036f,0.06103590130805969f,-0.38046833872795105f,-0.45007404685020447f,-0.5276026725769043f,-0.37024784088134766f,-0.3135625123977661f,-0.3714982867240906f,-0.12828999757766724f},
-{0.2802984118461609f,0.5001301765441895f,-0.13502129912376404f,0.6260269284248352f,0.12987366318702698f,0.6041213870048523f,0.2711336314678192f,-0.3632148504257202f,-0.13619378209114075f,0.16938945651054382f,0.5018476247787476f,0.3686026930809021f,0.3811538517475128f,-0.5396527647972107f,-0.19131632149219513f,0.09156869351863861f},
-{-1.5928384065628052f,0.23942683637142181f,0.0457797646522522f,-0.6350169777870178f,-0.03321319818496704f,0.08973085880279541f,-0.18186365067958832f,-0.3142535090446472f,-0.050184011459350586f,0.12480869889259338f,-0.5123732089996338f,-4.090933799743652f,-0.4121001660823822f,1.199095368385315f,-0.18886037170886993f,-0.7048641443252563f},
-{0.03677457198500633f,0.4954114556312561f,0.3954955041408539f,0.2689988911151886f,0.0033026933670043945f,1.278443694114685f,-0.4117635190486908f,-0.24394789338111877f,0.3487861454486847f,-0.32520344853401184f,0.14627091586589813f,-0.9104770421981812f,-0.07545550167560577f,-1.3930959701538086f,0.008092201314866543f,-1.8283593654632568f},
-{-0.31720414757728577f,-0.21001535654067993f,-0.15798500180244446f,0.3665239214897156f,-0.37393757700920105f,0.37094148993492126f,0.11292675137519836f,-0.2947862446308136f,-0.3764709532260895f,0.2424570620059967f,-0.1080506220459938f,-0.2837170362472534f,0.41839322447776794f,-0.01957082748413086f,-0.12957632541656494f,0.10856001079082489f},
-{0.03818705305457115f,0.27717405557632446f,-0.2018718123435974f,0.06585641950368881f,0.07545611262321472f,0.05265878140926361f,-0.11297860741615295f,-0.21416273713111877f,-0.24509364366531372f,0.19522181153297424f,0.351835161447525f,-0.2859584093093872f,-0.16718891263008118f,0.23180222511291504f,-0.23956191539764404f,-0.07242263853549957f},
-{0.4138670265674591f,0.1604653298854828f,0.056746453046798706f,0.036025404930114746f,0.3228367865085602f,-0.07083973288536072f,0.018455177545547485f,0.0059362053871154785f,0.40515169501304626f,0.014240056276321411f,-0.07738298177719116f,0.1407785713672638f,-0.13024571537971497f,-0.29546058177948f,-0.11976784467697144f,-0.35825538635253906f},
-{-1.0752074718475342f,-2.8200089931488037f,0.12081471085548401f,-0.12609876692295074f,0.29976895451545715f,0.4510769844055176f,-0.2826606035232544f,0.18327592313289642f,-0.3893685042858124f,-0.02222958207130432f,-0.19482164084911346f,-0.37641236186027527f,-0.19991017878055573f,-1.0054714679718018f,0.06622982025146484f,1.2732210159301758f},
-};
-
-const float h3[16][16] = {
-    {-0.36079341173171997f,0.5496202707290649f,-0.6524567604064941f,-1.0138130187988281f,-0.7639057636260986f,0.5781964063644409f,0.3332441747188568f,0.3036012351512909f,-0.2405819296836853f,0.04891335964202881f,-0.11870327591896057f,0.4001283347606659f,-0.533208429813385f,0.9845144152641296f,0.32505926489830017f,-0.19595709443092346f},
-{0.047732532024383545f,0.017954785376787186f,-0.18629395961761475f,-0.9162130951881409f,-0.43290695548057556f,-4.281400680541992f,-0.3198729455471039f,0.06247803568840027f,-0.19349214434623718f,-0.9508686065673828f,0.2572092115879059f,-0.41319137811660767f,-0.35956844687461853f,-0.5297766327857971f,0.10103966295719147f,-0.7109990119934082f},
-{0.07903262972831726f,0.2790505588054657f,-0.07798504829406738f,0.04248586297035217f,-0.1963958442211151f,-0.19260792434215546f,-0.4038352966308594f,0.015906542539596558f,0.15353140234947205f,0.030178606510162354f,0.2488909661769867f,0.13805970549583435f,-0.0816211998462677f,-0.20733052492141724f,-0.3036302626132965f,0.054825395345687866f},
-{-0.30922991037368774f,-0.05632366985082626f,-1.3186177015304565f,-0.9530683755874634f,-0.49597063660621643f,0.2564902603626251f,0.20021501183509827f,0.07002416253089905f,-0.4060443043708801f,-0.4593014717102051f,0.13192829489707947f,0.41021624207496643f,-0.2266009896993637f,0.25329798460006714f,0.28113701939582825f,-0.15740571916103363f},
-{-0.39607733488082886f,-0.05481579899787903f,0.1976260244846344f,0.022423356771469116f,0.16892847418785095f,-0.27518749237060547f,0.16012099385261536f,0.3626593053340912f,-0.08640444278717041f,-0.11053556203842163f,-0.10529157519340515f,-0.31317979097366333f,-0.1530032455921173f,-0.1336749792098999f,0.22959044575691223f,0.19986507296562195f},
-{-0.37449589371681213f,-0.02029903419315815f,-2.5072414875030518f,-12.973404884338379f,0.2337467223405838f,1.0865919589996338f,-0.18732719123363495f,0.22384825348854065f,-0.850281298160553f,-0.4489060342311859f,-0.23735009133815765f,0.05998014658689499f,0.23774290084838867f,0.08863037824630737f,0.5211813449859619f,-1.1956897974014282f},
-{0.4110594093799591f,0.2715781033039093f,-0.12724249064922333f,0.37246426939964294f,-0.06906148046255112f,-0.05251416191458702f,-0.08670487999916077f,-0.25336313247680664f,-0.030661463737487793f,-0.06259563565254211f,-0.1344406008720398f,0.35313835740089417f,0.13369451463222504f,0.2011522799730301f,0.3126353323459625f,-0.3391006588935852f},
-{-0.40892091393470764f,0.04420051723718643f,-0.26215535402297974f,0.25968697667121887f,0.4493691027164459f,-0.16038022935390472f,-0.23312048614025116f,-0.390264093875885f,0.28059282898902893f,-0.1559126079082489f,-0.14134526252746582f,-0.0003446042537689209f,-0.17052586376667023f,-0.4737553000450134f,0.08030081540346146f,0.005298197269439697f},
-{0.10697010159492493f,-0.12228584289550781f,-0.37870171666145325f,0.21184906363487244f,-0.37222859263420105f,-0.17138728499412537f,-0.1382003128528595f,0.3493293821811676f,-0.360889196395874f,-0.3875247836112976f,0.42142823338508606f,-0.3482915461063385f,-0.3289247751235962f,-0.2186824083328247f,0.09620395302772522f,-0.06898030638694763f},
-{0.2847062647342682f,0.018552124500274658f,0.11435768008232117f,0.36562982201576233f,-0.047046810388565063f,0.30447837710380554f,0.2430230677127838f,0.2909286320209503f,-0.2802048921585083f,0.18043199181556702f,0.41849127411842346f,-0.287167489528656f,0.24394884705543518f,-0.14084559679031372f,-0.10168051719665527f,0.010465055704116821f},
-{0.15459725260734558f,0.3123319149017334f,0.10377500206232071f,-0.044353384524583817f,-0.2320195883512497f,0.12762269377708435f,-0.08742031455039978f,0.05785742402076721f,-0.07219423353672028f,-0.2943510413169861f,0.1268840730190277f,-0.30447322130203247f,-0.044554103165864944f,-0.20284022390842438f,0.5049844980239868f,0.23406195640563965f},
-{-0.408692330121994f,0.7442746162414551f,-0.3166918158531189f,-0.5923694968223572f,-2.5536251068115234f,2.459355354309082f,0.03285527229309082f,0.38763079047203064f,-0.20705322921276093f,-0.25883403420448303f,0.12809070944786072f,0.03996849060058594f,1.5557342767715454f,2.810499429702759f,0.883807361125946f,-0.5292647480964661f},
-{-0.2991822361946106f,0.3794580399990082f,-0.07897943258285522f,-0.05932474136352539f,-0.019097916781902313f,0.10188531875610352f,-0.11253207921981812f,0.34576353430747986f,0.04814547300338745f,-0.35770976543426514f,-0.044228196144104004f,-0.36229726672172546f,0.015840977430343628f,-0.13475483655929565f,0.36124154925346375f,-0.16869547963142395f},
-{-0.2675279378890991f,-0.4076881408691406f,0.6109089851379395f,1.124742865562439f,0.791110098361969f,-1.8034776449203491f,-0.32875844836235046f,-0.31893211603164673f,-0.6889935731887817f,-1.1343306303024292f,-0.5256567001342773f,-0.8404866456985474f,1.0291988849639893f,-1.3514559268951416f,0.12213380634784698f,0.17103822529315948f},
-{-0.015470266342163086f,-0.23503242433071136f,0.13451209664344788f,0.36471807956695557f,-0.08753460645675659f,-0.20316985249519348f,0.05196094512939453f,-0.008358269929885864f,-0.4239840805530548f,-0.38441595435142517f,0.13179203867912292f,-0.11511552333831787f,0.07671336829662323f,0.1646096110343933f,0.19001242518424988f,-0.29890790581703186f},
-{0.1863725483417511f,-0.07918193191289902f,-0.8252384066581726f,-36.685184478759766f,1.862860083580017f,1.8086168766021729f,0.04860696196556091f,0.17769548296928406f,-0.32842522859573364f,-0.40967434644699097f,-0.3929237127304077f,-0.0008496989612467587f,2.3736817836761475f,1.629492998123169f,-0.45149895548820496f,-0.32196617126464844f},
-};
-
-const float hout[16] = { 0.45773375034332275f,0.3443804383277893f,-0.43964359164237976f,-0.21056394279003143f,0.19662600755691528f,0.7040731906890869f,0.0030125975608825684f,0.15066689252853394f,0.10095822811126709f,-0.13003124296665192f,0.18801097571849823f,0.0785079076886177f,-0.15748845040798187f,0.1868625432252884f,0.18598346412181854f,-0.9022102355957031f };
-
-const float b1[16] = { 0.7107149362564087f,1.0883506536483765f,-1.7145336866378784f,0.09724511206150055f,1.4542453289031982f,1.417521595954895f,-0.058932315558195114f,0.9398505687713623f,0.4389953017234802f,-0.9609658718109131f,0.8672975301742554f,1.5156910419464111f,-0.3718140721321106f,-0.886523962020874f,-1.087764859199524f,2.5278995037078857f };
-
-const float b2[16] = { -0.4577406942844391f,-0.4344789981842041f,-1.4564176797866821f,-0.6435210704803467f,-0.6939148902893066f,-0.16397996246814728f,-0.013260572217404842f,-0.43840786814689636f,-1.20063054561615f,-1.912178635597229f,-0.1346415877342224f,0.10342646390199661f,-0.23722384870052338f,0.9154923558235168f,-0.1802087128162384f,1.0650097131729126f };
-
-const float b3[16] = { -1.963319182395935f,-0.7180035710334778f,0.7040019035339355f,-0.4437018930912018f,-0.7515134811401367f,1.0377838611602783f,-0.45353031158447266f,-0.6562485098838806f,0.04508165270090103f,0.06766403466463089f,-0.29913392663002014f,-0.09212813526391983f,-1.5836485624313354f,0.42195138335227966f,-1.3884198665618896f,-0.511356770992279f };
-
-const float bout[1] = { 0.09115694463253021f };
-
-/////////////////////////////////////////////////////////////////////////////////////////////RL
-float input_RL[num_input_RL] = { 0.0f };
-
-//Critic Networks
-float hc1[num_input_RL][num_hidden_unit1] = {0.0f};
-float bc1[num_hidden_unit1] = {0.0f};
-float hc2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
-float bc2[num_hidden_unit2] = {0.0f};
-float hc3[num_hidden_unit2] = {0.0f};
-float bc3 = 0.0f;
-
-//Critic Networks Temporary
-float hc1_temp[num_input_RL][num_hidden_unit1] = {0.0f};
-float bc1_temp[num_hidden_unit1] = {0.0f};
-float hc2_temp[num_hidden_unit1][num_hidden_unit2] = {0.0f};
-float bc2_temp[num_hidden_unit2] = {0.0f};
-float hc3_temp[num_hidden_unit2] = {0.0f};
-float bc3_temp = 0.0f;
-
-//Actor Networks
-float ha1[num_input_RL][num_hidden_unit1] = {0.0f};
-float ba1[num_hidden_unit1] = {0.0f};
-float ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
-float ba2[num_hidden_unit2] = {0.0f};
-float ha3[num_hidden_unit2][2] = {0.0f};
-float ba3[2] = {0.0f};
-
-//Actor Networks Temporary
-float ha1_temp[num_input_RL][num_hidden_unit1] = {0.0f};
-float ba1_temp[num_hidden_unit1] = {0.0f};
-float ha2_temp[num_hidden_unit1][num_hidden_unit2] = {0.0f};
-float ba2_temp[num_hidden_unit2] = {0.0f};
-float ha3_temp[num_hidden_unit2][2] = {0.0f};
-float ba3_temp[2] = {0.0f};
-
-float VALVE_POS_RAW_NN = 0.0f;
-float DDV_JOINT_POS_FF(float REF_JOINT_VEL);
-
-/////////////////////////////////////////////RL tuning
-float Gradient_Limit = 0.5f;
-float gradient_rate_actor = 0.001f;
-float gradient_rate_critic = 0.001f;
-//////////////////////////////////////////////////////////////////////////////
-
-float Critic_Network_Temp(float *arr)
-{
-    float output1[num_hidden_unit1] = { 0.0f };
-    float output2[num_hidden_unit2] = { 0.0f };
-    float output = 0.0f;
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            output1[index2] = output1[index2] + hc1_temp[index1][index2] * arr[index1];
-        }
-        //ReLU
-        output1[index2] = output1[index2] + bc1_temp[index2];
-        hx_c_sum[index2] = output1[index2];
-        if (output1[index2] < 0) {
-            output1[index2] = 0;
-        }
-        //tanh
-        //output1[index2] = tanh(output1[index2] + bc1_temp[index2]);
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            output2[index2] = output2[index2] + hc2_temp[index1][index2] * output1[index1];
-        }
-        //ReLU
-        output2[index2] = output2[index2] + bc2_temp[index2];
-        hxh_c_sum[index2] = output2[index2];
-        if (output2[index2] < 0) {
-            output2[index2] = 0;
-        }
-        //tanh
-        //output2[index2] = tanh(output2[index2] + bc2_temp[index2]);
-    }
-    for (int index2 = 0; index2 < 1; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            output = output + hc3_temp[index1] * output2[index1];
-        }
-        output = output + bc3_temp;
-        hxhh_c_sum = output;
-    }
-    return output;
-}
-
-
-void Actor_Network(float *arr)
-{
-    float output1[num_hidden_unit1] = {0.0f};
-    float output2[num_hidden_unit2] = {0.0f};
-    float output[2] = {0.0f};
-
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            output1[index2] = output1[index2] + ha1_temp[index1][index2] * arr[index1];
-        }
-        output1[index2] = output1[index2] + ba1_temp[index2];
-        hx_a_sum[index2] = output1[index2];
-        if (output1[index2] < 0) {
-            output1[index2] = 0;
-        }
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            output2[index2] = output2[index2] + ha2_temp[index1][index2] * output1[index1];
-        }
-        output2[index2] = output2[index2] + ba2_temp[index2];
-        hxh_a_sum[index2] = output2[index2];
-        if (output2[index2] < 0) {
-            output2[index2] = 0;
-        }
-    }
-    for (int index2 = 0; index2 < 2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            output[index2] = output[index2] + ha3_temp[index1][index2] * output2[index1];
-        }
-        hxhh_a_sum[index2] = output[index2] + ba3_temp[index2];
-    }
-
-    mean_before_SP = output[0] + ba3_temp[0];    //SP = softplus
-    deviation_before_SP = output[1] + ba3_temp[1];
-    //Softplus
-    mean = log(1.0f+exp(mean_before_SP));
-    deviation = log(1.0f+exp(deviation_before_SP));
-    logging2 = mean;
-    logging4 = deviation;
-}
-
-
-void Actor_Network_Old(float *arr)
-{
-    float output1[num_hidden_unit1] = {0.0f};
-    float output2[num_hidden_unit2] = {0.0f};
-    float output[2] = {0.0f};
-
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            output1[index2] = output1[index2] + ha1[index1][index2] * arr[index1];
-        }
-        output1[index2] = output1[index2] + ba1[index2];
-        if (output1[index2] < 0) {
-            output1[index2] = 0;
-        }
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            output2[index2] = output2[index2] + ha2[index1][index2] * output1[index1];
-        }
-        output2[index2] = output2[index2] + ba2[index2];
-        if (output2[index2] < 0) {
-            output2[index2] = 0;
-        }
-    }
-    for (int index2 = 0; index2 < 2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            output[index2] = output[index2] + ha3[index1][index2] * output2[index1];
-        }
-    }
-    mean_old = output[0] + ba3[0];
-    deviation_old = output[1] + ba3[1];
-    //Softplus
-    mean_old = log(1.0f+exp(mean_old));
-    deviation_old = log(1.0f+exp(deviation_old));
-}
-
-float Grad_Normal_Dist_Mean(float mean, float deviation, float action)
-{
-    float grad_mean = 0.0f;
-    grad_mean = (action-mean)*exp(-(action-mean)*(action-mean)/(2.0f*deviation*deviation))/(sqrt(2.0f*PI)*deviation*deviation*deviation);
-    return grad_mean;
-}
-
-float Grad_Normal_Dist_Deviation(float mean, float deviation, float action)
-{
-    float grad_dev = 0.0f;
-    grad_dev = exp(-(action-mean)*(action-mean)/(2.0f*deviation*deviation))*(-1.0f/(sqrt(2.0f*PI)*deviation*deviation) + (action-mean)*(action-mean)/(sqrt(2.0f*PI)*deviation*deviation*deviation*deviation));
-    return grad_dev;
-}
-
-float ReLU(float x)
-{
-    if (x >= 0) {
-        return x;
-    } else {
-        return 0.0f;
-    }
-}
-
-void update_Critic_Networks(float (*arr)[num_input_RL])
-{
-    float G_hc1[num_input_RL][num_hidden_unit1] = {0.0f};
-    float G_bc1[num_hidden_unit1] = {0.0f};
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            for (int n=0; n<batch_size; n++) {
-                float d_V_d_hc1 = 0.0f;
-                for(int k=0; k<num_hidden_unit2; k++) {
-                    if (hxh_c_sum_array[n][k] >= 0) {
-                        if (hx_c_sum_array[n][index2] > 0) {
-                            d_V_d_hc1 = d_V_d_hc1 + arr[n][index1]*hc2_temp[index2][k]*hc3_temp[k];
-                        }
-                    }
-                }
-                G_hc1[index1][index2] = G_hc1[index1][index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc1);
-            }
-            G_hc1[index1][index2] = G_hc1[index1][index2] / batch_size;
-            if(G_hc1[index1][index2] > Gradient_Limit) G_hc1[index1][index2] = Gradient_Limit;
-            else if (G_hc1[index1][index2] < -Gradient_Limit) G_hc1[index1][index2] = -Gradient_Limit;
-            //hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate_critic * G_hc1[index1][index2];
-        }
-        for (int n=0; n<batch_size; n++) {
-            float d_V_d_bc1 = 0.0f;
-            for(int k=0; k<num_hidden_unit2; k++) {
-                if (hxh_c_sum_array[n][k] >= 0) {
-                    if (hx_c_sum_array[n][index2] > 0) {
-                        d_V_d_bc1 = d_V_d_bc1 + hc2_temp[index2][k]*hc3_temp[k];
-                    }
-                }
-            }
-            G_bc1[index2] = G_bc1[index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc1);
-        }
-        G_bc1[index2] = G_bc1[index2] / batch_size;
-        if(G_bc1[index2] > Gradient_Limit) G_bc1[index2] = Gradient_Limit;
-        else if (G_bc1[index2] < -Gradient_Limit) G_bc1[index2] = -Gradient_Limit;
-        //bc1_temp[index2] = bc1_temp[index2] - gradient_rate_critic * G_bc1[index2];
-    }
-
-
-    float G_hc2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
-    float G_bc2[num_hidden_unit2] = {0.0f};
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            for (int n=0; n<batch_size; n++) {
-                float d_V_d_hc2 = 0.0f;
-                if (hxh_c_sum_array[n][index2] >= 0) {
-                    if (hx_c_sum_array[n][index1] > 0) {
-                        d_V_d_hc2 = hx_c_sum_array[n][index1]*hc3_temp[index2];
-                    }
-                }
-                G_hc2[index1][index2] = G_hc2[index1][index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc2);
-            }
-            G_hc2[index1][index2] = G_hc2[index1][index2] / batch_size;
-            if(G_hc2[index1][index2] > Gradient_Limit) G_hc2[index1][index2] = Gradient_Limit;
-            else if (G_hc2[index1][index2] < -Gradient_Limit) G_hc2[index1][index2] = -Gradient_Limit;
-            //hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate_critic * G_hc2[index1][index2];
-        }
-        for (int n=0; n<batch_size; n++) {
-            float d_V_d_bc2 = 0.0f;
-            if (hxh_c_sum_array[n][index2] >= 0) {
-                d_V_d_bc2 = hc3_temp[index2];
-            }
-            G_bc2[index2] = G_bc2[index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc2);
-        }
-        G_bc2[index2] = G_bc2[index2] / batch_size;
-        if(G_bc2[index2] > Gradient_Limit) G_bc2[index2] = Gradient_Limit;
-        else if (G_bc2[index2] < -Gradient_Limit) G_bc2[index2] = -Gradient_Limit;
-        //bc2_temp[index2] = bc2_temp[index2] - gradient_rate_critic * G_bc2[index2];
-    }
-
-    float G_hc3[num_hidden_unit2]= {0.0f};
-    float G_bc3 = 0.0f;
-    for (int index2 = 0; index2 < 1; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            for (int n=0; n<batch_size; n++) {
-                float d_V_d_hc3 = 0.0f;
-                if (hxh_c_sum_array[n][index1] >= 0) {
-                    d_V_d_hc3 = d_V_d_hc3 + hxh_c_sum_array[n][index1];
-                }
-                G_hc3[index1] = G_hc3[index1] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc3);
-            }
-            G_hc3[index1] = G_hc3[index1] / batch_size;
-            if(G_hc3[index1] > Gradient_Limit) G_hc3[index1] = Gradient_Limit;
-            else if (G_hc3[index1] < -Gradient_Limit) G_hc3[index1] = -Gradient_Limit;
-            //hc3_temp[index1] = hc3_temp[index1] - gradient_rate_critic * G_hc3[index1];
-        }
-        for (int n=0; n<batch_size; n++) {
-            float d_V_d_bc3 = 0.0f;
-            d_V_d_bc3 = 1.0f;
-            G_bc3 = G_bc3 + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc3);
-        }
-        G_bc3 = G_bc3 / batch_size;
-        if(G_bc3 > Gradient_Limit) G_bc3 = Gradient_Limit;
-        else if (G_bc3 < -Gradient_Limit) G_bc3 = -Gradient_Limit;
-        //bc3_temp = bc3_temp - gradient_rate_critic * G_bc3;
-    }
-
-    // Simultaneous Update
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate_critic * G_hc1[index1][index2];
-        }
-        bc1_temp[index2] = bc1_temp[index2] - gradient_rate_critic * G_bc1[index2];
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate_critic * G_hc2[index1][index2];
-        }
-        bc2_temp[index2] = bc2_temp[index2] - gradient_rate_critic * G_bc2[index2];
-    }
-    for (int index2 = 0; index2 < 1; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            hc3_temp[index1] = hc3_temp[index1] - gradient_rate_critic * G_hc3[index1];
-        }
-        bc3_temp = bc3_temp - gradient_rate_critic * G_bc3;
-    }
-}
-
-///////////////////////////Softplus//////////////////////////////////
-void update_Actor_Networks(float (*arr)[num_input_RL])
-{
-
-
-    float G_ha1[num_input_RL][num_hidden_unit1] = {0.0f};
-    float G_ba1[num_hidden_unit1] = {0.0f};
-
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            for (int n=0; n<batch_size; n++) {
-                float d_x_d_ha1 = 0.0f;
-                float d_y_d_ha1 = 0.0f;
-                if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
-                    G_ha1[index1][index2] = G_ha1[index1][index2];
-                } else {
-                    for(int k=0; k<num_hidden_unit2; k++) {
-                        if (hxh_a_sum_array[n][k] >= 0) {
-                            if (hx_a_sum_array[n][index2] > 0) {
-                                d_x_d_ha1 = d_x_d_ha1 + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][0];
-                                d_y_d_ha1 = d_y_d_ha1 + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][1];
-                            }
-                        }
-                    }
-                    float d_mean_d_ha1 = 0.0f;
-                    float d_dev_d_ha1 = 0.0f;
-                    d_mean_d_ha1 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha1;
-                    d_dev_d_ha1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha1;
-
-                    G_ha1[index1][index2] = G_ha1[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha1*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha1*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
-                }
-            }
-            G_ha1[index1][index2] = -G_ha1[index1][index2] / batch_size;
-            if(G_ha1[index1][index2] > Gradient_Limit) G_ha1[index1][index2] = Gradient_Limit;
-            else if (G_ha1[index1][index2] < -Gradient_Limit) G_ha1[index1][index2] = -Gradient_Limit;
-            //ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate_actor * G_ha1[index1][index2];
-        }
-
-        for (int n=0; n<batch_size; n++) {
-            float d_x_d_ba1 = 0.0f;
-            float d_y_d_ba1 = 0.0f;
-            if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon))  {
-                G_ba1[index2] = G_ba1[index2];
-            } else {
-                for(int k=0; k<num_hidden_unit2; k++) {
-                    if (hxh_a_sum_array[n][k] >= 0) {
-                        if (hx_a_sum_array[n][index2] > 0) {
-                            d_x_d_ba1 = d_x_d_ba1 + ha2_temp[index2][k]*ha3_temp[k][0];
-                            d_y_d_ba1 = d_y_d_ba1 + ha2_temp[index2][k]*ha3_temp[k][1];
-                        }
-                    }
-                }
-                float d_mean_d_ba1 = 0.0f;
-                float d_dev_d_ba1 = 0.0f;
-                d_mean_d_ba1 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba1;
-                d_dev_d_ba1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba1;
-
-                G_ba1[index2] = G_ba1[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba1*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba1*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
-            }
-        }
-        G_ba1[index2] = -G_ba1[index2] / batch_size;
-        if(G_ba1[index2] > Gradient_Limit) G_ba1[index2] = Gradient_Limit;
-        else if (G_ba1[index2] < -Gradient_Limit) G_ba1[index2] = -Gradient_Limit;
-        //ba1_temp[index2] = ba1_temp[index2] - gradient_rate_actor * G_ba1[index2];
-    }
-
-    float G_ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
-    float G_ba2[num_hidden_unit2] = {0.0f};
-
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            for (int n=0; n<batch_size; n++) {
-                float d_x_d_ha2 = 0.0f;
-                float d_y_d_ha2 = 0.0f;
-                if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
-                    G_ha2[index1][index2] = G_ha2[index1][index2];
-                } else {
-                    if (hxh_a_sum_array[n][index2] >= 0) {
-                        if (hx_a_sum_array[n][index1] > 0) {
-                            d_x_d_ha2 = hx_a_sum_array[n][index1]*ha3_temp[index2][0];
-                            d_y_d_ha2 = hx_a_sum_array[n][index1]*ha3_temp[index2][1];
-                        }
-                    }
-
-                    float d_mean_d_ha2 = 0.0f;
-                    float d_dev_d_ha2 = 0.0f;
-                    d_mean_d_ha2 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha2;
-                    d_dev_d_ha2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha2;
-
-                    G_ha2[index1][index2] = G_ha2[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha2*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha2*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
-                }
-            }
-            G_ha2[index1][index2] = -G_ha2[index1][index2] / batch_size;
-            if(G_ha2[index1][index2] > Gradient_Limit) G_ha2[index1][index2] = Gradient_Limit;
-            else if (G_ha2[index1][index2] < -Gradient_Limit) G_ha2[index1][index2] = -Gradient_Limit;
-            //ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate_actor * G_ha2[index1][index2];
-        }
-
-        for (int n=0; n<batch_size; n++) {
-            float d_x_d_ba2 = 0.0f;
-            float d_y_d_ba2 = 0.0f;
-            if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon))  {
-                G_ba2[index2] = G_ba2[index2];
-            } else {
-
-                if (hxh_a_sum_array[n][index2] >= 0) {
-                    d_x_d_ba2 = ha3_temp[index2][0];
-                    d_y_d_ba2 = ha3_temp[index2][1];
-                }
-                float d_mean_d_ba2= 0.0f;
-                float d_dev_d_ba2= 0.0f;
-                d_mean_d_ba2 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba2;
-                d_dev_d_ba2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba2;
-
-                G_ba2[index2] = G_ba2[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba2*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba2*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
-            }
-        }
-        G_ba2[index2] = -G_ba2[index2] / batch_size;
-        if(G_ba2[index2] > Gradient_Limit) G_ba2[index2] = Gradient_Limit;
-        else if (G_ba2[index2] < -Gradient_Limit) G_ba2[index2] = -Gradient_Limit;
-        //ba2_temp[index2] = ba2_temp[index2] - gradient_rate_actor * G_ba2[index2];
-    }
-
-    float G_ha3[num_hidden_unit2][2] = {0.0f};
-    float G_ba3[2] = {0.0f};
-
-    for (int index2 = 0; index2 < 2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            for (int n=0; n<batch_size; n++) {
-                float d_x_d_ha3 = 0.0f;
-                float d_y_d_ha3 = 0.0f;
-                if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
-                    G_ha3[index1][index2] = G_ha3[index1][index2];
-                } else {
-                    if (hxh_a_sum_array[n][index1] >= 0) {
-                        if (hx_a_sum_array[n][index1] > 0) {
-                            d_x_d_ha3 = hxh_a_sum_array[n][index1];
-                            d_y_d_ha3 = hxh_a_sum_array[n][index1];
-                        }
-                    }
-                    float d_mean_d_ha3 = 0.0f;
-                    float d_dev_d_ha3 = 0.0f;
-                    d_mean_d_ha3 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha3;
-                    d_dev_d_ha3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha3;
-
-                    G_ha3[index1][index2] = G_ha3[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha3*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha3*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
-                }
-            }
-            G_ha3[index1][index2] = -G_ha3[index1][index2] / batch_size;
-            if(G_ha3[index1][index2] > Gradient_Limit) G_ha3[index1][index2] = Gradient_Limit;
-            else if (G_ha3[index1][index2] < -Gradient_Limit) G_ha3[index1][index2] = -Gradient_Limit;
-            //ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate_actor * G_ha3[index1][index2];
-        }
-
-        for (int n=0; n<batch_size; n++) {
-            float d_x_d_ba3 = 0.0f;
-            float d_y_d_ba3 = 0.0f;
-            if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon))  {
-                G_ba3[index2] = G_ba3[index2];
-            } else {
-
-                d_x_d_ba3 = 1.0f;
-                d_y_d_ba3 = 1.0f;
-
-                float d_mean_d_ba3= 0.0f;
-                float d_dev_d_ba3= 0.0f;
-                d_mean_d_ba3 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba3;
-                d_dev_d_ba3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba3;
-
-                G_ba3[index2] = G_ba3[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba3*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba3*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
-            }
-        }
-        G_ba3[index2] = -G_ba3[index2] / batch_size;
-        if(G_ba3[index2] > Gradient_Limit) G_ba3[index2] = Gradient_Limit;
-        else if (G_ba3[index2] < -Gradient_Limit) G_ba3[index2] = -Gradient_Limit;
-        //ba3_temp[index2] = ba3_temp[index2] - gradient_rate_actor * G_ba3[index2];
-    }
-
-    // Simultaneous Update
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate_actor * G_ha1[index1][index2];
-        }
-        ba1_temp[index2] = ba1_temp[index2] - gradient_rate_actor * G_ba1[index2];
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate_actor * G_ha2[index1][index2];
-        }
-        ba2_temp[index2] = ba2_temp[index2] - gradient_rate_actor * G_ba2[index2];
-    }
-    for (int index2 = 0; index2 < 2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate_actor * G_ha3[index1][index2];
-        }
-        ba3_temp[index2] = ba3_temp[index2] - gradient_rate_actor * G_ba3[index2];
-    }
-}
-
-float rand_normal(double mean, double stddev)
-{
-    //Box muller method
-    static double n2 = 0.0f;
-    static int n2_cached = 0;
-    if (!n2_cached) {
-        double x, y, r;
-        do {
-            x = 2.0f*rand()/RAND_MAX - 1;
-            y = 2.0f*rand()/RAND_MAX - 1;
-
-            r = x*x + y*y;
-        } while (r == 0.0f || r > 1.0f);
-        {
-            double d = sqrt(-2.0f*log(r)/r);
-            double n1 = x*d;
-            n2 = y*d;
-            double result = n1*stddev + mean;
-            n2_cached = 1;
-            return result;
-        }
-    } else {
-        n2_cached = 0;
-        return n2*stddev + mean;
-    }
-}
-
-float mean_adv(float x[], int size)
-{
-    float add = 0.0f;
-    float result;
-
-    for (int i=0; i<size; i++) {
-        add += x[i];
-    }
-    result = (float) add/size;
-    return result;
-}
-float deviation_adv(float x[], int size)
-{
-    float sigma = 0.0f;
-    float resultDeb = 0.0f;
-
-    for (int k=0; k<size; k++) {
-        sigma = pow((float)x[k]-mean_adv(x,size), (float)2.0f)/(size-1);
-        resultDeb += sqrt(sigma);
-    }
-    return resultDeb;
-}
-
-
-void Overwirte_Critic_Networks()
-{
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            hc1[index1][index2] = hc1_temp[index1][index2];
-        }
-        bc1[index2] = bc1_temp[index2];
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            hc2[index1][index2] = hc2_temp[index1][index2];
-        }
-        bc2[index2] = bc2_temp[index2];
-        hc3[index2] = hc3_temp[index2];
-    }
-    bc3 = bc3_temp;
-}
-void Overwirte_Actor_Networks()
-{
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            ha1[index1][index2] = ha1_temp[index1][index2];
-        }
-        ba1[index2] = ba1_temp[index2];
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            ha2[index1][index2] = ha2_temp[index1][index2];
-        }
-        ba2[index2] = ba2_temp[index2];
-    }
-    for (int index2 = 0; index2 < 2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            ha3[index1][index2] = ha3_temp[index1][index2];
-        }
-        ba3[index2] = ba3_temp[index2];
-    }
-}
-
 
 int main()
 {
-
-    HAL_Init();
-    SystemClock_Config();
-
     /*********************************
     ***     Initialization
     *********************************/
+    
+    HAL_Init();
+    SystemClock_Config();
+    
     LED = 0;
     pc.baud(9600);
 
@@ -881,14 +209,14 @@
     init_as5510(i2c_slave_addr1);
     make_delay();
 
-//    // spi init
+    // spi init
     eeprom.format(8,3);
     eeprom.frequency(5000000); //5M
     enc.format(8,0);
     enc.frequency(5000000); //5M
     make_delay();
 
-    //rom
+    // rom
     ROM_CALL_DATA();
     make_delay();
 
@@ -906,11 +234,6 @@
     TIM3->CR1 ^= TIM_CR1_UDIS;
     make_delay();
 
-    // TMR2 init
-//    Init_TMR2();
-//    TIM2->CR1 ^= TIM_CR1_UDIS;
-//    make_delay();
-
     // CAN
     can.attach(&CAN_RX_HANDLER);
     CAN_ID_INIT();
@@ -918,7 +241,6 @@
 
     //Timer priority
     NVIC_SetPriority(TIM3_IRQn, 2);
-    //NVIC_SetPriority(TIM2_IRQn, 3);
     NVIC_SetPriority(TIM4_IRQn, 3);
 
     //can.reset();
@@ -945,258 +267,30 @@
             ID_index_array[i] =  (i+1) * 0.5f;
     }
 
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            hc1_temp[index1][index2] = (float) (rand()%100) * 0.007f ;
-        }
-        bc1_temp[index2] = (float) (rand()%100) * 0.007f;
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            hc2_temp[index1][index2] = (float) (rand()%100) * 0.007f;
-        }
-        bc2_temp[index2] = (float) (rand()%100) * 0.007f;
-        hc3_temp[index2] = (float) (rand()%100) * 0.007f;
-    }
-    bc3_temp = (float) (rand()%100) * 0.007f;
-
-    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
-        for (int index1 = 0; index1 < num_input_RL; index1++) {
-            ha1_temp[index1][index2] = (float) (rand()%100) * 0.007f;
-        }
-        ba1_temp[index2] = (float) (rand()%100) * 0.007f;
-    }
-    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
-            ha2_temp[index1][index2] = (float) (rand()%100) * 0.007f;
-        }
-        ba2_temp[index2] = (float) (rand()%100) * 0.007f;
-    }
-    for (int index2 = 0; index2 < 2; index2++) {
-        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
-            ha3_temp[index1][index2] = (float) (rand()%100) * 0.007f;
-        }
-        ba3_temp[index2] = (float) (rand()%100) * 0.007f;
-    }
-
-    Overwirte_Critic_Networks();
-    Overwirte_Actor_Networks();
-
     /************************************
     ***     Program is operating!
     *************************************/
     while(1) {
 
-//        if(timer_while==27491) {
+        // UART example
+//        if(timer_while==100000) {
 //            timer_while = 0;
-//            pc.printf("ref : %f     virt_pos : %f  mean : %f    deviation : %f       Last_pos_of_batch : %f      reward_sum : %f\n", pos.sen/(float)(ENC_PULSE_PER_POSITION), logging3, logging2, logging4, logging1, logging5);
-//            //pc.printf("%f\n", virt_pos);
-//            //pc.printf("%f\n", pos.sen/(float)(ENC_PULSE_PER_POSITION));
-//            //pc.printf("ref : %f     virt_pos : %f\n", pos.sen/(float)(ENC_PULSE_PER_POSITION), virt_pos);
+//            pc.printf("%f\n", value);
 //        }
-
-
-        //i2c
-        read_field(i2c_slave_addr1);
-        if(DIR_VALVE_ENC < 0) value = 1023 - value;
-
-        //timer_while ++;
-
-        ///////////////////////////////////////////////////////Neural Network
-
-        if(NN_Control_Flag == 0) {
-            LED = 0;
-        }
-
-        else if(NN_Control_Flag == 1) {
-
-            int ind = 0;
-            for(int i=0; i<numpast_u; i++) {
-                input_NN[ind] = u_past[time_interval*i];
-                ind = ind + 1;
-            }
-
-            for(int i=0; i<numpast_x; i++) {
-                input_NN[ind] = x_past[time_interval*i] / 60.0f;
-                ind = ind + 1;
-            }
-            input_NN[ind] = (pos.sen / ENC_PULSE_PER_POSITION) / 60.0f;
-            ind = ind + 1;
-
-//            for(int i=0; i<numfuture_x; i++) {
-//                input_NN[ind] = x_future[time_interval*i+time_interval] / 60.0f;
-//                ind = ind + 1;
-//            }
-
-            for(int i=0; i<numpast_f; i++) {
-//                input_NN[ind] = f_past[time_interval*i] / 10000.0f * 8.0f + 0.5f;
-                input_NN[ind] = f_past[time_interval*i] / 10000.0f + 0.5f;
-                ind = ind + 1;
-            }
-//            input_NN[ind] = torq.sen / 10000.0f * 8.0f + 0.5f;
-            input_NN[ind] = torq.sen / 10000.0f + 0.5f;
-            ind = ind + 1;
-            for(int i=0; i<numfuture_f-1; i++) {
-//                input_NN[ind] = (f_future[time_interval*i+time_interval] - torq.sen)/10000.0f * 8.0f + 0.5f;
-//                input_NN[ind] = (f_future[time_interval*i+time_interval] - torq.sen)/10000.0f + 0.5f;
-//                input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f*8.0f+0.5f;
-                input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f + 0.5f;
-                ind = ind + 1;
-            }
-
-            float output1[16] = { 0.0f };
-            float output2[16] = { 0.0f };
-            float output3[16] = { 0.0f };
-            float output = 0.0f;
-
-            for (int index2 = 0; index2 < 16; index2++) {
-                for (int index1 = 0; index1 < num_input; index1++) {
-                    output1[index2] = output1[index2]
-                                      + h1[index1][index2] * input_NN[index1];
-                }
-                output1[index2] = output1[index2] + b1[index2];
-                if (output1[index2] < 0) {
-                    output1[index2] = 0;
-                }
-            }
-
-            for (int index2 = 0; index2 < 16; index2++) {
-                for (int index1 = 0; index1 < 16; index1++) {
-                    output2[index2] = output2[index2]
-                                      + h2[index1][index2] * output1[index1];
-                }
-                output2[index2] = output2[index2] + b2[index2];
-                if (output2[index2] < 0) {
-                    output2[index2] = 0;
-                }
-            }
-
-            for (int index2 = 0; index2 < 16; index2++) {
-                for (int index1 = 0; index1 < 16; index1++) {
-                    output3[index2] = output3[index2]
-                                      + h3[index1][index2] * output2[index1];
-                }
-                output3[index2] = output3[index2] + b3[index2];
-                if (output3[index2] < 0) {
-                    output3[index2] = 0;
-                }
-            }
-
-            for (int index2 = 0; index2 < 1; index2++) {
-                for (int index1 = 0; index1 < 16; index1++) {
-                    output = output + hout[index1] * output3[index1];
-                }
-                output = output + bout[index2];
+//        timer_while ++;
 
-            }
-            output = 1.0f/(1.0f+exp(-output));
-            output_normalized = output;
-            output = output * 20000.0f - 10000.0f;
-
-            if(output>=0) {
-                valve_pos.ref = output*0.0001f*((double)VALVE_MAX_POS - (double) VALVE_CENTER) + (double) VALVE_CENTER;
-            } else {
-                valve_pos.ref = -output*0.0001f*((double)VALVE_MIN_POS - (double) VALVE_CENTER) + (double) VALVE_CENTER;
-            }
-
-
-            if(LED==1) {
-                LED=0;
-            } else
-                LED = 1;
-
-        }
-
-
-        /////////////////////////////////////////////////////////////////////RL
-        switch (Update_Case) {
-            case 0: {
-                break;
-            }
-            case 1: {
-                //Network Update(just update and hold network)
-                for (int epoch = 0; epoch < num_epoch; epoch++) {
-                    float loss_sum = 0.0f;
-                    for (int n=batch_size-1; n>=0; n--) {
-                        //Calculate Estimated V
-                        //float temp_array[3] = {state_array[n][0], state_array[n][1], state_array[n][2]};
-                        float temp_array[2] = {state_array[n][0], state_array[n][1]};
-                        V[n] = Critic_Network_Temp(temp_array);
-                        for (int i=0; i<num_hidden_unit1; i++) {
-                            hx_c_sum_array[n][i] = hx_c_sum[i];
-                        }
-                        for (int i=0; i<num_hidden_unit2; i++) {
-                            hxh_c_sum_array[n][i] = hxh_c_sum[i];
-                        }
-                        hxhh_c_sum_array[n] = hxhh_c_sum;
-
-                        pi[n] = exp(-(action_array[n]-mean_array[n])*(action_array[n]-mean_array[n])/(2.0f*deviation_array[n]*deviation_array[n]))/(sqrt(2.0f*PI)*deviation_array[n]);
-                        Actor_Network_Old(temp_array);
-                        pi_old[n] = exp(-(action_array[n]-mean_old)*(action_array[n]-mean_old)/(2.0f*deviation_old*deviation_old))/(sqrt(2.0f*PI)*deviation_old);
-                        r[n] = exp(-0.25f * 5.0f * state_array[n][1] * state_array[n][1]);
-                        if(n == batch_size-1) return_G[n] = 0.0f;
-                        else return_G[n] = gamma * return_G[n+1] + r[n];
-                        if(n == batch_size-1) td_target[n] = r[n];
-                        else td_target[n] = r[n] + gamma * V[n+1];
-                        delta[n] = td_target[n] - V[n];
-                        if(n == batch_size-1) advantage[n] = 0.0f;
-                        else advantage[n] = gamma * lmbda * advantage[n+1] + delta[n];
-//                        return_G[n] = advantage[n] + V[n];
-                        ratio[n] = pi[n]/pi_old[n];
-                    }
-                    float mean_advantage = 0.0f;
-                    float dev_advantage = 0.0f;
-                    mean_advantage = mean_adv(advantage, batch_size);
-                    dev_advantage = deviation_adv(advantage, batch_size);
-                    for (int n=batch_size-1; n>=0; n--) {
-                        //advantage[n] = (advantage[n]-mean_advantage)/dev_advantage;
-                        surr1[n] = ratio[n] * advantage[n];
-                        if (ratio[n] > 1.0f + epsilon) {
-                            surr2[n] = (1.0f + epsilon)*advantage[n];
-                        } else if( ratio[n] < 1.0f - epsilon) {
-                            surr2[n] = (1.0f - epsilon)*advantage[n];
-                        } else {
-                            surr2[n] = ratio[n]*advantage[n];
-                        }
-                        loss[n] = -min(surr1[n], surr2[n]);
-                        loss_sum = loss_sum + loss[n];
-                    }
-                    reward_sum = 0.0f;
-                    for (int i=0; i<batch_size; i++) {
-                        reward_sum = reward_sum + r[i];
-                    }
-                    logging5 = reward_sum;
-
-
-                    //loss_batch = loss_sum / (float) batch_size;
-                    loss_batch = loss_sum;
-                    //Update Networks
-                    update_Critic_Networks(state_array);
-                    update_Actor_Networks(state_array);
-                }
-                Update_Done_Flag = 1;
-                Update_Case = 0;
-                //logging1 = V[0];
-
-                break;
-            }
-            case 2: {
-                //Network apply to next Network
-                Overwirte_Critic_Networks();
-                Overwirte_Actor_Networks();
-                virt_pos = 10.0f;
-                Update_Done_Flag = 1;
-                Update_Case = 0;
-                break;
-            }
-
+        //i2c for SW valve
+        if(OPERATING_MODE == 5){
+            read_field(i2c_slave_addr1);
+            if(DIR_VALVE_ENC < 0) value = 1023 - value;
         }
     }
 }
 
+
+// Velocity feedforward for SW valve
 float DDV_JOINT_POS_FF(float REF_JOINT_VEL)
 {
-
     int i = 0;
     float Ref_Valve_Pos_FF = 0.0f;
     for(i=0; i<VALVE_POS_NUM; i++) {
@@ -1223,12 +317,11 @@
         Ref_Valve_Pos_FF = (float) VALVE_MIN_POS;
     }
 
-    Ref_Valve_Pos_FF = (float) VELOCITY_COMP_GAIN * 0.01f * (float) (Ref_Valve_Pos_FF - (float) VALVE_CENTER);
+    Ref_Valve_Pos_FF = (float) VELOCITY_COMP_GAIN * 0.01f * (float) (Ref_Valve_Pos_FF - (float) VALVE_CENTER);  //VELOCITY_COMP_GAIN : 0~100
     return Ref_Valve_Pos_FF;
-
 }
 
-
+// Valve feedforward for SW valve
 void VALVE_POS_CONTROL(float REF_VALVE_POS)
 {
     int i = 0;
@@ -1238,7 +331,6 @@
     } else if(REF_VALVE_POS < VALVE_MIN_POS) {
         REF_VALVE_POS = VALVE_MIN_POS;
     }
-
     valve_pos_err = (float) (REF_VALVE_POS - value);
     valve_pos_err_diff = valve_pos_err - valve_pos_err_old;
     valve_pos_err_old = valve_pos_err;
@@ -1261,6 +353,7 @@
     Vout.ref = VALVE_PWM_RAW_FF + VALVE_PWM_RAW_FB;
 }
 
+// PWM duty vs. voltage output of L6205 in STM board
 #define LT_MAX_IDX  57
 float LT_PWM_duty[LT_MAX_IDX] = {-100.0f, -80.0f, -60.0f, -50.0f, -40.0f, -35.0f, -30.0f, -25.0f, -20.0f,
                                  -19.0f, -18.0f, -17.0f, -16.0f, -15.0f, -14.0f, -13.0f, -12.0f, -11.0f, -10.0f,
@@ -1303,8 +396,6 @@
 
 
 
-
-
 /*******************************************************************************
                             TIMER INTERRUPT
 *******************************************************************************/
@@ -1327,26 +418,18 @@
         }
 
         ADC1->CR2  |= 0x40000000;
+        // Torque Sensing =============================================
         if (SENSING_MODE == 0) {
-            // Torque Sensing (0~210)bar =============================================
             float pres_A_new = (((float) ADC1->DR) - 2047.5f);
-            double alpha_update_ft = 1.0f / (1.0f + FREQ_TMR4 / (2.0f * 3.14f * 100.0f)); // f_cutoff : 200Hz
+            double alpha_update_ft = 1.0f / (1.0f + FREQ_TMR4 / (2.0f * 3.14f * 100.0f)); // f_cutoff : 100Hz
             pres_A.sen = (1.0f - alpha_update_ft) * pres_A.sen + alpha_update_ft * pres_A_new;
             torq.sen = -pres_A.sen / TORQUE_SENSOR_PULSE_PER_TORQUE;
 
-
-//        float alpha_update_pres_A = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*100.0f));
-////        float pres_A_new = ((float)ADC1->DR - PRES_A_NULL)  / PRES_SENSOR_A_PULSE_PER_BAR;
-//        float pres_A_new = ((float)ADC1->DR);
-//        pres_A.sen = pres_A.sen*(1.0f-alpha_update_pres_A)+pres_A_new*(alpha_update_pres_A);
-//        torq.sen = - (pres_A.sen-2048.0f); //pulse -2047~2047
-
-
+        // Pressure Sensing (0~210)bar =============================================
         } else if (SENSING_MODE == 1) {
-            // Pressure Sensing (0~210)bar =============================================
             float pres_A_new = (((float)ADC1->DR) - PRES_A_NULL);
             float pres_B_new = (((float)ADC2->DR) - PRES_B_NULL);
-            double alpha_update_pres = 1.0f / (1.0f + FREQ_TMR4 / (2.0f * 3.14f * 200.0f)); // f_cutoff : 500Hz
+            double alpha_update_pres = 1.0f / (1.0f + FREQ_TMR4 / (2.0f * 3.14f * 200.0f)); // f_cutoff : 200Hz
             pres_A.sen = (1.0f - alpha_update_pres) * pres_A.sen + alpha_update_pres * pres_A_new;
             pres_B.sen = (1.0f - alpha_update_pres) * pres_B.sen + alpha_update_pres * pres_B_new;
             CUR_PRES_A_BAR = pres_A.sen / PRES_SENSOR_A_PULSE_PER_BAR;
@@ -1359,30 +442,11 @@
             }
         }
 
-//        //Pressure sensor A
-//        ADC1->CR2  |= 0x40000000;                        // adc _ 12bit
-//        //while((ADC1->SR & 0b10));
-//        float alpha_update_pres_A = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*100.0f));
-//        float pres_A_new = ((float)ADC1->DR);
-//        pres_A.sen = pres_A.sen*(1.0f-alpha_update_pres_A)+pres_A_new*(alpha_update_pres_A);
-//        torq.sen = - (pres_A.sen-2048.0f); //pulse -2047~2047    //SW just changed the sign to correct the direction of loadcell on LIGHT. Correct later.
-//
-//
-//        //Pressure sensor B
-//        float alpha_update_pres_B = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*100.0f));
-//        float pres_B_new = ((float)ADC2->DR);
-//        pres_B.sen = pres_B.sen*(1.0f-alpha_update_pres_B)+pres_B_new*(alpha_update_pres_B);
-//        //torq.sen = pres_A.sen * (float) PISTON_AREA_A - pres_B.sen * (float) PISTON_AREA_B;
-
-
         //Current
         //ADC3->CR2  |= 0x40000000;                        // adc _ 12bit
-        //int raw_cur = ADC3->DR;
-        //while((ADC3->SR & 0b10));
         float alpha_update_cur = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*500.0f)); // f_cutoff : 500Hz
         float cur_new = ((float)ADC3->DR-2048.0f)*20.0f/4096.0f; // unit : mA
         cur.sen=cur.sen*(1.0f-alpha_update_cur)+cur_new*(alpha_update_cur);
-        //cur.sen = raw_cur;
 
         CNT_TMR4++;
     }
@@ -1448,7 +512,6 @@
 
 
         // UTILITY MODE ------------------------------------------------------------
-
         switch (UTILITY_MODE) {
             case MODE_NO_ACT: {
                 break;
@@ -1467,8 +530,6 @@
 
                         if (TORQUE_VREF > 3.3f) TORQUE_VREF = 3.3f;
                         if (TORQUE_VREF < 0.0f) TORQUE_VREF = 0.0f;
-
-                        //spi_eeprom_write(RID_TORQUE_SENSOR_VREF, (int16_t) (TORQUE_VREF * 1000.0));
                         dac_1 = TORQUE_VREF / 3.3f;
                     }
                 } else {
@@ -1477,7 +538,6 @@
                     CUR_TORQUE_sum = 0;
                     CUR_TORQUE_mean = 0;
 
-//                    ROM_RESET_DATA();
                     spi_eeprom_write(RID_TORQUE_SENSOR_VREF, (int16_t) (TORQUE_VREF * 1000.0f));
 
                     dac_1 = TORQUE_VREF / 3.3f;
@@ -1551,7 +611,7 @@
 //                        }
 //                        V_out = 0;
 //
-//                        ROM_RESET_DATA();
+//                      
 //
 //                        //spi_eeprom_write(RID_VALVE_DEADZONE_PLUS, VALVE_DEADZONE_PLUS);
 //                        //spi_eeprom_write(RID_VALVE_DEADZONE_MINUS, VALVE_DEADZONE_MINUS);
@@ -1568,7 +628,6 @@
                 if (FINDHOME_STAGE == FINDHOME_INIT) {
                     cnt_findhome = 0;
                     cnt_vel_findhome = 0;
-                    //REFERENCE_MODE = MODE_REF_NO_ACT; // Stop taking reference data from PODO
                     pos.ref = pos.sen;
                     vel.ref = 0.0f;
                     FINDHOME_STAGE = FINDHOME_GOTOLIMIT;
@@ -1588,23 +647,14 @@
                     }
 
                     if ((cnt_vel_findhome < 3*TMR_FREQ_5k) &&  cnt_findhome < 10*TMR_FREQ_5k) { // wait for 3sec
-                        //REFERENCE_MODE = MODE_REF_NO_ACT;
                         if (HOMEPOS_OFFSET > 0) pos.ref = pos.ref + 12.0f;
                         else pos.ref = pos.ref - 12.0f;
 
-//                        pos.err = pos.ref_home_pos - pos.sen;
-//                        float VALVE_POS_RAW_POS_FB = 0.0f;
-//                        VALVE_POS_RAW_POS_FB = (float) P_GAIN_JOINT_POSITION * pos.err/(float) ENC_PULSE_PER_POSITION * 0.01f;
-//                        valve_pos.ref = VALVE_POS_RAW_POS_FB + (float) VALVE_CENTER;
-//                        VALVE_POS_CONTROL(valve_pos.ref);
-
                         CONTROL_MODE = MODE_JOINT_CONTROL;
                         alpha_trans = 0.0f;
 
-
                     } else {
                         ENC_SET(HOMEPOS_OFFSET);
-//                        ENC_SET_ZERO();
                         INIT_REF_POS = HOMEPOS_OFFSET;
                         REF_POSITION = 0;
                         REF_VELOCITY = 0;
@@ -1621,20 +671,11 @@
                         vel.ref = 0.0f;
                         pos.ref_home_pos = 0.0f;
                         vel.ref_home_pos = 0.0f;
-                        //FINDHOME_STAGE = FINDHOME_INIT;
-                        //CONTROL_UTILITY_MODE = MODE_JOINT_CONTROL;
-
-
                     }
                 } else if (FINDHOME_STAGE == FINDHOME_ZEROPOSE) {
                     int T_move = 2*TMR_FREQ_5k;
                     pos.ref = (0.0f - (float)INIT_REF_POS)*0.5f*(1.0f - cos(3.14159f * (float)cnt_findhome / (float)T_move)) + (float)INIT_REF_POS;
-                    //pos.ref = 0.0f;
                     vel.ref = 0.0f;
-
-                    // input for position control
-
-//                    CONTROL_MODE = MODE_JOINT_CONTROL;
                     alpha_trans = 0.0f;
 
                     double torq_ref = 0.0f;
@@ -1664,8 +705,6 @@
 
                         I_REF = I_REF_POS;
 
-
-
                     } else {
                         float VALVE_POS_RAW_FORCE_FB = 0.0f;
                         VALVE_POS_RAW_FORCE_FB = DDV_JOINT_POS_FF(vel.sen) + (P_GAIN_JOINT_POSITION * 0.01f * pos.err + DDV_JOINT_POS_FF(vel.ref));
@@ -1682,18 +721,8 @@
 
                     }
 
-
-
-
-//                    pos.err = pos.ref - (float)pos.sen;
-//                    float VALVE_POS_RAW_POS_FB = 0.0f;
-//                    VALVE_POS_RAW_POS_FB = (float) P_GAIN_JOINT_POSITION * 0.01f * pos.err/(float) ENC_PULSE_PER_POSITION;
-//                    valve_pos.ref = VALVE_POS_RAW_POS_FB + (float) VALVE_CENTER;
-//                    VALVE_POS_CONTROL(valve_pos.ref);
-
                     cnt_findhome++;
                     if (cnt_findhome >= T_move) {
-                        //REFERENCE_MODE = MODE_REF_DIRECT;
                         cnt_findhome = 0;
                         pos.ref = 0.0f;
                         vel.ref = 0.0f;
@@ -1755,7 +784,7 @@
 //                    }
 //                    if (fl_temp_cnt2 == 100) {
 //
-//                        ROM_RESET_DATA();
+//                       
 //
 //                        //spi_eeprom_write(RID_VALVE_GAIN_PLUS_1 + flag_flowrate, (int16_t) (VALVE_GAIN_LPM_PER_V[flag_flowrate] * 100.0f));
 //                        cur_vel_sum = 0;
@@ -1810,13 +839,11 @@
                     CUR_PRES_A_mean = 0;
                     CUR_PRES_B_mean = 0;
 
-//                    ROM_RESET_DATA();
                     spi_eeprom_write(RID_PRES_A_SENSOR_VREF, (int16_t) (PRES_A_VREF * 1000.0f));
                     spi_eeprom_write(RID_PRES_B_SENSOR_VREF, (int16_t) (PRES_B_VREF * 1000.0f));
 
                     dac_1 = PRES_A_VREF / 3.3f;
                     dac_2 = PRES_B_VREF / 3.3f;
-                    //pc.printf("nulling end");
                 }
                 TMR3_COUNT_PRES_NULL++;
                 break;
@@ -1846,7 +873,7 @@
 //                    CUR_PRES_A_mean = 0;
 //                    CUR_PRES_B_mean = 0;
 //
-//                    ROM_RESET_DATA();
+//                   
 //
 //                    //spi_eeprom_write(RID_PRES_SENSOR_A_PULSE_PER_BAR, (int16_t) (PRES_SENSOR_A_PULSE_PER_BAR * 100.0f));
 //                    //spi_eeprom_write(RID_PRES_SENSOR_B_PULSE_PER_BAR, (int16_t) (PRES_SENSOR_B_PULSE_PER_BAR * 100.0f));
@@ -1904,7 +931,6 @@
                             VALVE_POS_AVG_OLD = VALVE_MIN_POS;
                         }
                     }
-//                    ROM_RESET_DATA();
                     spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
                     spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
                     for(int i=0; i<25; i++) {
@@ -1980,8 +1006,6 @@
                     if((DZ_case == -1 && DZ_NUM == 1) | (DZ_case == 1 && DZ_NUM == 1)) {
                         if(VALVE_DZ_timer < (int) (1.0 * (float) TMR_FREQ_5k)) {
                             Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
-                            //pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
-                            //CONTROL_MODE = MODE_JOINT_CONTROL;
                         } else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
                             START_POS = pos.sen;
                         } else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
@@ -2018,8 +1042,6 @@
                     } else if((DZ_case == -1 && DZ_NUM == 2) | (DZ_case == 1 && DZ_NUM == 2)) {
                         if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
                             Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
-                            //pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
-                            //CONTROL_MODE = MODE_JOINT_CONTROL;
                         } else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
                             START_POS = pos.sen;
                         } else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
@@ -2054,7 +1076,6 @@
                                 VALVE_DEADZONE_MINUS = (float) FIRST_DZ;
                                 VALVE_DEADZONE_PLUS = (float) SECOND_DZ;
 
-//                                ROM_RESET_DATA();
                                 spi_eeprom_write(RID_VALVE_CNETER, (int16_t) VALVE_CENTER);
                                 spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
                                 spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
@@ -2066,8 +1087,6 @@
                     } else if(DZ_case == 0 && DZ_NUM ==1) {
                         if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
                             Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
-                            //pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
-                            //CONTROL_MODE = MODE_JOINT_CONTROL;
                         } else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
                             START_POS = pos.sen;
                         } else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
@@ -2103,8 +1122,6 @@
                     } else {
                         if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
                             Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
-                            //pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
-                            //CONTROL_MODE = MODE_JOINT_CONTROL;
                         } else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
                             START_POS = pos.sen;
                         } else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
@@ -2138,8 +1155,7 @@
                                 first_check = 0;
                                 VALVE_DEADZONE_MINUS = (float) FIRST_DZ;
                                 VALVE_DEADZONE_PLUS = (float) SECOND_DZ;
-
-//                                ROM_RESET_DATA();
+                                
                                 spi_eeprom_write(RID_VALVE_CNETER, (int16_t) VALVE_CENTER);
                                 spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
                                 spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
@@ -2159,15 +1175,12 @@
                 if(first_check == 0) {
                     if(VALVE_FR_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
                         Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
-                        //CAN_TX_PRES((int16_t) (VALVE_FR_timer), (int16_t) (6));
                     } else if(VALVE_FR_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
                         Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
                         pos_plus_end = pos.sen;
-                        //                    CAN_TX_PRES((int16_t) (V_out), (int16_t) (7));
                     } else if(VALVE_FR_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
                         Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
                     } else if(VALVE_FR_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
-                        //                    CAN_TX_PRES((int16_t) (V_out), (int16_t) (8));
                         Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
                         pos_minus_end = pos.sen;
                         first_check = 1;
@@ -2179,7 +1192,6 @@
                     }
                 } else {
                     if(VALVE_FR_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
-                        //V_out = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
                         pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
                         CONTROL_MODE = MODE_JOINT_CONTROL;
                     } else if(VALVE_FR_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
@@ -2219,7 +1231,6 @@
                     if(max_check == 1 && min_check == 1) {
 
                         VALVE_POS_NUM = ID_index;
-//                        ROM_RESET_DATA();
                         for(int i=0; i<100; i++) {
                             spi_eeprom_write(RID_VALVE_POS_VS_FLOWRATE_0 + i, (int16_t) (JOINT_VEL[i] & 0xFFFF));
                             spi_eeprom_write(RID_VALVE_POS_VS_FLOWRATE_0_1 + i, (int16_t) ((JOINT_VEL[i] >> 16) & 0xFFFF));
@@ -2228,7 +1239,6 @@
                         first_check = 0;
                         VALVE_FR_timer = 0;
                         CONTROL_UTILITY_MODE = MODE_NO_ACT;
-//                        CAN_TX_PRES((int16_t) (VALVE_FR_timer), (int16_t) (6));
                     }
                 }
                 break;
@@ -2324,12 +1334,6 @@
                     CONTROL_UTILITY_MODE = MODE_SEND_OVER;
                     CONTROL_MODE = MODE_NO_ACT;
                 }
-//                if (cnt_step_test > (int) (2.0f * (float) TMR_FREQ_5k))
-//                {
-//                    CONTROL_UTILITY_MODE = MODE_NO_ACT;
-//                    CONTROL_MODE = MODE_NO_ACT;
-//                    CAN_TX_PWM((int16_t) (1)); //1300
-//                }
 
                 break;
             }
@@ -2338,8 +1342,9 @@
                 break;
         }
 
+
+
         // CONTROL MODE ------------------------------------------------------------
-
         switch (CONTROL_MODE) {
             case MODE_NO_ACT: {
                 V_out = 0.0f;
@@ -2370,8 +1375,7 @@
                 K_LPF = K_LPF*(1.0f-alpha_K_D)+K_SPRING*(alpha_K_D);
                 D_LPF = D_LPF*(1.0f-alpha_K_D)+D_DAMPER*(alpha_K_D);
 
-//                torq_ref = torq.ref + K_LPF * pos.err - D_LPF * vel.sen / ENC_PULSE_PER_POSITION; //[N]
-                torq_ref = torq.ref;
+                torq_ref = torq.ref + K_LPF * pos.err - D_LPF * vel.sen / ENC_PULSE_PER_POSITION; //[N]
 
                 // torque feedback
                 torq.err = torq_ref - torq.sen; //[N]
@@ -2468,15 +1472,9 @@
                     }
 
                     VALVE_POS_CONTROL(valve_pos.ref);
-
-//                    Vout.ref = (float) P_GAIN_JOINT_POSITION * 0.01f * ((float) pos.err);
                     V_out = (float) Vout.ref;
-
                 }
-
                 torq_ref_past = torq_ref;
-
-
                 break;
             }
 
@@ -2549,16 +1547,6 @@
                 x_4_des_old = x_4_des;
                 float V_input = 0.0f;
                 V_out = (-f4 + x_4_des_dot - k4*(x_v-x_4_des)- rho3/rho4*gamma_hat*g3_prime*(-torq.err))/g4;
-//                //V_out LPF
-//                float alpha_V_out = 1.0f/(1.0f + 5000.0f/(2.0f*3.14f*50.0f)); // f_cutoff : 50Hz
-//                V_out = V_out*(1.0f-alpha_V_out)+V_input*(alpha_V_out);
-
-//                float rho_gamma = 5000.0f;//5000 for change //50000 for not change
-//                float gamma_hat_dot = rho3*(-torq.err)/rho_gamma*((-f3+torq_ref_dot-k3*(-torq.err))/gamma_hat + g3_prime*(x_v-x_4_des));
-//                gamma_hat = gamma_hat + gamma_hat_dot / (float) TMR_FREQ_5k;
-//
-//                if(gamma_hat > 10000.0f) gamma_hat = 10000.0f;
-//                else if(gamma_hat < 100.0f) gamma_hat = 100.0f;
 
                 float rho_a = 0.00001f;
                 float a_hat_dot = -rho3/rho_a*vel.sen/(float)(ENC_PULSE_PER_POSITION)*0.001f*(-torq.err);
@@ -2570,96 +1558,6 @@
                 break;
             }
 
-            case MODE_RL: {
-                //t.reset();
-                //t.start();
-
-//                if(LED == 0) LED = 1;
-//                else LED = 0;
-
-                if (Update_Done_Flag == 1) {
-                    //Gather Data on each loop
-//                  pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
-//                  train_set_x[RL_timer] = pos.sen/(float)(ENC_PULSE_PER_POSITION)/35.0f - 1.0f;   //-1.0~1.0
-//                  train_set_error[RL_timer] = pos.err/70.0f;      //-1.0~1.0
-                    pos.err = pos.sen/(float)(ENC_PULSE_PER_POSITION)  - virt_pos; //[mm]
-                    train_set_x[RL_timer] = virt_pos/70.0f;   //-1.0~1.0
-                    train_set_error[RL_timer] = pos.err/70.0f;      //-1.0~1.0
-                    //train_set_count[RL_timer] = (float) RL_timer / (batch_size *num_batch);  //-1.0~1.0
-                    //float temp_array[3] = {train_set_x[RL_timer], train_set_error[RL_timer], train_set_count[RL_timer]};
-                    float temp_array[2] = {train_set_x[RL_timer], train_set_error[RL_timer]};
-                    Actor_Network(temp_array);
-                    for (int i=0; i<num_hidden_unit1; i++) {
-                        hx_a_sum_array[RL_timer][i] = hx_a_sum[i];
-                    }
-                    for (int i=0; i<num_hidden_unit2; i++) {
-                        hxh_a_sum_array[RL_timer][i] = hxh_a_sum[i];
-                    }
-                    hxhh_a_sum_array[RL_timer][0] = hxhh_a_sum[0];
-                    hxhh_a_sum_array[RL_timer][1] = hxhh_a_sum[1];
-                    mean_array[RL_timer] = mean;
-                    deviation_array[RL_timer] = deviation;
-                    action_array[RL_timer] = rand_normal(mean_array[RL_timer], deviation_array[RL_timer]);
-
-                    virt_pos = virt_pos + (action_array[RL_timer] - 5.0f) * 1000.0f * 0.0002f;
-                    if (virt_pos > 70 ) {
-                        virt_pos = 70.0f;
-                    } else if(virt_pos < -70) {
-                        virt_pos = -70.0f;
-                    }
-
-                    RL_timer++;
-
-
-                    if (RL_timer >= batch_size) {
-                        RL_timer = 0;
-                        batch++;
-                        for(int i=0; i<batch_size; i++) {
-                            state_array[i][0] = train_set_x[i];
-                            state_array[i][1] = train_set_error[i];
-                            //state_array[i][2] = train_set_count[i];
-                        }
-                        Update_Case = 1;
-                        Update_Done_Flag = 0;
-                        logging1 = virt_pos;
-
-                        if(batch >= num_batch) {
-                            batch = 0;
-                            RL_timer = 0;
-                            Update_Case = 2;
-                            Update_Done_Flag = 0;
-                            virt_pos = 10.0f;
-                        }
-                    }
-                }
-
-                else {
-                    pos.err = pos.sen/(float)(ENC_PULSE_PER_POSITION) - virt_pos; //[mm]
-                    float temp_array[3] = {0.0f};
-                    temp_array[0] = virt_pos/70.0f;   //-1.0~1.0
-                    temp_array[1] = pos.err/70.0f;      //-1.0~1.0
-                    //temp_array[2] = (float) RL_timer / (batch_size *num_batch);  //-1.0~1.0
-                    Actor_Network(temp_array);
-                    action = rand_normal(mean, deviation);
-                    //logging1 = action;
-                    //logging2 = mean;
-                    //logging4 = deviation;
-                    virt_pos = virt_pos + (action-5.0f) * 1000.0f * 0.0002f;
-                    if (virt_pos > 70) {
-                        virt_pos = 70.0f;
-                    } else if(virt_pos < -70) {
-                        virt_pos = -70.0f;
-                    }
-
-                    logging3 = virt_pos;
-                }
-
-                //t.stop();
-                //logging1 = t.read()*1000.0f;    //msec
-
-                break;
-            }
-
             default:
                 break;
         }
@@ -2697,7 +1595,6 @@
                 double FF_gain = 1.0f;
 
                 VALVE_PWM_RAW = KP_I * 2.0f * I_ERR + KI_I * 2.0f* I_ERR_INT;
-                //        VALVE_PWM_RAW = VALVE_PWM_RAW + FF_gain * (R_model*I_REF); // Unit : mV
                 I_REF_fil_diff = I_REF_fil - I_REF_fil_old;
                 I_REF_fil_old = I_REF_fil;
 //                VALVE_PWM_RAW = VALVE_PWM_RAW + FF_gain * (R_model * I_REF_fil + L_model * I_REF_fil_diff * 5000.0f); // Unit : mV
@@ -2754,15 +1651,12 @@
 //            else if (CUR_PWM_lin < 0) V_out = (float) (CUR_PWM_lin - 174.0f);
 //            else V_out = (float) (CUR_PWM_lin);
 
+            // Output Voltage Linearization & Dead Zone Cancellation (Electrical dead-zone) by SW
             if (V_out > 0 ) V_out = (V_out + 180.0f)/0.8588f;
             else if (V_out < 0) V_out = (V_out - 200.0f)/0.8651f;
             else V_out = 0.0f;
         }
 
-//        if(V_out > 0.0f) V_out = (float) (V_out + 169.0f);
-//        else if(V_out < 0.0f) V_out = (float) (V_out - 174.0f);
-//        else V_out = V_out;
-
         /*******************************************************
         ***     PWM
         ********************************************************/
@@ -2775,9 +1669,9 @@
         } else if(V_out<=-VALVE_VOLTAGE_LIMIT*1000.0f) {
             V_out = -VALVE_VOLTAGE_LIMIT*1000.0f;
         }
-        PWM_out= V_out/(SUPPLY_VOLTAGE*1000.0f); // Full duty : 12000.0mV
+        PWM_out= V_out/(SUPPLY_VOLTAGE*1000.0f);
 
-        // Saturation of output voltage to 12.0V
+        // Saturation of output voltage
         if(PWM_out > 1.0f) PWM_out=1.0f;
         else if (PWM_out < -1.0f) PWM_out=-1.0f;
 
@@ -2812,11 +1706,13 @@
                     }
                 }
             }
+            
+            // ID:1300
             if (flag_data_request[1] == HIGH) {
-                CAN_TX_TORQUE((int16_t) (return_G[0]*100.0f)); //1300
+                CAN_TX_TORQUE((int16_t) 7); //1300
             }
 
-
+            // ID:1400
             if (flag_data_request[2] == HIGH) {
                 double t_value = 0.0f;
                 if(value>=(float) VALVE_CENTER) {
@@ -2839,27 +1735,19 @@
             for (can_rest = 0; can_rest < 10000; can_rest++) {
                 ;
             }
-
+            
+            // ID:1500
             if (flag_data_request[3] == HIGH) {
                 //PWM
                 CAN_TX_PWM((int16_t) (torq.ref)); //1500
-//                CAN_TX_PWM((int16_t) (f_future[1])); //1500
             }
-
+            
+            // ID:1600
             if (flag_data_request[4] == HIGH) {
                 //valve position
-                //CAN_TX_VALVE_POSITION((int16_t) pos.sen/(float)(ENC_PULSE_PER_POSITION), (int16_t) virt_pos, (int16_t) (logging2*1000.0f), (int16_t) (logging4*1000.0f)); //1600
                 CAN_TX_VALVE_POSITION((int16_t) (a_hat*0.0001f), (int16_t) 0, (int16_t) 0, (int16_t) 0); //1600
             }
 
-            // Others : Reference position, Reference FT, PWM, Current  (ID:1300)
-//        if (flag_data_request[1] == HIGH) {
-//            CAN_TX_SOMETHING((int) (FORCE_VREF), (int16_t) (1), (int16_t) (2), (int16_t) (3));
-//        }
-            //if (flag_delay_test == 1){
-            //CAN_TX_PRES((int16_t) (0),(int16_t) torq_ref);
-            //}
-
             TMR2_COUNT_CAN_TX = 0;
         }
         TMR2_COUNT_CAN_TX++;
--- a/setting.h	Mon Dec 28 12:10:50 2020 +0000
+++ b/setting.h	Mon Dec 28 14:27:11 2020 +0000
@@ -4,10 +4,10 @@
 // pwm 
 #define PIN_V       PB_7
 #define PIN_W       PB_6
-//#define PWM_ARR 0x465         // loop 80k, pwm 40k 
+//#define PWM_ARR     0x465       // loop 80k, pwm 40k 
 //#define PWM_ARR     0x8CA       // loop 40k, pwm 20k
 #define PWM_ARR     0x1194      // loop 20k, pwm 10k
-//#define PWM_ARR     0x2328    // loop 10k, pwm 5k
+//#define PWM_ARR     0x2328      // loop 10k, pwm 5k
 #define TMR3_COUNT  0x4650      // loop 5k
 #define TMR2_COUNT  0x2710      // loop 500hz with prescale 18
 
@@ -54,7 +54,6 @@
 
 
 // User Function 
-
 void CurrentControl();
 void ValveControl(unsigned int ControlMode);
 
@@ -65,7 +64,6 @@
 #define             LATEST_VERSION      19032
 
 
-
 /*******************************************************************************
  * COMMON CONSTANTS
  ******************************************************************************/
@@ -442,100 +440,11 @@
 extern float K_LPF;
 extern float D_LPF;
 
-extern float totq_sen_past;
+extern float torq_sen_past;
 extern float torq_ref_past;
 extern float output_normalized;
 
 
-#define     numpast_u           0
-#define     numpast_x           5
-#define     numfuture_x         0
-#define     numpast_f           0
-#define     numfuture_f         10
-//#define     num_input           17  //numpast_x + 1 + numfuture_x + numpast_f + 1 + numfuture_f
-#define     num_input           16  //numpast_x + 1 + numfuture_x + numpast_f + numfuture_f
-
-#define     num_array_u_past        1  // numpast_u * time_interval + 1
-#define     num_array_f_future      11  // numfuture_f * time_interval + 1
-#define     num_array_f_past        1  // numpast_f * time_interval + 1        
-#define     num_array_x_past        6  // numpast_x * time_interval + 1      
-#define     num_array_x_future      1  // numfuture_x * time_interval + 1
-
-#define     time_interval           1
-
-
-
-/////////////RL
-#define num_batch           10
-#define num_epoch           1
-#define batch_size          100
-#define num_input_RL        2
-#define num_hidden_unit1    10
-#define num_hidden_unit2    10
-
-extern int batch;
-extern float train_set_x[batch_size];
-extern float train_set_error[batch_size];
-extern float train_set_count[batch_size];
-extern float state_array[batch_size][num_input_RL];
-extern float V[batch_size];
-extern float r[batch_size];
-extern float td_target[batch_size];
-extern float delta[batch_size];
-extern float advantage[batch_size];
-extern float return_G[batch_size];
-
-extern float mean;
-extern float deviation;
-extern float mean_old;
-extern float deviation_old;
-extern float mean_before_SP;
-extern float deviation_before_SP;
-extern float mean_before_SP_array[batch_size];
-extern float deviation_before_SP_array[batch_size];
-extern float mean_array[batch_size];
-extern float mean_array_old[batch_size];
-extern float deviation_array[batch_size];
-extern float deviation_array_old[batch_size];
-
-extern float hx_c_sum[num_hidden_unit1];
-extern float hx_c_sum_array[batch_size][num_hidden_unit1];
-extern float hxh_c_sum[num_hidden_unit2];
-extern float hxh_c_sum_array[batch_size][num_hidden_unit2];
-extern float hxhh_c_sum;
-extern float hxhh_c_sum_array[batch_size];
-
-extern float hx_a_sum[num_hidden_unit1];
-extern float hx_a_sum_array[batch_size][num_hidden_unit1];
-extern float hxh_a_sum[num_hidden_unit2];
-extern float hxh_a_sum_array[batch_size][num_hidden_unit2];
-extern float hxhh_a_sum[2];
-extern float hxhh_a_sum_array[batch_size][2];
-
-extern float action;
-extern float action_array[batch_size];
-extern float ratio[batch_size];
-extern float pi[batch_size];
-extern float pi_old[batch_size];
-extern float epsilon;
-extern float surr1[batch_size];
-extern float surr2[batch_size];
-extern float loss[batch_size];
-extern float loss_batch;
-extern float gamma;
-extern float lmbda;
-extern char Update_Done_Flag;
-extern char Update_Case;
-extern float reward_sum; 
-
-extern float virt_pos;
-extern float logging1;
-extern float logging2;
-extern float logging3;
-extern float logging4;
-extern float logging5;
-
-