20210305

Dependencies:   mbed FastPWM

main.cpp

Committer:
Lightvalve
Date:
2020-11-24
Revision:
173:68c7914679ec
Parent:
172:63af34265fe9
Child:
174:c828479f53f9

File content as of revision 173:68c7914679ec:

//201124_1
#include "mbed.h"
#include "FastPWM.h"
#include "INIT_HW.h"
#include "function_CAN.h"
#include "SPI_EEP_ENC.h"
#include "I2C_AS5510.h"
#include "setting.h"
#include "function_utilities.h"
#include "stm32f4xx_flash.h"
#include "FlashWriter.h"
#include <string>
#include <iostream>

using namespace std;
Timer t;

///191008////

// dac & check ///////////////////////////////////////////
DigitalOut check(PC_2);
DigitalOut check_2(PC_3);
AnalogOut dac_1(PA_4);
AnalogOut dac_2(PA_5);
AnalogIn adc1(PC_4); //pressure_1
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;
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);

// UART ///////////////////////////////////////////
Serial pc(PA_9,PA_10); //  _ UART

// CAN ///////////////////////////////////////////
CAN can(PB_8, PB_9, 1000000);
CANMessage msg;
void onMsgReceived()
{
    CAN_RX_HANDLER();
}

// Variables ///////////////////////////////////////////
State pos;
State vel;
State Vout;
State torq;
State pres_A;
State pres_B;
State cur;
State valve_pos;

State INIT_Vout;
State INIT_Valve_Pos;
State INIT_Pos;
State INIT_torq;

extern int CID_RX_CMD;
extern int CID_RX_REF_POSITION;
extern int CID_RX_REF_VALVE_POS;
extern int CID_RX_REF_PWM;

extern int CID_TX_INFO;
extern int CID_TX_POSITION;
extern int CID_TX_TORQUE;
extern int CID_TX_PRES;
extern int CID_TX_VOUT;
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_SIN_WAVE,                                  //4
    MODE_REF_SQUARE_WAVE,                                  //5
};

/*******************************************************************************
 *  CONTROL MODE
 ******************************************************************************/
enum _CONTROL_MODE {
    //control mode
    MODE_NO_ACT = 0,                                    //0
    MODE_VALVE_POSITION_CONTROL,                        //1
    MODE_JOINT_CONTROL,                                 //2

    MODE_VALVE_OPEN_LOOP,                               //3
    MODE_JOINT_ADAPTIVE_BACKSTEPPING,                   //4
    MODE_RL,                                            //5

    MODE_JOINT_POSITION_PRES_CONTROL_PWM,               //6
    MODE_JOINT_POSITION_PRES_CONTROL_VALVE_POSITION,    //7
    MODE_VALVE_POSITION_PRES_CONTROL_LEARNING,          //8

    MODE_TEST_CURRENT_CONTROL,                          //9
    MODE_TEST_PWM_CONTROL,                              //10

    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

    //utility
    MODE_TORQUE_SENSOR_NULLING = 20,                    //20
    MODE_VALVE_NULLING_AND_DEADZONE_SETTING,            //21
    MODE_FIND_HOME,                                     //22
    MODE_VALVE_GAIN_SETTING,                            //23
    MODE_PRESSURE_SENSOR_NULLING,                       //24
    MODE_PRESSURE_SENSOR_CALIB,                         //25
    MODE_ROTARY_FRICTION_TUNING,                        //26

    MODE_DDV_POS_VS_PWM_ID = 30,                           //30
    MODE_DDV_DEADZONE_AND_CENTER,                       //31
    MODE_DDV_POS_VS_FLOWRATE,                           //32
    MODE_SYSTEM_ID,                                     //33
    MODE_FREQ_TEST,                                     //34
    MODE_SEND_BUFFER,                                   //35
    MODE_SEND_OVER,                                     //36
    MODE_STEP_TEST,                                     //37
};

void SystemClock_Config(void)
{
    RCC_OscInitTypeDef RCC_OscInitStruct = {0};
    RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};

    /** 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
    */
    RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
    RCC_OscInitStruct.HSIState = RCC_HSI_ON;
    RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
    RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
    RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
    RCC_OscInitStruct.PLL.PLLM = 8;//8
    RCC_OscInitStruct.PLL.PLLN = 180; //180
    RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
    RCC_OscInitStruct.PLL.PLLQ = 2;
    RCC_OscInitStruct.PLL.PLLR = 2;
    if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
        //Error_Handler();
    }
    /** Activate the Over-Drive mode
    */
    if (HAL_PWREx_EnableOverDrive() != HAL_OK) {
        //Error_Handler();
    }
    /** Initializes the CPU, AHB and APB busses clocks
    */
    RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
                                  |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
    RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
    RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
    RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
    RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;

    if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) {
        //Error_Handler();
    }
}

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.3752100467681885f,0.9850414395332336f,0.12903714179992676f,-0.23237967491149902f,-1.5664141178131104f,0.36565715074539185f,-0.17472904920578003f,-0.3780243396759033f,-0.5318458676338196f,-0.6931207776069641f,-0.24376395344734192f,-3.9280478954315186f,-0.259793758392334f,-0.5339483022689819f,-0.2571594715118408f,-0.4960939884185791f},
    {-1.184814453125f,0.8704654574394226f,-0.3927857577800751f,-0.40050771832466125f,-1.4921096563339233f,0.5157514810562134f,-0.4054011106491089f,-0.3723553717136383f,-0.264297217130661f,-0.4598728120326996f,-0.2805407643318176f,-2.543855905532837f,0.24001067876815796f,-0.9143947958946228f,-0.20967772603034973f,-0.46271881461143494f},
    {-0.9112814664840698f,0.6714562773704529f,0.36391180753707886f,-0.6117674708366394f,-1.1069424152374268f,0.9712548851966858f,0.2872133255004883f,-0.059537652879953384f,-0.28272250294685364f,-0.4464949667453766f,-0.3544096052646637f,-1.0609019994735718f,0.0019771659281104803f,-0.2590618431568146f,0.05590221285820007f,-1.0201798677444458f},
    {-0.2895396053791046f,-0.01403216365724802f,0.39742106199264526f,0.20069332420825958f,-0.6715657114982605f,0.5361601710319519f,-0.11584559082984924f,0.3479021489620209f,-0.01779201813042164f,-0.017457854002714157f,0.08943979442119598f,0.845181941986084f,-0.15994226932525635f,-0.14522784948349f,-0.2961459457874298f,-0.7345172166824341f},
    {1.1968307495117188f,-0.8280011415481567f,-0.0051451027393341064f,0.39627134799957275f,0.3181920051574707f,-0.05303953215479851f,0.1294034719467163f,0.16528914868831635f,0.07129872590303421f,0.7101694941520691f,0.34140077233314514f,1.623598575592041f,-0.06323867291212082f,0.27155500650405884f,-0.3865056037902832f,-0.30631402134895325f},
    {3.009206533432007f,-3.122997522354126f,0.21773302555084229f,0.7692314386367798f,2.249300003051758f,-2.275317907333374f,0.16514194011688232f,0.11058115214109421f,0.17132356762886047f,2.417614459991455f,-0.25413116812705994f,2.2743594646453857f,-0.25959381461143494f,0.8003392219543457f,-0.4132833778858185f,1.4499995708465576f},
    {-0.7179104089736938f,0.8526995182037354f,-0.2501986622810364f,-0.875395655632019f,-0.5985659956932068f,2.8744397163391113f,0.06014183163642883f,-0.8439451456069946f,-0.05617062747478485f,-0.640657901763916f,0.14294663071632385f,3.381211519241333f,-0.1638868898153305f,-0.2370987981557846f,-0.15618428587913513f,-0.7710326910018921f},
    {-0.5504567623138428f,0.25199615955352783f,-0.26619744300842285f,-0.08971554040908813f,-0.3043712079524994f,0.903326153755188f,-0.17925891280174255f,-0.6943695545196533f,-0.25526830554008484f,0.20558907091617584f,0.09723648428916931f,2.3618743419647217f,0.38060376048088074f,-0.1769549399614334f,0.04303058981895447f,-0.12222103029489517f},
    {0.06810358166694641f,0.17962348461151123f,0.10248100757598877f,-0.30372604727745056f,0.4354613721370697f,-0.7276828289031982f,-0.07246989011764526f,-0.6118704676628113f,-0.42743170261383057f,1.453460693359375f,-0.30540645122528076f,1.6834946870803833f,0.23858578503131866f,0.21455851197242737f,-0.30555272102355957f,0.8063939213752747f},
    {-0.0713198110461235f,-0.4495846927165985f,0.18462657928466797f,0.05500239133834839f,0.7719969153404236f,-1.2848507165908813f,-0.2990540862083435f,-0.22474081814289093f,-0.1015893891453743f,0.7663454413414001f,-0.016399379819631577f,-0.03539150580763817f,0.38201630115509033f,-0.09081173688173294f,0.3484981060028076f,0.7820040583610535f},
    {0.33533185720443726f,0.13371603190898895f,0.37182438373565674f,0.39484986662864685f,0.35771995782852173f,-1.3015228509902954f,-0.20339298248291016f,-0.14145439863204956f,-0.5059540271759033f,0.8015591502189636f,0.34025880694389343f,-0.6485148072242737f,-0.05657690018415451f,0.09265313297510147f,0.26688337326049805f,0.2284013032913208f},
    {-0.4380135238170624f,-0.15535405278205872f,-0.40320003032684326f,0.0452105812728405f,0.23505118489265442f,-0.8950125575065613f,0.1533789038658142f,0.1997886300086975f,-0.24218705296516418f,0.45601460337638855f,-0.42232224345207214f,-0.5756524205207825f,0.15488487482070923f,-0.013335001654922962f,0.10493969917297363f,0.23898905515670776f},
    {-0.02198643982410431f,0.009633726440370083f,0.19847965240478516f,0.0860355794429779f,0.336037278175354f,-0.277248352766037f,-0.2404318004846573f,-0.07731665670871735f,-0.2765587270259857f,-0.1708865910768509f,-0.11712735891342163f,-0.7335506677627563f,0.10241620987653732f,-0.06552530825138092f,-0.22268100082874298f,-0.13819573819637299f},
    {0.020149538293480873f,-0.03840681165456772f,0.4127817749977112f,-0.2523573637008667f,-0.21765978634357452f,-0.4540342092514038f,-0.32001304626464844f,-0.5396589040756226f,-0.21919101476669312f,-0.2550864815711975f,-0.20302052795886993f,-0.2918916642665863f,-0.3021690249443054f,-0.19007131457328796f,0.0479682981967926f,0.28083792328834534f},
    {0.19955825805664062f,0.13080951571464539f,0.20282304286956787f,-0.21126452088356018f,0.15339018404483795f,-0.06708966940641403f,0.04202890396118164f,0.06752092391252518f,0.25217023491859436f,-0.20238792896270752f,-0.2873592674732208f,-0.42253321409225464f,0.11435109376907349f,-0.2376958578824997f,0.0668090283870697f,0.04261681064963341f},
    {-0.03747318685054779f,-0.29164087772369385f,-0.40439701080322266f,-0.3783135414123535f,-0.40124887228012085f,-0.026558339595794678f,-0.15568238496780396f,-0.08766567707061768f,0.21709603071212769f,-0.35802650451660156f,-0.4817592203617096f,-0.3809756338596344f,-0.2601439654827118f,-0.1273980438709259f,-0.08245879411697388f,0.014104350470006466f},
    {0.16147102415561676f,-0.5628581643104553f,0.16706281900405884f,-0.1172998696565628f,-0.03297983109951019f,-0.9104568362236023f,-0.041414469480514526f,0.1465616226196289f,0.04248951002955437f,0.007101915311068296f,-0.3614332377910614f,-0.48312774300575256f,0.12316523492336273f,0.3939219117164612f,0.29427415132522583f,0.3038717210292816f},
};

const float h2[16][16] = {
    {0.33418041467666626f,2.9079723358154297f,-0.06966331601142883f,-0.009902028366923332f,2.812035322189331f,4.195849418640137f,-0.038234543055295944f,0.0904630720615387f,-0.43008196353912354f,-0.1415480375289917f,0.10707370936870575f,-0.20333009958267212f,-0.031739287078380585f,-3.289416551589966f,-1.172767996788025f,-0.6248859763145447f},
    {0.11070519685745239f,-2.3348469734191895f,0.057057321071624756f,-0.10134492069482803f,-5.252432346343994f,-1.3715343475341797f,-0.8426902890205383f,-0.2990124225616455f,-0.33757925033569336f,0.2895788848400116f,-7.361403465270996f,-0.858361005783081f,0.0845860168337822f,2.2169580459594727f,-3.0816471576690674f,-1.0190033912658691f},
    {-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.1391567885875702f,0.03293241187930107f,-0.2894435524940491f,0.25554025173187256f,0.08946844935417175f,0.1340968757867813f,-0.39087218046188354f,0.4122363030910492f,0.26211628317832947f,0.2953031361103058f,0.7025435566902161f,0.05798906087875366f,-0.5013425946235657f,-0.030901746824383736f,-0.06675297021865845f,-0.0446302704513073f},
    {-2.245600938796997f,1.6008015871047974f,-0.25313520431518555f,0.1469619870185852f,1.6072996854782104f,-1.3637473583221436f,-0.5957030653953552f,-0.08570799231529236f,-0.024399548768997192f,-0.39465832710266113f,-6.811410427093506f,-0.7977238893508911f,-0.022602174431085587f,-1.6454986333847046f,0.5441725850105286f,-0.7979243397712708f},
    {0.5210384130477905f,-0.11346126347780228f,-0.3519742488861084f,0.29306867718696594f,-0.3572634160518646f,1.75344979763031f,-0.744201123714447f,-0.019414573907852173f,-0.23047015070915222f,0.3579089343547821f,-2.398893117904663f,-0.48980283737182617f,-0.45957082509994507f,0.5487804412841797f,-0.7850930690765381f,-0.7663227319717407f},
    {-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.007747650612145662f,0.3667842745780945f,0.33083590865135193f,-0.38213321566581726f,-0.14358049631118774f,-0.2546055316925049f,-0.09043094515800476f,-0.3003333508968353f,0.2600560486316681f,-0.37898191809654236f,0.49078798294067383f,-0.3058888614177704f,-0.31673234701156616f,0.44664251804351807f,-0.9339061975479126f,-0.1061311885714531f},
    {-0.17694538831710815f,0.1767565757036209f,-0.11379697918891907f,-0.07116051763296127f,0.041274964809417725f,-0.517110288143158f,-0.10284432768821716f,0.0019084513187408447f,0.06103590130805969f,-0.38046833872795105f,-0.3456110656261444f,-0.24793067574501038f,-0.4166972041130066f,-0.30618393421173096f,-0.33565962314605713f,-0.48154377937316895f},
    {0.5043365359306335f,0.1850307136774063f,-0.13502129912376404f,-0.25706031918525696f,-0.8451530337333679f,-0.9415315389633179f,-0.2777014970779419f,-0.3632148504257202f,-0.13619378209114075f,0.16938945651054382f,1.5622152090072632f,-0.19312366843223572f,0.1250869333744049f,-0.1843482404947281f,1.0270578861236572f,-0.5840676426887512f},
    {-0.25693249702453613f,-0.010147050023078918f,0.0457797646522522f,-0.3549601435661316f,-0.03321319818496704f,-0.4391511380672455f,0.17873415350914001f,-0.20421427488327026f,-0.050184011459350586f,0.12480869889259338f,-0.22192376852035522f,0.3545852601528168f,-0.3647043704986572f,0.4194667637348175f,-0.3910166025161743f,-0.2837793529033661f},
    {2.3816981315612793f,0.4564768075942993f,0.3954955041408539f,0.11254638433456421f,1.1973353624343872f,1.804193377494812f,-0.8583166599273682f,-0.11795541644096375f,0.3487861454486847f,-0.32520344853401184f,-1.3897980451583862f,-0.5921090841293335f,-0.14213289320468903f,-0.26851770281791687f,1.597784161567688f,-0.5877130031585693f},
    {-0.267646849155426f,-0.20429572463035583f,-0.15798500180244446f,0.3999568819999695f,-0.37393757700920105f,0.35770177841186523f,0.11292675137519836f,-0.2947862446308136f,-0.3764709532260895f,0.2424570620059967f,-0.10294663906097412f,-0.2837170362472534f,0.41839322447776794f,-0.02792874164879322f,-0.13706544041633606f,0.11999254673719406f},
    {0.2282707840204239f,-0.13254989683628082f,-0.2018718123435974f,-0.07019486278295517f,0.07545611262321472f,-0.33204764127731323f,-0.4035329520702362f,-0.21416273713111877f,-0.24509364366531372f,0.19522181153297424f,0.47974857687950134f,-0.8069085478782654f,-0.40297332406044006f,0.23708327114582062f,0.5259239673614502f,-0.3548051416873932f},
    {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},
    {-0.5818981528282166f,0.014110059477388859f,0.12081471085548401f,-0.2973254919052124f,0.5392167568206787f,0.3773144781589508f,-0.39351940155029297f,0.31089308857917786f,-0.3893685042858124f,-0.02222958207130432f,-6.493835926055908f,-0.12242847681045532f,-0.2689415514469147f,-0.2518419325351715f,-0.1694900244474411f,-0.652117908000946f},
};

const float h3[16][16] = {
    {-0.36079341173171997f,-1.5671656131744385f,-0.870830237865448f,-0.4786093831062317f,-0.5575059056282043f,-0.773746132850647f,0.29977259039878845f,0.1743643879890442f,-0.5892294645309448f,-0.19605471193790436f,-0.27379146218299866f,0.06893575936555862f,2.2012624740600586f,-2.7650468349456787f,-1.8527313470840454f,1.5724681615829468f},
    {0.047732532024383545f,-0.23476845026016235f,-2.8836917877197266f,-0.42602431774139404f,-2.397148370742798f,1.254254937171936f,-0.3198729455471039f,-0.25123724341392517f,0.013695899397134781f,-0.5729482173919678f,0.09775999933481216f,-0.5587971806526184f,-0.9381403923034668f,-1.532671570777893f,-0.6944977045059204f,1.4258947372436523f},
    {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.16969707608222961f,0.3056027889251709f,-0.380797415971756f,-0.17742466926574707f,0.10660405457019806f,0.20021501183509827f,0.07002416253089905f,-0.25412267446517944f,-0.365601509809494f,0.13192829489707947f,0.41021624207496643f,-0.13397035002708435f,0.0815882533788681f,0.15073642134666443f,0.10944337397813797f},
    {-0.39607733488082886f,-0.05481579899787903f,0.1976260244846344f,0.022423356771469116f,0.16892847418785095f,-0.6999471187591553f,0.16012099385261536f,0.21129152178764343f,-0.08640444278717041f,-0.11053556203842163f,-0.2634495496749878f,-0.31317979097366333f,-0.1530032455921173f,-0.24679358303546906f,0.22959044575691223f,-3.0342295169830322f},
    {-0.37449589371681213f,-0.10077743977308273f,-4.51036262512207f,-0.04963836818933487f,-0.8192825317382812f,-0.6951172947883606f,-0.19780586659908295f,-0.09049295634031296f,-0.9114404916763306f,-0.8623005151748657f,-0.4059421718120575f,-0.16295623779296875f,-5.017462730407715f,-1.1079373359680176f,0.34683844447135925f,0.6427209377288818f},
    {0.4110594093799591f,0.2715781033039093f,-0.38537508249282837f,0.37246426939964294f,-0.05490662157535553f,-0.009114405140280724f,-0.08670487999916077f,-0.25336313247680664f,-0.030661463737487793f,-0.06259563565254211f,-0.1344406008720398f,0.35313835740089417f,-0.13377737998962402f,0.25604528188705444f,0.3126353323459625f,-0.1528691202402115f},
    {-0.40892091393470764f,0.043769627809524536f,-0.3867315948009491f,0.25968697667121887f,0.3424709737300873f,-0.051169753074645996f,-0.23312048614025116f,-0.390264093875885f,0.28059282898902893f,-0.1559126079082489f,-0.14134526252746582f,-0.0003446042537689209f,-0.2742875814437866f,-0.36560842394828796f,0.07994696497917175f,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.22762465476989746f,1.5232031345367432f,-0.2233445942401886f,1.524779200553894f,2.6997625827789307f,-0.08742031455039978f,0.05785742402076721f,-0.1277361363172531f,-0.37371426820755005f,-0.03133596479892731f,-0.30447322130203247f,-1.9101834297180176f,0.6954238414764404f,0.46117544174194336f,1.1762653589248657f},
    {-0.408692330121994f,0.07260357588529587f,-0.02147701010107994f,0.0922636091709137f,-0.1529182642698288f,-0.05657944083213806f,0.03285527229309082f,0.38763079047203064f,-0.20705322921276093f,-0.25883403420448303f,0.12809070944786072f,0.03996849060058594f,-0.6609845757484436f,-0.1087266057729721f,-0.10636871308088303f,-0.0133456289768219f},
    {-0.2991822361946106f,0.3794580399990082f,-0.08715943992137909f,-0.05932474136352539f,0.11478022485971451f,0.3007120192050934f,-0.11253207921981812f,0.34576353430747986f,0.04814547300338745f,-0.35770976543426514f,-0.044228196144104004f,-0.36229726672172546f,0.05380958318710327f,-0.13672849535942078f,0.35829514265060425f,-0.10585878044366837f},
    {-0.2675279378890991f,-0.1429223269224167f,-0.9267327189445496f,-0.1256239265203476f,0.49980443716049194f,-0.843601405620575f,-0.33532586693763733f,-0.31893211603164673f,-1.478386402130127f,-1.1926257610321045f,-0.5260127782821655f,-0.8384293913841248f,0.9772797226905823f,0.1813446283340454f,0.17612296342849731f,1.590701699256897f},
    {-0.015470266342163086f,-0.4976375699043274f,2.497199058532715f,0.14489558339118958f,0.11334121972322464f,0.3805958926677704f,0.02394937537610531f,-0.16103173792362213f,-0.677362859249115f,-0.8498573303222656f,-0.026575788855552673f,-0.427055299282074f,0.17177484929561615f,1.67837655544281f,0.08538639545440674f,-1.3552721738815308f},
    {0.1863725483417511f,0.13157431781291962f,-0.047772910445928574f,-0.49708226323127747f,0.7275430560112f,-0.145163431763649f,0.04860696196556091f,0.17769548296928406f,-0.050254471600055695f,0.19876523315906525f,-0.5504136085510254f,0.19592127203941345f,0.23928996920585632f,-0.12190091609954834f,-0.1250786930322647f,0.041962411254644394f},
};

const float hout[16] = { 0.45773375034332275f,0.5733839869499207f,-0.5152473449707031f,-0.035915032029151917f,-0.306951105594635f,0.30648893117904663f,-0.1005084440112114f,-0.08898112922906876f,-0.2034129500389099f,-0.05844772607088089f,-0.07081260532140732f,0.08596939593553543f,0.5426119565963745f,0.5678461194038391f,1.0715678930282593f,-0.25178417563438416f };

const float b1[16] = { 0.5956194400787354f,1.4903173446655273f,-1.7145336866378784f,0.2382747083902359f,1.812330722808838f,1.1310549974441528f,-0.058932315558195114f,1.0475828647613525f,0.5750831365585327f,-1.1691874265670776f,0.564017653465271f,0.8430382013320923f,-0.3627738058567047f,-0.8757394552230835f,-1.087764859199524f,1.8534502983093262f };

const float b2[16] = { -0.19254711270332336f,-1.2538373470306396f,-1.4564176797866821f,-0.6360846757888794f,-2.2159981727600098f,-0.5284036993980408f,0.07729385793209076f,-0.30969977378845215f,-1.20063054561615f,-1.912178635597229f,0.16195619106292725f,0.17741809785366058f,-0.3301374316215515f,1.8553483486175537f,-0.1654871553182602f,0.5861462950706482f };

const float b3[16] = { -1.963319182395935f,-0.5293647646903992f,-0.10495924949645996f,-0.23769626021385193f,1.5550658702850342f,1.2147407531738281f,-0.47398853302001953f,-0.9554895758628845f,-0.067354217171669f,-0.006115084979683161f,-0.45877549052238464f,-0.290895938873291f,-1.0047727823257446f,1.1215981245040894f,-1.407442569732666f,-1.6007274389266968f };

const float bout[1] = { -0.10839174687862396f };

/////////////////////////////////////////////////////////////////////////////////////////////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);


float Critic_Network(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[index1][index2] * arr[index1];
        }
        //ReLU
        output1[index2] = output1[index2] + bc1[index2];
        hx_c_sum[index2] = output1[index2];
        if (output1[index2] < 0) {
            output1[index2] = 0;
        }
        //tanh
        //output1[index2] = tanh(output1[index2] + bc1[index2]);
    }
    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
            output2[index2] = output2[index2] + hc2[index1][index2] * arr[index1];
        }
        //ReLU
        output2[index2] = output2[index2] + bc2[index2];
        hxh_c_sum[index2] = output2[index2];
        if (output2[index2] < 0) {
            output2[index2] = 0;
        }
        //tanh
        //output2[index2] = tanh(output2[index2] + bc2[index2]);
    }
    for (int index2 = 0; index2 < 1; index2++) {
        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
            output = output + hc3[index1] * output2[index1];
        }
        output = output + bc3;
        hxhh_c_sum = output;
    }
    return output;
}

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] * arr[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[index1][index2] * arr[index1];
        }
        output1[index2] = output1[index2] + ba1[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[index1][index2] * arr[index1];
        }
        output2[index2] = output2[index2] + ba2[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[index1][index2] * output2[index1];
        }
    }
    hxhh_a_sum[0] = output[0] + ba3[0];
    hxhh_a_sum[1] = output[1] + ba3[1];

    mean_before_SP = output[0] + ba3[0];    //SP = softplus
    deviation_before_SP = output[1] + ba3[1];
    //Softplus
    mean = log(1.0f+exp(mean_before_SP));
    deviation = log(1.0f+exp(deviation_before_SP));
}


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] * arr[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 gradient_rate = 0.001f;
//    float hx_sum = 0.0f;


    ///////////////////////////////////////////////////////////CRITIC
    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++) {
                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) {
                            G_hc1[index1][index2] = G_hc1[index1][index2] + arr[n][index1]*hc2_temp[index2][k]*hc3_temp[k];
                        }
                    }
                }
            }
            G_hc1[index1][index2] = G_hc1[index1][index2] / batch_size;
            //hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate * G_hc1[index1][index2];
        }
        for (int n=0; n<batch_size; n++) {
            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) {
                        G_bc1[index2] = G_bc1[index2] + hc2_temp[index2][k]*hc3_temp[k];
                    }

                }
            }
        }
        G_bc1[index2] = G_bc1[index2] / batch_size;
        //bc1_temp[index2] = bc1_temp[index2] - gradient_rate * 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++) {
                if (hxh_c_sum_array[n][index2] >= 0) {
                    if (hx_c_sum_array[n][index1] > 0) {
                        G_hc2[index1][index2] = G_hc2[index1][index2] + hx_c_sum_array[n][index1]*hc3_temp[index2];
                    }
                }
            }
            G_hc2[index1][index2] = G_hc2[index1][index2] / batch_size;
            //hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate * G_hc2[index1][index2];
        }
        for (int n=0; n<batch_size; n++) {
            if (hxh_c_sum_array[n][index2] >= 0) {
                G_bc2[index2] = G_bc2[index2] + hc3_temp[index2];
            }
        }
        G_bc2[index2] = G_bc2[index2] / batch_size;
        //bc2_temp[index2] = bc2_temp[index2] - gradient_rate * 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++) {
                if (hxh_c_sum_array[n][index1] >= 0) {
                    G_hc3[index1] = G_hc3[index1] + hxh_c_sum_array[n][index1];
                }
            }
            G_hc3[index1] = G_hc3[index1] / batch_size;
            //hc3_temp[index1] = hc3_temp[index1] - gradient_rate * G_hc3[index1];
        }
        for (int n=0; n<batch_size; n++) {
            G_bc2[index2] = G_bc2[index2] + 1.0f;
        }
        G_bc3 = G_bc3 / batch_size;
        //bc3_temp = bc3_temp - gradient_rate * 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 * G_hc1[index1][index2];
        }
        bc1_temp[index2] = bc1_temp[index2] - gradient_rate * 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 * G_hc2[index1][index2];
        }
        bc2_temp[index2] = bc2_temp[index2] - gradient_rate * 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 * G_hc3[index1];
        }
        bc3_temp = bc3_temp - gradient_rate * G_bc3;
    }

}

///////////////////////////Softplus//////////////////////////////////
void update_Actor_Networks(float (*arr)[num_input_RL])
{
    float gradient_rate = 0.001f;

    float G_ha1[num_input_RL][num_hidden_unit1] = {0.0f};
    float G_ba1[num_hidden_unit1] = {0.0f};
    float d_x_d_ha1[num_input_RL][num_hidden_unit1] = {0.0f};
    float d_x_d_ba1[num_hidden_unit1] = {0.0f};
    float d_y_d_ha1[num_input_RL][num_hidden_unit1] = {0.0f};
    float d_y_d_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++) {
                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[index1][index2] = d_x_d_ha1[index1][index2] + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][0];
                                d_y_d_ha1[index1][index2] = d_y_d_ha1[index1][index2] + 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[index1][index2];
                    d_dev_d_ha1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha1[index1][index2];

                    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;
            ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate * G_ha1[index1][index2];
        }

        for (int n=0; n<batch_size; n++) {
            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[index2] = d_x_d_ba1[index2] + ha2_temp[index2][k]*ha3_temp[k][0];
                            d_y_d_ba1[index2] = d_y_d_ba1[index2] + 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[index2];
                d_dev_d_ba1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba1[index2];

                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;
        ba1_temp[index2] = ba1_temp[index2] - gradient_rate * G_ba1[index2];
    }

    float G_ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
    float G_ba2[num_hidden_unit2] = {0.0f};
    float d_x_d_ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
    float d_x_d_ba2[num_hidden_unit2] = {0.0f};
    float d_y_d_ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
    float d_y_d_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++) {
                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[index1][index2] = d_x_d_ha2[index1][index2] + hx_a_sum_array[n][index1]*ha3_temp[index2][0];
                            d_y_d_ha2[index1][index2] = d_y_d_ha2[index1][index2] + 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[index1][index2];
                    d_dev_d_ha2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha2[index1][index2];

                    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;
            ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate * G_ha2[index1][index2];
        }

        for (int n=0; n<batch_size; n++) {
            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[index2] = d_x_d_ba2[index2] + ha3_temp[index2][0];
                    d_y_d_ba2[index2] = d_y_d_ba2[index2] + 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[index2];
                d_dev_d_ba2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba2[index2];

                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;
        ba2_temp[index2] = ba2_temp[index2] - gradient_rate * G_ba2[index2];
    }

    float G_ha3[num_hidden_unit2][2] = {0.0f};
    float G_ba3[2] = {0.0f};
    float d_x_d_ha3[num_hidden_unit2][2] = {0.0f};
    float d_x_d_ba3[2] = {0.0f};
    float d_y_d_ha3[num_hidden_unit2][2] = {0.0f};
    float d_y_d_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++) {
                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[index1][index2] = d_x_d_ha3[index1][index2] + hxh_a_sum_array[n][index1];
                            d_y_d_ha3[index1][index2] = d_y_d_ha3[index1][index2] + 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[index1][index2];
                    d_dev_d_ha3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha3[index1][index2];

                    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;
            ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate * G_ha3[index1][index2];
        }

        for (int n=0; n<batch_size; n++) {
            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[index2] = d_x_d_ba3[index2] + 1.0f;
                d_y_d_ba3[index2] = d_y_d_ba3[index2] + 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[index2];
                d_dev_d_ba3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba3[index2];

                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;
        ba3_temp[index2] = ba3_temp[index2] - gradient_rate * G_ba3[index2];
    }
}

///////////////////////////ReLU - Bad performance//////////////////////////////////
//void update_Actor_Networks(float (*arr)[num_input_RL])
//{
//    float gradient_rate = 0.001f;   //-0.01f
//
//    float G_ha1[num_input_RL][num_hidden_unit] = {0.0f};
//    float G_ba1[num_hidden_unit] = {0.0f};
//    for (int index2 = 0; index2 < num_hidden_unit; index2++) {
//        for (int index1 = 0; index1 < num_input_RL; index1++) {
//            for (int i=0; i<batch_size; i++) {
//                if((advantage[i] >= 0.0f && ratio[i] >= 1.0f + epsilon) || (advantage[i] < 0.0f && ratio[i] < 1.0f - epsilon)) {
//                    G_ha1[index1][index2] = G_ha1[index1][index2];
//                } else {
//
//                    float hx_sum_total = 0.0f;
//                    for(int m = 0; m < num_hidden_unit; m++) {
//                        for(int n = 0; n < num_input_RL; n++) {
//                            hx_sum_total = hx_sum_total + ha1_temp[n][m]*arr[i][n];
//                        }
//                    }
//                    hx_sum_total = hx_sum_total + bc1_temp[index2];
//                    float d_mean_d_ha1 = 0.0f;
//                    float d_dev_d_ha1 = 0.0f;
//                    if (hx_sum_total >=0) {
//                        float hx_sum = 0.0f;
//                        for(int j=0; j<num_input_RL; j++) {
//                            hx_sum = hx_sum + ha1_temp[j][index2]*arr[i][j];
//                        }
//                        hx_sum = hx_sum + bc1_temp[index2];
//                        if (hx_sum >= 0) {
//                            d_mean_d_ha1 = ha2_temp[index2][0]*arr[i][index1];
//                            d_dev_d_ha1 = ha2_temp[index2][1]*arr[i][index1];
//                        } else {
//                            d_mean_d_ha1 = 0.0f;
//                            d_dev_d_ha1 = 0.0f;
//                        }
//                    } else {
//                        d_mean_d_ha1 = 0.0f;
//                        d_dev_d_ha1 = 0.0f;
//                    }
//                    G_ha1[index1][index2] = G_ha1[index1][index2] + advantage[i]/pi_old[i]*(d_mean_d_ha1*Grad_Normal_Dist_Mean(mean_array[i],deviation_array[i],action_array[i])+d_dev_d_ha1*Grad_Normal_Dist_Deviation(mean_array[i],deviation_array[i],action_array[i]));
//                }
//            }
//            G_ha1[index1][index2] = G_ha1[index1][index2] / batch_size;
//            ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate * G_ha1[index1][index2];
//        }
//        for (int i=0; i<batch_size; i++) {
//            if((advantage[i] >= 0.0f && ratio[i] >= 1.0f + epsilon) || (advantage[i] < 0.0f && ratio[i] < 1.0f - epsilon))  {
//                G_ba1[index2] = G_ba1[index2];
//            } else {
//
//                float hx_sum_total = 0.0f;
//                for(int m = 0; m < num_hidden_unit; m++) {
//                    for(int n = 0; n < num_input_RL; n++) {
//                        hx_sum_total = hx_sum_total + ha1_temp[n][m]*arr[i][n];
//                    }
//                }
//                hx_sum_total = hx_sum_total + bc1_temp[index2];
//                float d_mean_d_ba1 = 0.0f;
//                float d_dev_d_ba1 = 0.0f;
//                if (hx_sum_total >=0) {
//
//                    float hx_sum = 0.0f;
//                    for(int j=0; j<num_input_RL; j++) {
//                        hx_sum = hx_sum + ha1_temp[j][index2]*arr[i][j];
//                    }
//                    hx_sum = hx_sum + bc1_temp[index2];
//
//                    if(hx_sum >=0) {
//                        d_mean_d_ba1 = ha2_temp[index2][0];
//                        d_dev_d_ba1 = ha2_temp[index2][1];
//                    } else {
//                        d_mean_d_ba1 = 0.0f;
//                        d_dev_d_ba1 = 0.0f;
//                    }
//                } else {
//                    d_mean_d_ba1 = 0.0f;
//                    d_dev_d_ba1 = 0.0f;
//                }
//                G_ba1[index2] = G_ba1[index2] + advantage[i]/pi_old[i]*(d_mean_d_ba1*Grad_Normal_Dist_Mean(mean_array[i],deviation_array[i],action_array[i])+d_dev_d_ba1*Grad_Normal_Dist_Deviation(mean_array[i],deviation_array[i],action_array[i]));
//            }
//        }
//        G_ba1[index2] = G_ba1[index2] / batch_size;
//        ba1_temp[index2] = ba1_temp[index2] - gradient_rate * G_ba1[index2];
//    }
//
//    float G_ha2[num_hidden_unit][2] = {0.0f};
//    float G_ba2[2] = {0.0f};
//    for (int index2 = 0; index2 < 2; index2++) {
//        for (int index1 = 0; index1 < num_hidden_unit; index1++) {
//            for (int i=0; i<batch_size; i++) {
//                if((advantage[i] >= 0.0f && ratio[i] >= 1.0f + epsilon) || (advantage[i] < 0.0f && ratio[i] < 1.0f - epsilon)) {
//                    G_ha2[index1][index2] = G_ha2[index1][index2];
//                } else {
//
//                    float hx_sum_total = 0.0f;
//                    for(int m = 0; m < num_hidden_unit; m++) {
//                        for(int n = 0; n < num_input_RL; n++) {
//                            hx_sum_total = hx_sum_total + ha1_temp[n][m]*arr[i][n];
//                        }
//                    }
//                    hx_sum_total = hx_sum_total + bc1_temp[index2];
//                    float d_mean_d_ha2 = 0.0f;
//                    float d_dev_d_ha2 = 0.0f;
//                    if (hx_sum_total >=0) {
//                        float hx_sum = 0.0f;
//                        for(int j=0; j<num_input_RL; j++) {
//                            hx_sum = hx_sum + ha1_temp[j][index1]*arr[i][j];
//                        }
//                        hx_sum = hx_sum + bc1_temp[index1];
//                        if (hx_sum >= 0) {
//                            d_mean_d_ha2 = hx_sum;
//                            d_dev_d_ha2 = hx_sum;
//                        } else {
//                            d_mean_d_ha2 = 0.0f;
//                            d_mean_d_ha2 = 0.0f;
//                        }
//                    } else {
//                        d_mean_d_ha2 = 0.0f;
//                        d_mean_d_ha2 = 0.0f;
//                    }
//                    G_ha2[index1][index2] = G_ha2[index1][index2] + advantage[i]/pi_old[i]*(d_mean_d_ha2*Grad_Normal_Dist_Mean(mean_array[i],deviation_array[i],action_array[i])+d_dev_d_ha2*Grad_Normal_Dist_Deviation(mean_array[i],deviation_array[i],action_array[i]));
//                }
//            }
//            G_ha2[index1][index2] = G_ha2[index1][index2] / batch_size;
//            ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate * G_ha2[index1][index2];
//        }
//        for (int i=0; i<batch_size; i++) {
//            if((advantage[i] >= 0.0f && ratio[i] >= 1.0f + epsilon) || (advantage[i] < 0.0f && ratio[i] < 1.0f - epsilon))  {
//                G_ba2[index2] = G_ba2[index2];
//            } else {
//
//                float d_mean_d_ba2 = 0.0f;
//                float d_dev_d_ba2 = 0.0f;
//                d_mean_d_ba2 = 1.0f;
//                d_dev_d_ba2 = 1.0f;
//                G_ba1[index2] = G_ba1[index2] + advantage[i]/pi_old[i]*(d_mean_d_ba2*Grad_Normal_Dist_Mean(mean_array[i],deviation_array[i],action_array[i])+d_dev_d_ba2*Grad_Normal_Dist_Deviation(mean_array[i],deviation_array[i],action_array[i]));
//            }
//        }
//        G_ba2[index2] = G_ba2[index2] / batch_size;
//        ba2_temp[index2] = ba2_temp[index2] - gradient_rate * G_ba2[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;
    }
}


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
    *********************************/
    LED = 0;
    pc.baud(9600);

    // i2c init
    i2c.frequency(400 * 1000);          // 0.4 mHz
    wait_ms(2);                         // Power Up wait
    look_for_hardware_i2c();            // Hardware present
    init_as5510(i2c_slave_addr1);
    make_delay();

//    // spi init
    eeprom.format(8,3);
    eeprom.frequency(5000000); //5M
    enc.format(8,0);
    enc.frequency(5000000); //5M
    make_delay();

    //rom
    ROM_CALL_DATA();
    make_delay();

    // ADC init
    Init_ADC();
    make_delay();

    // Pwm init
    Init_PWM();
    TIM4->CR1 ^= TIM_CR1_UDIS;
    make_delay();

    // TMR3 init
    Init_TMR3();
    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();
    make_delay();

    //Timer priority
    NVIC_SetPriority(TIM3_IRQn, 2);
    //NVIC_SetPriority(TIM2_IRQn, 3);
    NVIC_SetPriority(TIM4_IRQn, 3);

    //can.reset();
    can.filter(msg.id, 0xFFFFF000, CANStandard);

    // spi _ enc
    spi_enc_set_init();
    make_delay();

    //DAC init
    if (SENSING_MODE == 0) {
        dac_1 = TORQUE_VREF / 3.3f;
        dac_2 = 0.0f;
    } else if (SENSING_MODE == 1) {
        dac_1 = PRES_A_VREF / 3.3f;
        dac_2 = PRES_B_VREF / 3.3f;
    }
    make_delay();

    for (int i=0; i<50; i++) {
        if(i%2==0)
            ID_index_array[i] = - i * 0.5f;
        else
            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.01f ;
        }
        bc1_temp[index2] = (float) (rand()%100) * 0.01f;
    }
    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.01f;
        }
        bc2[index2] = (float) (rand()%100) * 0.01f;
        hc3[index2] = (float) (rand()%100) * 0.01f;
    }
    bc3 = (float) (rand()%100) * 0.01f;

    for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
        for (int index1 = 0; index1 < num_input_RL; index1++) {
            ha1[index1][index2] = (float) (rand()%100) * 0.01f;
        }
        ba1[index2] = (float) (rand()%100) * 0.01f;
    }
    for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
        for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
            ha2[index1][index2] = (float) (rand()%100) * 0.01f;
        }
        ba2[index2] = (float) (rand()%100) * 0.01f;
    }
    for (int index2 = 0; index2 < 2; index2++) {
        for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
            ha3[index1][index2] = (float) (rand()%100) * 0.01f;
        }
        ba3[index2] = (float) (rand()%100) * 0.01f;
    }

    Overwirte_Critic_Networks();
    Overwirte_Actor_Networks();

    /************************************
    ***     Program is operating!
    *************************************/
    while(1) {

//        if(timer_while==27491) {
//            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);
//        }


        //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 + 0.5f;
                ind = ind + 1;
            }
            input_NN[ind] = torq.sen / 10000.0f + 0.5f;
            ind = ind + 1;
            for(int i=0; i<numfuture_f; i++) {
//                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+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];

            }
            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 i=batch_size-1; i>=0; i--) {
                        //Calculate Estimated V
                        //float temp_array[3] = {state_array[i][0], state_array[i][1], state_array[i][2]};
                        float temp_array[2] = {state_array[i][0], state_array[i][1]};
                        V[i] = Critic_Network_Temp(temp_array);
                        for (int i=0; i<num_hidden_unit1; i++) {
                            hx_c_sum_array[RL_timer][i] = hx_c_sum[i];
                        }
                        for (int i=0; i<num_hidden_unit2; i++) {
                            hxh_c_sum_array[RL_timer][i] = hxh_c_sum[i];
                        }
                        hxhh_c_sum_array[RL_timer] = hxhh_c_sum;
                        pi[i] = exp(-(action_array[i]-mean_array[i])*(action_array[i]-mean_array[i])/(2.0f*deviation_array[i]*deviation_array[i]))/(sqrt(2.0f*PI)*deviation_array[i]);
                        Actor_Network_Old(temp_array);
                        pi_old[i] = exp(-(action_array[i]-mean_old)*(action_array[i]-mean_old)/(2.0f*deviation_old*deviation_old))/(sqrt(2.0f*PI)*deviation_old);
                        r[i] = exp(-0.25f * state_array[i][1] * state_array[i][1]);
                        if(i == batch_size-1) return_G[i] = 0.0f;
                        else return_G[i] = gamma * return_G[i+1] + r[i];
                        if(i == batch_size-1) td_target[i] = r[i];
                        else td_target[i] = r[i] + gamma * V[i+1];
                        delta[i] = td_target[i] - V[i];
                        if(i == batch_size-1) advantage[i] = 0.0f;
                        else advantage[i] = gamma * lmbda * advantage[i+1] + delta[i];
                        ratio[i] = pi[i]/pi_old[i];
                        surr1[i] = ratio[i] * advantage[i];
                        if (ratio[i] > 1.0f + epsilon) {
                            surr2[i] = (1.0f + epsilon)*advantage[i];
                        } else if( ratio[i] < 1.0f - epsilon) {
                            surr2[i] = (1.0f - epsilon)*advantage[i];
                        } else {
                            surr2[i] = ratio[i]*advantage[i];
                        }
                        loss[i] = -min(surr1[i], surr2[i]);
                        loss_sum = loss_sum + loss[i];
                    }
                    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);
                }
                //virt_pos = 10.0f;
                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;
            }

        }
    }
}

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++) {
        if(REF_JOINT_VEL >= min(JOINT_VEL[i],JOINT_VEL[i+1]) && REF_JOINT_VEL <=  max(JOINT_VEL[i],JOINT_VEL[i+1])) {
            if(i==0) {
                if(JOINT_VEL[i+1] == JOINT_VEL[i]) {
                    Ref_Valve_Pos_FF = (float) VALVE_CENTER;
                } else {
                    Ref_Valve_Pos_FF = ((float) 10/(JOINT_VEL[i+1] - JOINT_VEL[i]) * (REF_JOINT_VEL - JOINT_VEL[i])) + (float) VALVE_CENTER;
                }
            } else {
                if(JOINT_VEL[i+1] == JOINT_VEL[i-1]) {
                    Ref_Valve_Pos_FF = (float) VALVE_CENTER;
                } else {
                    Ref_Valve_Pos_FF = ((float) 10*(ID_index_array[i+1] - ID_index_array[i-1])/(JOINT_VEL[i+1] - JOINT_VEL[i-1]) * (REF_JOINT_VEL - JOINT_VEL[i-1])) + (float) VALVE_CENTER + (float) (10*ID_index_array[i-1]);
                }
            }
            break;
        }
    }
    if(REF_JOINT_VEL > max(JOINT_VEL[VALVE_POS_NUM-1], JOINT_VEL[VALVE_POS_NUM-2])) {
        Ref_Valve_Pos_FF = (float) VALVE_MAX_POS;
    } else if(REF_JOINT_VEL < min(JOINT_VEL[VALVE_POS_NUM-1], JOINT_VEL[VALVE_POS_NUM-2])) {
        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);
    return Ref_Valve_Pos_FF;

}


void VALVE_POS_CONTROL(float REF_VALVE_POS)
{
    int i = 0;

    if(REF_VALVE_POS > VALVE_MAX_POS) {
        REF_VALVE_POS = VALVE_MAX_POS;
    } 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;
    valve_pos_err_sum += valve_pos_err;
    if (valve_pos_err_sum > 1000.0f) valve_pos_err_sum = 1000.0f;
    if (valve_pos_err_sum<-1000.0f) valve_pos_err_sum = -1000.0f;

    VALVE_PWM_RAW_FB = P_GAIN_VALVE_POSITION * valve_pos_err + I_GAIN_VALVE_POSITION * valve_pos_err_sum + D_GAIN_VALVE_POSITION * valve_pos_err_diff;

    for(i=0; i<24; i++) {
        if(REF_VALVE_POS >= min(VALVE_POS_VS_PWM[i],VALVE_POS_VS_PWM[i+1]) && (float) REF_VALVE_POS <=  max(VALVE_POS_VS_PWM[i],VALVE_POS_VS_PWM[i+1])) {
            if(i==0) {
                VALVE_PWM_RAW_FF = (float) 1000.0f / (float) (VALVE_POS_VS_PWM[i+1] - VALVE_POS_VS_PWM[i]) * ((float) REF_VALVE_POS - VALVE_POS_VS_PWM[i]);
            } else {
                VALVE_PWM_RAW_FF = (float) 1000.0f* (float) (ID_index_array[i+1] - ID_index_array[i-1])/(VALVE_POS_VS_PWM[i+1] - VALVE_POS_VS_PWM[i-1]) * ((float) REF_VALVE_POS - VALVE_POS_VS_PWM[i-1]) + 1000.0f * (float) ID_index_array[i-1];
            }
            break;
        }
    }
    Vout.ref = VALVE_PWM_RAW_FF + VALVE_PWM_RAW_FB;
}

#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,
                                 -9.0f, -8.0f, -7.0f, -6.0f, -5.0f, -4.0f, -3.0f, -2.0f, -1.0f, 0.0f,
                                 1.0f, 2.0f, 3.0f, 4.0f, 5.0f, 6.0f, 7.0f, 8.0f, 9.0f, 10.0f,
                                 11.0f, 12.0f, 13.0f, 14.0f, 15.0f, 16.0f, 17.0f, 18.0f, 19.0f, 20.0f,
                                 25.0f, 30.0f, 35.0f, 40.0f, 50.0f, 60.0f, 80.0f, 100.0f
                                };  // duty
float LT_Voltage_Output[LT_MAX_IDX] = {-230.0f, -215.0f, -192.5f, -185.0f, -177.5f, -170.0f, -164.0f, -160.0f, -150.0f,
                                       -150.0f, -145.0f, -145.0f, -145.0f, -135.0f, -135.0f, -135.0f, -127.5f, -127.5f, -115.0f,
                                       -115.0f, -115.0F, -100.0f, -100.0f, -100.0f, -60.0f, -60.0f, -10.0f, -5.0f, 0.0f,
                                       7.5f, 14.0f, 14.0f, 14.0f, 42.5f, 42.5f, 42.5f, 80.0f, 80.0f, 105.0f,
                                       105.0f, 105.0f, 120.0f, 120.0f, 120.0f, 131.0f, 131.0f, 140.0f, 140.0f, 140.0f,
                                       155.0f, 160.0f, 170.0f, 174.0f, 182.0f, 191.0f, 212.0f, 230.0f
                                      }; // mV

float PWM_duty_byLT(float Ref_V)
{
    float PWM_duty = 0.0f;
    if(Ref_V<LT_Voltage_Output[0]) {
        PWM_duty = (Ref_V-LT_Voltage_Output[0])/1.5f+LT_PWM_duty[0];
    } else if (Ref_V>=LT_Voltage_Output[LT_MAX_IDX-1]) {
        PWM_duty = (Ref_V-LT_Voltage_Output[LT_MAX_IDX-1])/1.5f+LT_PWM_duty[LT_MAX_IDX-1];
    } else {
        int idx = 0;
        for(idx=0; idx<LT_MAX_IDX-1; idx++) {
            float ini_x = LT_Voltage_Output[idx];
            float fin_x = LT_Voltage_Output[idx+1];
            float ini_y = LT_PWM_duty[idx];
            float fin_y = LT_PWM_duty[idx+1];
            if(Ref_V>=ini_x && Ref_V<fin_x) {
                PWM_duty = (fin_y-ini_y)/(fin_x-ini_x)*(Ref_V-ini_x) + ini_y;
                break;
            }
        }
    }

    return PWM_duty;
}





/*******************************************************************************
                            TIMER INTERRUPT
*******************************************************************************/

float FREQ_TMR4 = (float)FREQ_20k;
float DT_TMR4 = (float)DT_20k;
long  CNT_TMR4 = 0;
int   TMR4_FREQ_10k = (int)FREQ_10k;
extern "C" void TIM4_IRQHandler(void)
{
    if (TIM4->SR & TIM_SR_UIF ) {

        /*******************************************************
        ***     Sensor Read & Data Handling
        ********************************************************/

        //Encoder
        if (CNT_TMR4 % (int) ((int) FREQ_TMR4/TMR4_FREQ_10k) == 0) {
            ENC_UPDATE();
        }

        ADC1->CR2  |= 0x40000000;
        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
            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


        } 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
            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;
            CUR_PRES_B_BAR = pres_B.sen / PRES_SENSOR_B_PULSE_PER_BAR;

            if ((OPERATING_MODE & 0x01) == 0) { // Rotary Actuator
                torq.sen = (PISTON_AREA_A * CUR_PRES_A_BAR - PISTON_AREA_B * CUR_PRES_B_BAR) * 0.0001f; // mm^3*bar >> Nm
            } else if ((OPERATING_MODE & 0x01) == 1) { // Linear Actuator
                torq.sen = (PISTON_AREA_A * CUR_PRES_A_BAR - PISTON_AREA_B * CUR_PRES_B_BAR) * 0.1f; // mm^2*bar >> N
            }
        }

//        //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++;
    }
    TIM4->SR = 0x0;  // reset the status register
}


int j =0;
float FREQ_TMR3 = (float)FREQ_5k;
float DT_TMR3 = (float)DT_5k;
int cnt_trans = 0;
double VALVE_POS_RAW_FORCE_FB_LOGGING = 0.0f;
int can_rest =0;

extern "C" void TIM3_IRQHandler(void)
{
    if (TIM3->SR & TIM_SR_UIF ) {

        if (((OPERATING_MODE&0b110)>>1) == 0) {
            K_v = 0.4f; // Moog (LPM >> mA) , 100bar
            mV_PER_mA = 500.0f; // 5000mV/10mA
            mV_PER_pulse = 0.5f; // 5000mV/10000pulse
            mA_PER_pulse = 0.001f; // 10mA/10000pulse
        } else if (((OPERATING_MODE&0b110)>>1) == 1) {
            K_v = 0.5f; // KNR (LPM >> mA) , 100bar
            mV_PER_mA = 166.6666f; // 5000mV/30mA
            mV_PER_pulse = 0.5f; // 5000mV/10000pulse
            mA_PER_pulse = 0.003f; // 30mA/10000pulse
        }

        if(MODE_POS_FT_TRANS == 1) {
            alpha_trans = (float)(1.0f - cos(3.141592f * (float)cnt_trans * DT_TMR3 /3.0f))/2.0f;
            cnt_trans++;
            torq.err_sum = 0;
            if((float)cnt_trans * DT_TMR3 > 3.0f)
                MODE_POS_FT_TRANS = 2;
        } else if(MODE_POS_FT_TRANS == 3) {
            alpha_trans = (float)(1.0f + cos(3.141592f * (float)cnt_trans * DT_TMR3 /3.0f))/2.0f;
            cnt_trans++;
            torq.err_sum = 0;
            if((float) cnt_trans * DT_TMR3 > 3.0f )
                MODE_POS_FT_TRANS = 0;
        } else if(MODE_POS_FT_TRANS == 2) {
            alpha_trans = 1.0f;
            cnt_trans = 0;
        } else {
            alpha_trans = 0.0f;
            cnt_trans = 0;
        }


        int UTILITY_MODE = 0;
        int CONTROL_MODE = 0;

        if (CONTROL_UTILITY_MODE >= 20 || CONTROL_UTILITY_MODE == 0) {
            UTILITY_MODE = CONTROL_UTILITY_MODE;
            CONTROL_MODE = MODE_NO_ACT;
        } else {
            CONTROL_MODE = CONTROL_UTILITY_MODE;
            UTILITY_MODE = MODE_NO_ACT;
        }



        // UTILITY MODE ------------------------------------------------------------

        switch (UTILITY_MODE) {
            case MODE_NO_ACT: {
                break;
            }

            case MODE_TORQUE_SENSOR_NULLING: {
                // DAC Voltage reference set
                if (TMR3_COUNT_TORQUE_NULL < TMR_FREQ_5k * 2) {
                    CUR_TORQUE_sum += torq.sen;

                    if (TMR3_COUNT_TORQUE_NULL % 10 == 0) {
                        CUR_TORQUE_mean = CUR_TORQUE_sum / 10.0f;
                        CUR_TORQUE_sum = 0;

                        TORQUE_VREF += 0.000003f * (0.0f - CUR_TORQUE_mean);

                        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 {
                    CONTROL_UTILITY_MODE = MODE_NO_ACT;
                    TMR3_COUNT_TORQUE_NULL = 0;
                    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;

                }
                TMR3_COUNT_TORQUE_NULL++;
                break;
            }

//            case MODE_VALVE_NULLING_AND_DEADZONE_SETTING: {
//                if (TMR3_COUNT_DEADZONE == 0) {
//                    if (pos_plus_end == pos_minus_end) need_enc_init = true;
//                    else temp_time = 0;
//                }
//                if (need_enc_init) {
//                    if (TMR3_COUNT_DEADZONE < (int) (0.5f * (float) TMR_FREQ_5k)) {
//                        V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
//                        pos_plus_end = pos.sen;
//                    } else if (TMR3_COUNT_DEADZONE < TMR_FREQ_5k) {
//                        V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
//                        pos_minus_end = pos.sen;
//                    } else if (TMR3_COUNT_DEADZONE == TMR_FREQ_5k) need_enc_init = false;
//                    temp_time = TMR_FREQ_5k;
//                }
//
//                if (temp_time <= TMR3_COUNT_DEADZONE && TMR3_COUNT_DEADZONE < (temp_time + 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);
//                    VALVE_CENTER = VALVE_DEADZONE_PLUS = VALVE_DEADZONE_MINUS = 0;
//
//                } else if (temp_time <= TMR3_COUNT_DEADZONE && TMR3_COUNT_DEADZONE < (temp_time + (int) (1.9f * (float) TMR_FREQ_5k))) {
//                    V_out = 0;
//                    CUR_VELOCITY_sum += CUR_VELOCITY;
//                } else if (TMR3_COUNT_DEADZONE == (temp_time + 2 * TMR_FREQ_5k)) {
//                    if (CUR_VELOCITY_sum == 0) DZ_dir = 1;
//                    else if (CUR_VELOCITY_sum > 0) DZ_dir = 1;
//                    else if (CUR_VELOCITY_sum < 0) DZ_dir = -1;
//                    else DZ_temp_cnt2 = DZ_end;
//                    CUR_VELOCITY_sum = 0;
//                } else if (TMR3_COUNT_DEADZONE > (temp_time + 2 * TMR_FREQ_5k)) {
//                    if (TMR3_COUNT_DEADZONE > (temp_time + 10 * TMR_FREQ_5k)) DZ_temp_cnt2 = DZ_end;
//
//                    // Position of Dead Zone
//                    //  (CUR_VELOCITY < 0)  (CUR_VELOCITY == 0)  (CUR_VELOCITY > 0)
//                    //     |        /                 |    /                      |/
//                    //     | ______/               ___|___/                ______/|
//                    //     |/                     /   |                   /       |
//                    //    /|                     /    |                  /        |
//                    //     0V                         0V                          0V
//
//                    if (DZ_temp_cnt2 < DZ_end) {
//                        if (TMR3_COUNT_DEADZONE % 20 != 0) {
//                            CUR_VELOCITY_sum += CUR_VELOCITY;
//                        } else {
//                            V_out -= DZ_dir;
//                            if (CUR_VELOCITY_sum * DZ_dir < 0) DZ_temp_cnt++;
//                            CUR_VELOCITY_sum = 0;
//                        }
//                        if (DZ_temp_cnt == 5) {
//                            if (DZ_dir >= 0) VALVE_DEADZONE_MINUS = (int16_t) V_out;
//                            else VALVE_DEADZONE_PLUS = (int16_t) V_out;
//                            DZ_dir = -DZ_dir;
//                            DZ_temp_cnt = 0;
//                            DZ_temp_cnt2++;
//                        }
//                    } else {
//                        TMR3_COUNT_DEADZONE = -1;
//                        VALVE_CENTER = VALVE_DEADZONE_PLUS / 2 + VALVE_DEADZONE_MINUS / 2;
//                        if (VALVE_DEADZONE_PLUS < VALVE_DEADZONE_MINUS) {
//                            VALVE_DEADZONE_PLUS = VALVE_CENTER;
//                            VALVE_DEADZONE_MINUS = VALVE_CENTER;
//                        }
//                        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);
//
//                        CONTROL_MODE = MODE_NO_ACT;
//                        DZ_temp_cnt2 = 0;
//                    }
//                }
//                TMR3_COUNT_DEADZONE++;
//                break;
//            }

            case MODE_FIND_HOME: {
                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;
                } else if (FINDHOME_STAGE == FINDHOME_GOTOLIMIT) {
                    int cnt_check_enc = (TMR_FREQ_5k/20);
                    if(cnt_findhome%cnt_check_enc == 0) {
                        FINDHOME_POSITION = pos.sen;
                        FINDHOME_VELOCITY = FINDHOME_POSITION - FINDHOME_POSITION_OLD;
                        FINDHOME_POSITION_OLD = FINDHOME_POSITION;
                    }
                    cnt_findhome++;

                    if (abs(FINDHOME_VELOCITY) <= 1) {
                        cnt_vel_findhome = cnt_vel_findhome + 1;
                    } else {
                        cnt_vel_findhome = 0;
                    }

                    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;
                        FINDHOME_POSITION = 0;
                        FINDHOME_POSITION_OLD = 0;
                        FINDHOME_VELOCITY = 0;
                        cnt_findhome = 0;
                        cnt_vel_findhome = 0;
                        FINDHOME_STAGE = FINDHOME_ZEROPOSE;


                        cnt_findhome = 0;
                        pos.ref = 0.0f;
                        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;
                    pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
                    vel.err = (0.0f - vel.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm/s]
                    pos.err_sum += pos.err/(float) TMR_FREQ_5k; //[mm]

                    if (((OPERATING_MODE&0b110)>>1) == 0 || ((OPERATING_MODE&0b110)>>1) == 1) {

                        double I_REF_POS = 0.0f;
                        double I_REF_FORCE_FB = 0.0f; // I_REF by Force Feedback
                        double I_REF_VC = 0.0f; // I_REF for velocity compensation

                        double temp_vel_pos = 0.0f;
                        double temp_vel_torq = 0.0f;
                        double wn_Pos = 2.0f * PI * 5.0f; // f_cut : 5Hz Position Control

                        if ((OPERATING_MODE & 0x01) == 0) { // Rotary Mode
                            temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION) * 3.14159f / 180.0f; // rad/s
                            //                            L when P-gain = 100, f_cut = 10Hz                                 L feedforward velocity
                        } else if ((OPERATING_MODE & 0x01) == 1) {
                            temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION); // mm/s
                            //                            L when P-gain = 100, f_cut = 10Hz                                 L feedforward velocity
                        }
                        if (temp_vel_pos > 0.0f) I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_A * 0.00006f / (K_v * sqrt(2.0f * alpha3 / (alpha3 + 1.0f))));
                        else I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_B * 0.00006f / (K_v * sqrt(2.0f / (alpha3 + 1.0f))));

                        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));

                        if (VALVE_POS_RAW_FORCE_FB >= 0) {
                            valve_pos.ref = VALVE_POS_RAW_FORCE_FB + VALVE_DEADZONE_PLUS;
                        } else {
                            valve_pos.ref = VALVE_POS_RAW_FORCE_FB + VALVE_DEADZONE_MINUS;
                        }

                        VALVE_POS_CONTROL(valve_pos.ref);

                        V_out = (float) Vout.ref;

                    }




//                    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;
                        pos.ref_home_pos = 0.0f;
                        vel.ref_home_pos = 0.0f;
                        FINDHOME_STAGE = FINDHOME_INIT;
                        CONTROL_UTILITY_MODE = MODE_JOINT_CONTROL;
                    }
                }

                break;
            }

//            case MODE_VALVE_GAIN_SETTING: {
//                if (TMR3_COUNT_FLOWRATE == 0) {
//                    if (pos_plus_end == pos_minus_end) need_enc_init = true;
//                    else {
//                        V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
//                        temp_time = (int) (0.5f * (float) TMR_FREQ_5k);
//                    }
//                }
//                if (need_enc_init) {
//                    if (TMR3_COUNT_FLOWRATE < (int) (0.5f * (float) TMR_FREQ_5k)) {
//                        V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
//                        pos_plus_end = pos.sen;
//                    } else if (TMR3_COUNT_FLOWRATE < TMR_FREQ_5k) {
//                        V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
//                        pos_minus_end = pos.sen;
//                    } else if (TMR3_COUNT_FLOWRATE == TMR_FREQ_5k) {
//                        need_enc_init = false;
//                        check_vel_pos_init = (int) (0.9f * (float) (pos_plus_end - pos_minus_end));
//                        check_vel_pos_fin = (int) (0.95f * (float) (pos_plus_end - pos_minus_end));
//                        check_vel_pos_interv = check_vel_pos_fin - check_vel_pos_init;
//                    }
//                    temp_time = TMR_FREQ_5k;
//                }
//                TMR3_COUNT_FLOWRATE++;
//                if (TMR3_COUNT_FLOWRATE > temp_time) {
//                    if (flag_flowrate % 2 == 0) { // (+)
//                        VALVE_VOLTAGE = 1000.0f * (float) (flag_flowrate / 2 + 1);
//                        V_out = VALVE_VOLTAGE;
//                        if (pos.sen > (pos_minus_end + check_vel_pos_init) && pos.sen < (pos_minus_end + check_vel_pos_fin)) {
//                            fl_temp_cnt++;
//                        } else if (pos.sen >= (pos_minus_end + check_vel_pos_fin) && CUR_VELOCITY == 0) {
//                            VALVE_GAIN_LPM_PER_V[flag_flowrate] = 0.95873f * 0.5757f * (float) TMR_FREQ_5k / 10000.0 * (float) check_vel_pos_interv / (float) fl_temp_cnt / VALVE_VOLTAGE; // 0.9587=6*pi/65536*10000 0.5757=0.02525*0.02*0.0095*2*60*1000
//                            //                        VALVE_GAIN_LPM_PER_V[flag_flowrate] = (float) TMR_FREQ_10k * (float) check_vel_pos_interv / (float) fl_temp_cnt / VALVE_VOLTAGE; // PULSE/sec
//                            fl_temp_cnt2++;
//                        }
//                    } else if (flag_flowrate % 2 == 1) { // (-)
//                        VALVE_VOLTAGE = -1. * (float) (flag_flowrate / 2 + 1);
//                        V_out = VALVE_VOLTAGE;
//                        if (pos.sen < (pos_plus_end - check_vel_pos_init) && pos.sen > (pos_plus_end - check_vel_pos_fin)) {
//                            fl_temp_cnt++;
//                        } else if (pos.sen <= (pos_plus_end - check_vel_pos_fin) && CUR_VELOCITY == 0) {
//                            VALVE_GAIN_LPM_PER_V[flag_flowrate] = 0.95873f * 0.5757f * (float) TMR_FREQ_5k / 10000.0f * (float) check_vel_pos_interv / (float) fl_temp_cnt / (-VALVE_VOLTAGE);
//                            //                        VALVE_GAIN_LPM_PER_V[flag_flowrate] = (float) TMR_FREQ_10k * (float) check_vel_pos_interv / (float) fl_temp_cnt / (-VALVE_VOLTAGE); // PULSE/sec
//                            fl_temp_cnt2++;
//                        }
//                    }
//                    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;
//                        fl_temp_cnt = 0;
//                        fl_temp_cnt2 = 0;
//                        flag_flowrate++;
//                    }
//                    if (flag_flowrate == 10) {
//                        V_out = 0;
//                        flag_flowrate = 0;
//                        TMR3_COUNT_FLOWRATE = 0;
//                        valve_gain_repeat_cnt++;
//                        if (valve_gain_repeat_cnt >= 1) {
//                            CONTROL_MODE = MODE_NO_ACT;
//                            valve_gain_repeat_cnt = 0;
//                        }
//
//                    }
//                    break;
//                }
//
//            }
            case MODE_PRESSURE_SENSOR_NULLING: {
                // DAC Voltage reference set
                if (TMR3_COUNT_PRES_NULL < TMR_FREQ_5k * 2) {
                    CUR_PRES_A_sum += pres_A.sen;
                    CUR_PRES_B_sum += pres_B.sen;

                    if (TMR3_COUNT_PRES_NULL % 10 == 0) {
                        CUR_PRES_A_mean = CUR_PRES_A_sum / 10.0f;
                        CUR_PRES_B_mean = CUR_PRES_B_sum / 10.0f;
                        CUR_PRES_A_sum = 0;
                        CUR_PRES_B_sum = 0;

                        float VREF_NullingGain = 0.0003f;
                        PRES_A_VREF = PRES_A_VREF + VREF_NullingGain * CUR_PRES_A_mean;
                        PRES_B_VREF = PRES_B_VREF + VREF_NullingGain * CUR_PRES_B_mean;

                        if (PRES_A_VREF > 3.3f) PRES_A_VREF = 3.3f;
                        if (PRES_A_VREF < 0.0f) PRES_A_VREF = 0.0f;
                        if (PRES_B_VREF > 3.3f) PRES_B_VREF = 3.3f;
                        if (PRES_B_VREF < 0.0f) PRES_B_VREF = 0.0f;

                        dac_1 = PRES_A_VREF / 3.3f;
                        dac_2 = PRES_B_VREF / 3.3f;
                    }
                } else {
                    CONTROL_UTILITY_MODE = MODE_NO_ACT;
                    TMR3_COUNT_PRES_NULL = 0;
                    CUR_PRES_A_sum = 0;
                    CUR_PRES_B_sum = 0;
                    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;
            }

//            case MODE_PRESSURE_SENSOR_CALIB: {
//                if (TMR3_COUNT_PRES_CALIB < 2 * TMR_FREQ_5k) {
//                    V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
//                    if (TMR3_COUNT_PRES_CALIB >= TMR_FREQ_5k) {
//                        CUR_PRES_A_sum += CUR_PRES_A;
//                    }
//                } else if (TMR3_COUNT_PRES_CALIB < 4 * TMR_FREQ_5k) {
//                    V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
//                    if (TMR3_COUNT_PRES_CALIB >= 3 * TMR_FREQ_5k) {
//                        CUR_PRES_B_sum += CUR_PRES_B;
//                    }
//                } else {
//                    CONTROL_MODE = MODE_NO_ACT;
//                    TMR3_COUNT_PRES_CALIB = 0;
//                    V_out = 0;
//                    PRES_SENSOR_A_PULSE_PER_BAR = CUR_PRES_A_sum / ((float) TMR_FREQ_5k - 1.0f) - PRES_A_NULL;
//                    PRES_SENSOR_A_PULSE_PER_BAR = PRES_SENSOR_A_PULSE_PER_BAR / ((float) PRES_SUPPLY - 1.0f);
//                    PRES_SENSOR_B_PULSE_PER_BAR = CUR_PRES_B_sum / ((float) TMR_FREQ_5k - 1.0f) - PRES_B_NULL;
//                    PRES_SENSOR_B_PULSE_PER_BAR = PRES_SENSOR_B_PULSE_PER_BAR / ((float) PRES_SUPPLY - 1.0f);
//                    CUR_PRES_A_sum = 0;
//                    CUR_PRES_B_sum = 0;
//                    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));
//                }
//                TMR3_COUNT_PRES_CALIB++;
//                break;
//            }

//            case MODE_ROTARY_FRICTION_TUNING: {
//                if (TMR3_COUNT_ROTARY_FRIC_TUNE % (5 * TMR_FREQ_5k) == 0) freq_fric_tune = 4.0f + 3.0f * sin(2 * 3.14159f * 0.5f * TMR3_COUNT_ROTARY_FRIC_TUNE * 0.0001f * 0.05f);
//                V_out = PWM_out * sin(2 * 3.14159f * freq_fric_tune * TMR3_COUNT_ROTARY_FRIC_TUNE * 0.0001f);
//                if (V_out > 0) V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
//                else V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
//                TMR3_COUNT_ROTARY_FRIC_TUNE++;
//                if (TMR3_COUNT_ROTARY_FRIC_TUNE > TUNING_TIME * TMR_FREQ_5k) {
//                    TMR3_COUNT_ROTARY_FRIC_TUNE = 0;
//                    V_out = 0.0f;
//                    CONTROL_MODE = MODE_NO_ACT;
//                }
//                break;
//            }

            case MODE_DDV_POS_VS_PWM_ID: {
                CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
                VALVE_ID_timer = VALVE_ID_timer + 1;

                if(VALVE_ID_timer < TMR_FREQ_5k*1) {
                    Vout.ref = 3000.0f * sin(2.0f*3.14f*VALVE_ID_timer/TMR_FREQ_5k * 100.0f);
                } else if(VALVE_ID_timer < TMR_FREQ_5k*2) {
                    Vout.ref = 1000.0f*(ID_index_array[ID_index]);
                } else if(VALVE_ID_timer == TMR_FREQ_5k*2) {
                    VALVE_POS_TMP = 0;
                    data_num = 0;
                } else if(VALVE_ID_timer < TMR_FREQ_5k*3) {
                    data_num = data_num + 1;
                    VALVE_POS_TMP = VALVE_POS_TMP + value;
                } else if(VALVE_ID_timer == TMR_FREQ_5k*3) {
                    Vout.ref = 0.0f;
                } else {
                    VALVE_POS_AVG[ID_index] = VALVE_POS_TMP / data_num;
                    VALVE_ID_timer = 0;
                    ID_index= ID_index +1;
                }

                if(ID_index>=25) {
                    int i;
                    VALVE_POS_AVG_OLD = VALVE_POS_AVG[0];
                    for(i=0; i<25; i++) {
                        VALVE_POS_VS_PWM[i] = (int16_t) (VALVE_POS_AVG[i]);
                        if(VALVE_POS_AVG[i] > VALVE_POS_AVG_OLD) {
                            VALVE_MAX_POS = VALVE_POS_AVG[i];
                            VALVE_POS_AVG_OLD = VALVE_MAX_POS;
                        } else if(VALVE_POS_AVG[i] < VALVE_POS_AVG_OLD) {
                            VALVE_MIN_POS = VALVE_POS_AVG[i];
                            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++) {
                        spi_eeprom_write(RID_VALVE_POS_VS_PWM_0 + i, (int16_t) VALVE_POS_VS_PWM[i]);
                    }
                    ID_index = 0;
                    CONTROL_UTILITY_MODE = MODE_NO_ACT;
                }


                break;
            }

            case MODE_DDV_DEADZONE_AND_CENTER: {
                CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
                VALVE_DZ_timer = VALVE_DZ_timer + 1;
                if(first_check == 0) {
                    if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
                        Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
                    } else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
                        Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
                        pos_plus_end = pos.sen;
                    } else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
                        Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
                    } else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
                        Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
                        pos_minus_end = pos.sen;
                    } else if(VALVE_DZ_timer < (int) (3.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;
                    } else if(VALVE_DZ_timer < (int) (4.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;
                        data_num = data_num + 1;
                        VALVE_POS_TMP = VALVE_POS_TMP + value;
                    } else if(VALVE_DZ_timer == (int) (4.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;
                        DDV_POS_AVG = VALVE_POS_TMP / data_num;
                        START_POS = pos.sen;
                        VALVE_POS_TMP = 0;
                        data_num = 0;

                    } else if(VALVE_DZ_timer < (int) (5.0f * (float) TMR_FREQ_5k)) {
                        valve_pos.ref = DDV_POS_AVG;
                        VALVE_POS_CONTROL(valve_pos.ref);

                    } else if(VALVE_DZ_timer < (int) (6.0f * (float) TMR_FREQ_5k)) {
                        valve_pos.ref = DDV_POS_AVG;
                        VALVE_POS_CONTROL(valve_pos.ref);

                    } else if(VALVE_DZ_timer == (int) (6.0f * (float) TMR_FREQ_5k)) {
                        valve_pos.ref = DDV_POS_AVG;
                        VALVE_POS_CONTROL(valve_pos.ref);
                        FINAL_POS = pos.sen;

                        if((FINAL_POS - START_POS)>200) {
                            DZ_case = 1;
                        } else if((FINAL_POS - START_POS)<-200) {
                            DZ_case = -1;
                        } else {
                            DZ_case = 0;
                        }

                        CAN_TX_PRES((int16_t) (DZ_case), (int16_t) (6));

                        first_check = 1;
                        DZ_DIRECTION = 1;
                        VALVE_DZ_timer = 0;
                        Ref_Valve_Pos_Old = DDV_POS_AVG;
                        DZ_NUM = 1;
                        DZ_index = 1;

                    }
                } else {
                    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)) {
                            valve_pos.ref = Ref_Valve_Pos_Old  - DZ_case * DZ_DIRECTION * 64 / DZ_index;
                            if(valve_pos.ref <= VALVE_MIN_POS) {
                                valve_pos.ref = VALVE_MIN_POS;
                            } else if(valve_pos.ref >= VALVE_MAX_POS) {
                                valve_pos.ref = VALVE_MAX_POS;
                            }
                            VALVE_POS_CONTROL(valve_pos.ref);

                        } else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
                            Ref_Valve_Pos_Old = valve_pos.ref;
                            FINAL_POS = pos.sen;

                            if((FINAL_POS - START_POS)>100) {
                                DZ_DIRECTION = 1 * DZ_case;
                            } else if((FINAL_POS - START_POS)<-100) {
                                DZ_DIRECTION = -1 * DZ_case;
                            } else {
                                DZ_DIRECTION = 1 * DZ_case;
                            }

                            VALVE_DZ_timer = 0;
                            DZ_index= DZ_index *2;
                            if(DZ_index >= 128) {
                                FIRST_DZ = valve_pos.ref;
                                DZ_NUM = 2;
                                Ref_Valve_Pos_Old = FIRST_DZ;
                                DZ_index = 1;
                                DZ_DIRECTION = 1;
                            }
                        }
                    } 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)) {
                            valve_pos.ref = Ref_Valve_Pos_Old  - DZ_case * DZ_DIRECTION * 64 / DZ_index;
                            if(valve_pos.ref <= VALVE_MIN_POS) {
                                valve_pos.ref = VALVE_MIN_POS;
                            } else if(valve_pos.ref >= VALVE_MAX_POS) {
                                valve_pos.ref = VALVE_MAX_POS;
                            }
                            VALVE_POS_CONTROL(valve_pos.ref);

                        } else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
                            Vout.ref = 0.0f;
                        } else if(VALVE_DZ_timer > (int) (2.0f * (float) TMR_FREQ_5k)) {
                            Ref_Valve_Pos_Old = valve_pos.ref;
                            FINAL_POS = pos.sen;

                            if((FINAL_POS - START_POS)>100) {
                                DZ_DIRECTION = 1 * DZ_case;
                            } else if((FINAL_POS - START_POS)<-100) {
                                DZ_DIRECTION = -1 * DZ_case;
                            } else {
                                DZ_DIRECTION = -1 * DZ_case;
                            }

                            VALVE_DZ_timer = 0;
                            DZ_index= DZ_index * 2;
                            if(DZ_index >= 128) {
                                SECOND_DZ = valve_pos.ref;
                                VALVE_CENTER = (int) (0.5f * (float) (FIRST_DZ) + 0.5f * (float) (SECOND_DZ));
                                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);

                                CONTROL_UTILITY_MODE = MODE_NO_ACT;
                                DZ_index = 1;
                            }
                        }
                    } 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)) {
                            valve_pos.ref = Ref_Valve_Pos_Old  - DZ_DIRECTION * 64 / DZ_index;
                            if(valve_pos.ref <= VALVE_MIN_POS) {
                                valve_pos.ref = VALVE_MIN_POS;
                            } else if(valve_pos.ref >= VALVE_MAX_POS) {
                                valve_pos.ref = VALVE_MAX_POS;
                            }
                            VALVE_POS_CONTROL(valve_pos.ref);

                        } else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
                            Ref_Valve_Pos_Old = valve_pos.ref;
                            FINAL_POS = pos.sen;

                            if((FINAL_POS - START_POS)>100) {
                                DZ_DIRECTION = 1;
                            } else if((FINAL_POS - START_POS)<-100) {
                                DZ_DIRECTION = -1;
                            } else {
                                DZ_DIRECTION = 1;
                            }
                            VALVE_DZ_timer = 0;
                            DZ_index= DZ_index *2;
                            if(DZ_index >= 128) {
                                FIRST_DZ = valve_pos.ref;
                                DZ_NUM = 2;
                                Ref_Valve_Pos_Old = FIRST_DZ;
                                DZ_index = 1;
                                DZ_DIRECTION = 1;
                            }
                        }
                    } 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)) {
                            valve_pos.ref = Ref_Valve_Pos_Old  + DZ_DIRECTION * 64 / DZ_index;
                            if(valve_pos.ref <= VALVE_MIN_POS) {
                                valve_pos.ref = VALVE_MIN_POS;
                            } else if(valve_pos.ref > VALVE_MAX_POS) {
                                valve_pos.ref = VALVE_MAX_POS - 1;
                            }
                            VALVE_POS_CONTROL(valve_pos.ref);

                        } else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
                            Vout.ref = 0.0f;
                        } else if(VALVE_DZ_timer > (int) (2.0f * (float) TMR_FREQ_5k)) {
                            Ref_Valve_Pos_Old = valve_pos.ref;
                            FINAL_POS = pos.sen;

                            if((FINAL_POS - START_POS)>100) {
                                DZ_DIRECTION = 1;
                            } else if((FINAL_POS - START_POS)<-100) {
                                DZ_DIRECTION = -1;
                            } else {
                                DZ_DIRECTION = 1;
                            }

                            VALVE_DZ_timer = 0;
                            DZ_index= DZ_index *2;
                            if(DZ_index >= 128) {
                                SECOND_DZ = valve_pos.ref;
                                VALVE_CENTER = (int) (0.5f * (float) (FIRST_DZ) + 0.5f * (float) (SECOND_DZ));
                                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);

                                CONTROL_UTILITY_MODE = MODE_NO_ACT;
                                DZ_index = 1;
                            }
                        }
                    }
                }
                break;
            }

            case MODE_DDV_POS_VS_FLOWRATE: {
                CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
                VALVE_FR_timer = VALVE_FR_timer + 1;
                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;
                        VALVE_FR_timer = 0;
                        valve_pos.ref = (float) VALVE_CENTER;
                        ID_index = 0;
                        max_check = 0;
                        min_check = 0;
                    }
                } 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)) {
                        data_num = 0;
                        valve_pos.ref = 10.0f*((float) ID_index_array[ID_index]) + (float) VALVE_CENTER;

                        VALVE_POS_CONTROL(valve_pos.ref);
                        START_POS = pos.sen;
                    } else if(VALVE_FR_timer < (int) (5.0f * (float) TMR_FREQ_5k)) {
                        valve_pos.ref = 10.0f*((float) ID_index_array[ID_index]) + (float) VALVE_CENTER;
                        VALVE_POS_CONTROL(valve_pos.ref);
                        data_num = data_num + 1;
                        if(abs(0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen) > 20000.0f) {
                            FINAL_POS = pos.sen;
                            one_period_end = 1;
                        }
                    } else if(VALVE_FR_timer == (int) (5.0f * (float) TMR_FREQ_5k)) {
                        FINAL_POS = pos.sen;
                        one_period_end = 1;
                        V_out = 0.0f;
                    }

                    if(one_period_end == 1) {
                        if(valve_pos.ref > VALVE_MAX_POS) {
                            max_check = 1;
                        } else if(valve_pos.ref < VALVE_MIN_POS) {
                            min_check = 1;
                        }
                        JOINT_VEL[ID_index] = (FINAL_POS - START_POS) / data_num * TMR_FREQ_5k;   //  pulse/sec

                        VALVE_FR_timer = 0;
                        one_period_end = 0;
                        ID_index= ID_index +1;
                        V_out = 0.0f;
                    }

                    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));
                        }
                        ID_index = 0;
                        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;
            }

            case MODE_SYSTEM_ID: {
                freq_sysid_Iref = (double) cnt_sysid * DT_TMR3 * 3.0f;
                valve_pos.ref = 2500.0f * sin(2.0f * 3.14159f * freq_sysid_Iref * (double) cnt_sysid * DT_TMR3);
                CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
                cnt_sysid++;
                if (freq_sysid_Iref >= 300) {
                    cnt_sysid = 0;
                    CONTROL_UTILITY_MODE = MODE_NO_ACT;
                }
                break;
            }

            case MODE_FREQ_TEST: {
                float valve_pos_ref = 2500.0f * sin(2.0f * 3.141592f * freq_test_valve_ref * (float) cnt_freq_test * DT_TMR3);
                if(valve_pos_ref >= 0) {
                    valve_pos.ref = (double)VALVE_CENTER + (double)valve_pos_ref * ((double)VALVE_MAX_POS-(double)VALVE_CENTER)/10000.0f;
                } else {
                    valve_pos.ref = (double)VALVE_CENTER - (double)valve_pos_ref * ((double)VALVE_MIN_POS-(double)VALVE_CENTER)/10000.0f;
                }
                ref_array[cnt_freq_test] = valve_pos_ref;
                if(value>=(float) VALVE_CENTER) {
                    pos_array[cnt_freq_test] = 10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
                } else {
                    pos_array[cnt_freq_test] = -10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
                }

                CONTROL_MODE = MODE_VALVE_POSITION_CONTROL;
                cnt_freq_test++;
                if (freq_test_valve_ref * (float) cnt_freq_test * DT_TMR3 > 2) {
                    buffer_data_size = cnt_freq_test;
                    cnt_freq_test = 0;
                    cnt_send_buffer = 0;
                    freq_test_valve_ref = freq_test_valve_ref * 1.05f;
                    if (freq_test_valve_ref >= 400) {
                        CONTROL_UTILITY_MODE = MODE_NO_ACT;
                        CONTROL_MODE = MODE_NO_ACT;
                        CAN_TX_PWM((int16_t) (1)); //1300
                    }
                    CONTROL_MODE = MODE_NO_ACT;
                    CONTROL_UTILITY_MODE = MODE_SEND_OVER;

                }
                break;
            }
            case MODE_SEND_BUFFER: {
//                if (TMR2_COUNT_CAN_TX % (int) ((int) TMR_FREQ_5k/CAN_FREQ) == 0) {
//                    CAN_TX_PRES((int16_t) (pos_array[cnt_send_buffer]), (int16_t) (ref_array[cnt_send_buffer])); // 1400
//                    if(cnt_send_buffer>=buffer_data_size) {
//                        CONTROL_UTILITY_MODE = MODE_FREQ_TEST;
//                    }
//                    cnt_send_buffer++;
//                }

                break;
            }
            case MODE_SEND_OVER: {
                CAN_TX_TORQUE((int16_t) (buffer_data_size)); //1300
                CONTROL_UTILITY_MODE = MODE_NO_ACT;
                CONTROL_MODE = MODE_NO_ACT;
                break;
            }

            case MODE_STEP_TEST: {
                float valve_pos_ref = 0.0f;
                if (cnt_step_test < (int) (1.0f * (float) TMR_FREQ_5k)) {
                    valve_pos_ref = 0.0f;
                } else {
                    valve_pos_ref = 10000.0f;
                }
                if(valve_pos_ref >= 0) {
                    valve_pos.ref = (double)VALVE_CENTER + (double)valve_pos_ref * ((double)VALVE_MAX_POS-(double)VALVE_CENTER)/10000.0f;
                } else {
                    valve_pos.ref = (double)VALVE_CENTER - (double)valve_pos_ref * ((double)VALVE_MIN_POS-(double)VALVE_CENTER)/10000.0f;
                }
                ref_array[cnt_step_test] = valve_pos_ref;
                if(value>=(float) VALVE_CENTER) {
                    pos_array[cnt_step_test] = 10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
                } else {
                    pos_array[cnt_step_test] = -10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
                }

                CONTROL_MODE = MODE_VALVE_POSITION_CONTROL;
                cnt_step_test++;
                if (cnt_step_test > (int) (2.0f * (float) TMR_FREQ_5k)) {
                    buffer_data_size = cnt_step_test;
                    cnt_step_test = 0;
                    cnt_send_buffer = 0;
                    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;
            }

            default:
                break;
        }

        // CONTROL MODE ------------------------------------------------------------

        switch (CONTROL_MODE) {
            case MODE_NO_ACT: {
                V_out = 0.0f;
                break;
            }

            case MODE_VALVE_POSITION_CONTROL: {
                if (OPERATING_MODE == 5) { //SW Valve
                    VALVE_POS_CONTROL(valve_pos.ref);
                    V_out = Vout.ref;
                } else if (CURRENT_CONTROL_MODE == 0) { //PWM
                    V_out = valve_pos.ref;
                } else {
                    I_REF = valve_pos.ref * 0.001f;
                }
                break;
            }

            case MODE_JOINT_CONTROL: {

                double torq_ref = 0.0f;
                pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
                vel.err = (0.0f - vel.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm/s]
                pos.err_sum += pos.err/(float) TMR_FREQ_5k; //[mm]

                //K & D Low Pass Filter
                float alpha_K_D = 1.0f/(1.0f + 5000.0f/(2.0f*3.14f*30.0f)); // f_cutoff : 30Hz
                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;

                // torque feedback
                torq.err = torq_ref - torq.sen; //[N]
                torq.err_sum += torq.err/(float) TMR_FREQ_5k; //[N]

                if (((OPERATING_MODE&0b110)>>1) == 0 || ((OPERATING_MODE&0b110)>>1) == 1) {

                    double I_REF_POS = 0.0f;
                    double I_REF_FORCE_FB = 0.0f; // I_REF by Force Feedback
                    double I_REF_VC = 0.0f; // I_REF for velocity compensation

                    double temp_vel_pos = 0.0f;
                    double temp_vel_torq = 0.0f;
                    double wn_Pos = 2.0f * PI * 5.0f; // f_cut : 5Hz Position Control

                    if ((OPERATING_MODE & 0x01) == 0) { // Rotary Mode
                        temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION) * PI / 180.0f; // rad/s
                        //                            L when P-gain = 100, f_cut = 10Hz                                 L feedforward velocity
                    } else if ((OPERATING_MODE & 0x01) == 1) {
                        temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION); // mm/s
                        //                            L when P-gain = 100, f_cut = 10Hz                                 L feedforward velocity
                    }
                    if (temp_vel_pos > 0.0f) I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_A * 0.00006f / (K_v * sqrt(2.0f * alpha3 / (alpha3 + 1.0f))));
                    else I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_B * 0.00006f / (K_v * sqrt(2.0f / (alpha3 + 1.0f))));

                    // velocity compensation for torque control
                    if ((OPERATING_MODE & 0x01) == 0) { // Rotary Mode
                        I_REF_FORCE_FB = 0.001f * ((double) P_GAIN_JOINT_TORQUE * torq.err + (double) I_GAIN_JOINT_TORQUE * torq.err_sum);
                        //                temp_vel_torq = (0.01 * (double) VELOCITY_COMP_GAIN * (double) CUR_VELOCITY / (double) ENC_PULSE_PER_POSITION) * PI / 180.0; // rad/s
                        temp_vel_torq = (0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / (double) ENC_PULSE_PER_POSITION) * PI / 180.0f; // rad/s
                        //                                                          L feedforward velocity
                    } else if ((OPERATING_MODE & 0x01) == 1) {
                        I_REF_FORCE_FB = 0.001f * 0.01f*((double) P_GAIN_JOINT_TORQUE * torq.err + (double) I_GAIN_JOINT_TORQUE * torq.err_sum); // Linear Actuators are more sensitive.
                        //                temp_vel_torq = (0.01 * (double) VELOCITY_COMP_GAIN * (double) CUR_VELOCITY / (double) ENC_PULSE_PER_POSITION); // mm/s
                        temp_vel_torq = (0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / (double) ENC_PULSE_PER_POSITION); // mm/s
                        //                                                          L feedforward velocity
                    }
                    if (temp_vel_torq > 0.0f) I_REF_VC = temp_vel_torq * ((double) PISTON_AREA_A * 0.00006f / (K_v * sqrt(2.0f * alpha3 / (alpha3 + 1.0f))));
                    else I_REF_VC = temp_vel_torq * ((double) PISTON_AREA_B * 0.00006f / (K_v * sqrt(2.0f / (alpha3 + 1.0f))));
                    //                                                  L   velocity(rad/s or mm/s) >> I_ref(mA)
                    //            Ref_Joint_FT_dot = (Ref_Joint_FT_Nm - Ref_Joint_FT_Nm_old) / TMR_DT_5k;
                    //            Ref_Joint_FT_Nm_old = Ref_Joint_FT_Nm;

                    I_REF = (1.0f - alpha_trans) * I_REF_POS + alpha_trans * (I_REF_VC + I_REF_FORCE_FB);

                    // Anti-windup for FT
                    if (I_GAIN_JOINT_TORQUE != 0) {
                        double I_MAX = 10.0f; // Maximum Current : 10mV
                        double Ka = 2.0f / ((double) I_GAIN_JOINT_TORQUE * 0.001f);
                        if (I_REF > I_MAX) {
                            double I_rem = I_REF - I_MAX;
                            I_rem = Ka*I_rem;
                            I_REF = I_MAX;
                            torq.err_sum = torq.err_sum - I_rem /(float) TMR_FREQ_5k;
                        } else if (I_REF < -I_MAX) {
                            double I_rem = I_REF - (-I_MAX);
                            I_rem = Ka*I_rem;
                            I_REF = -I_MAX;
                            torq.err_sum = torq.err_sum - I_rem /(float) TMR_FREQ_5k;
                        }
                    }

                } else {
                    float VALVE_POS_RAW_FORCE_FB = 0.0f;
                    float VALVE_POS_RAW_FORCE_FF = 0.0f;
                    float VALVE_POS_RAW = 0.0f;

                    VALVE_POS_RAW_FORCE_FB = alpha_trans*(((float) P_GAIN_JOINT_TORQUE * torq.err + (float) I_GAIN_JOINT_TORQUE * torq.err_sum) * 0.01f
                                                          + DDV_JOINT_POS_FF(vel.sen))+ (1.0f-alpha_trans) * (P_GAIN_JOINT_POSITION * 0.01f * pos.err + DDV_JOINT_POS_FF(vel.ref));

                    VALVE_POS_RAW_FORCE_FF = P_GAIN_JOINT_TORQUE_FF * torq_ref * 0.001f + D_GAIN_JOINT_TORQUE_FF * (torq_ref - torq_ref_past) * 0.0001f;

                    VALVE_POS_RAW = VALVE_POS_RAW_FORCE_FB + VALVE_POS_RAW_FORCE_FF;


                    if (VALVE_POS_RAW >= 0) {
                        valve_pos.ref = VALVE_POS_RAW + VALVE_DEADZONE_PLUS;
                    } else {
                        valve_pos.ref = VALVE_POS_RAW + VALVE_DEADZONE_MINUS;
                    }

                    if(I_GAIN_JOINT_TORQUE != 0) {
                        double Ka = 2.0f / (double) I_GAIN_JOINT_TORQUE * 100.0f;
                        if(valve_pos.ref>VALVE_MAX_POS) {
                            double valve_pos_rem = valve_pos.ref - VALVE_MAX_POS;
                            valve_pos_rem = valve_pos_rem * Ka;
                            valve_pos.ref = VALVE_MAX_POS;
                            torq.err_sum = torq.err_sum - valve_pos_rem/(float) TMR_FREQ_5k;
                        } else if(valve_pos.ref < VALVE_MIN_POS) {
                            double valve_pos_rem = valve_pos.ref - VALVE_MIN_POS;
                            valve_pos_rem = valve_pos_rem * Ka;
                            valve_pos.ref = VALVE_MIN_POS;
                            torq.err_sum = torq.err_sum - valve_pos_rem/(float) TMR_FREQ_5k;
                        }
                    }

                    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;
            }

            case MODE_VALVE_OPEN_LOOP: {
                V_out = (float) Vout.ref;
                break;
            }

            case MODE_JOINT_ADAPTIVE_BACKSTEPPING: {


                float Va = (1256.6f + Amm * pos.sen/(float)(ENC_PULSE_PER_POSITION)) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * x,      unit : m^3
                float Vb = (1256.6f + Amm  * (79.0f - pos.sen/(float)(ENC_PULSE_PER_POSITION))) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * (79.0mm-x),      unit : m^3

//                float Va = (1256.6f + Amm * 39.5f) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * x,      unit : m^3
//                float Vb = (1256.6f + Amm  * 39.5f) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * (79.0mm-x),      unit : m^3
                V_adapt = 1.0f / (1.0f/Va + 1.0f/Vb); //initial 0.0000053f


                float f3 = -Amm*Amm*beta*0.000001f*0.000001f/V_adapt * vel.sen/(float)(ENC_PULSE_PER_POSITION)*0.001f; // unit : N/s    //xdot=10mm/s일때 -137076

                float g3_prime = 0.0f;
                if (torq.sen > Amm*(Ps-Pt)*0.000001f) {
                    g3_prime = 1.0f;
                } else if (torq.sen < -Amm*(Ps-Pt)*0.000001f) {
                    g3_prime = -1.0f;
                } else {
                    if ((value-VALVE_CENTER) > 0) {
                        g3_prime = sqrt(Ps-Pt-torq.sen/Amm*1000000.0f);
//                        g3_prime = sqrt(Ps-Pt);
                    } else {
                        g3_prime = sqrt(Ps-Pt+torq.sen/Amm*1000000.0f);
//                        g3_prime = sqrt(Ps-Pt);
                    }
                }
                float tau = 0.01f;
                float K_valve = 0.0004f;

                float x_v = 0.0f;   //x_v : -1~1
                if(value>=VALVE_CENTER) {
                    x_v = 1.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
                } else {
                    x_v = -1.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
                }
                float f4 = -x_v/tau;
                float g4 = K_valve/tau;

                float torq_ref_dot = torq.ref_diff * 500.0f;

                pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
                vel.err = (0.0f - vel.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm/s]
                pos.err_sum += pos.err/(float) TMR_FREQ_5k; //[mm]

                torq.err = torq.ref - torq.sen; //[N]
                torq.err_sum += torq.err/(float) TMR_FREQ_5k; //[N]

                float k3 = 20000.0f; //2000
                float k4 = 10.0f;
                float rho3 = 3.2f;
                float rho4 = 25000000.0f;
                float x_4_des = (-f3 + torq_ref_dot - k3*(-torq.err))/(gamma_hat*g3_prime);
                if (x_4_des > 1) x_4_des = 1;
                else if (x_4_des < -1) x_4_des = -1;

                if (x_4_des > 0) {
                    valve_pos.ref = x_4_des * (float)(VALVE_MAX_POS - VALVE_CENTER) + (float) VALVE_CENTER;
                } else {
                    valve_pos.ref = x_4_des * (float)(VALVE_CENTER - VALVE_MIN_POS) + (float) VALVE_CENTER;
                }


                float x_4_des_dot = (x_4_des - x_4_des_old)*(float) TMR_FREQ_5k;
                x_4_des_old = x_4_des;

                V_out = (-f4 + x_4_des_dot - k4*(x_v-x_4_des)- rho3/rho4*gamma_hat*g3_prime*(-torq.err))/g4;

                float rho_gamma = 50000.0f;//5000
                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;
                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;
                    mean_before_SP_array[RL_timer] = mean_before_SP;
                    deviation_before_SP_array[RL_timer] = deviation_before_SP;
                    action_array[RL_timer] = rand_normal(mean_array[RL_timer], deviation_array[RL_timer]);


                    virt_pos = virt_pos + (action_array[RL_timer] - 3.0f) * 1000.0f * 0.0002f;
                    if (virt_pos > 70.0f ) {
                        virt_pos = 70.0f;
                    } else if(virt_pos < -70.0f) {
                        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;
                        //virt_pos = 10.0f;

                        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-3.0f) * 1000.0f * 0.0002f;
                    if (virt_pos > 70.0f) {
                        virt_pos = 70.0f;
                    } else if(virt_pos < -70.0f) {
                        virt_pos = -70.0f;
                    }

                    logging3 = virt_pos;
                }

                //t.stop();
                //logging1 = t.read()*1000.0f;    //msec

                break;
            }

            default:
                break;
        }


        if (((OPERATING_MODE&0b110)>>1) == 0 || ((OPERATING_MODE&0b110)>>1) == 1) { //Moog Valve or KNR Valve

            ////////////////////////////////////////////////////////////////////////////
            ////////////////////////////  CURRENT CONTROL //////////////////////////////
            ////////////////////////////////////////////////////////////////////////////
            if (CURRENT_CONTROL_MODE) {
                double alpha_update_Iref = 1.0f / (1.0f + 5000.0f / (2.0f * 3.14f * 300.0f)); // f_cutoff : 500Hz
                I_REF_fil = (1.0f - alpha_update_Iref) * I_REF_fil + alpha_update_Iref*I_REF;

                I_ERR = I_REF_fil - cur.sen;
                I_ERR_INT = I_ERR_INT + (I_ERR) * 0.0002f;


                // Moog Valve Current Control Gain
                double R_model = 500.0f; // ohm
                double L_model = 1.2f;
                double w0 = 2.0f * 3.14f * 150.0f;
                double KP_I = 0.1f * L_model*w0;
                double KI_I = 0.1f * R_model*w0;

                // KNR Valve Current Control Gain
                if (((OPERATING_MODE & 0b110)>>1) == 1) { // KNR Valve
                    R_model = 163.0f; // ohm
                    L_model = 1.0f;
                    w0 = 2.0f * 3.14f * 80.0f;
                    KP_I = 1.0f * L_model*w0;
                    KI_I = 0.08f * R_model*w0;
                }

                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
                VALVE_PWM_RAW = VALVE_PWM_RAW + FF_gain * (R_model * I_REF_fil); // Unit : mV
                double V_MAX = 12000.0f; // Maximum Voltage : 12V = 12000mV

                double Ka = 3.0f / KP_I;
                if (VALVE_PWM_RAW > V_MAX) {
                    V_rem = VALVE_PWM_RAW - V_MAX;
                    V_rem = Ka*V_rem;
                    VALVE_PWM_RAW = V_MAX;
                    I_ERR_INT = I_ERR_INT - V_rem * 0.0002f;
                } else if (VALVE_PWM_RAW < -V_MAX) {
                    V_rem = VALVE_PWM_RAW - (-V_MAX);
                    V_rem = Ka*V_rem;
                    VALVE_PWM_RAW = -V_MAX;
                    I_ERR_INT = I_ERR_INT - V_rem * 0.0002f;
                }
                Cur_Valve_Open_pulse = cur.sen / mA_PER_pulse;
            } else {
                VALVE_PWM_RAW = I_REF * mV_PER_mA;
                Cur_Valve_Open_pulse = I_REF / mA_PER_pulse;
            }

            ////////////////////////////////////////////////////////////////////////////
            /////////////////  Dead Zone Cancellation & Linearization //////////////////
            ////////////////////////////////////////////////////////////////////////////
            // Dead Zone Cancellation (Mechanical Valve dead-zone)
            if (FLAG_VALVE_DEADZONE) {
                if (VALVE_PWM_RAW > 0) VALVE_PWM_RAW = VALVE_PWM_RAW + VALVE_DEADZONE_PLUS * mV_PER_pulse; // unit: mV
                else if (VALVE_PWM_RAW < 0) VALVE_PWM_RAW = VALVE_PWM_RAW + VALVE_DEADZONE_MINUS * mV_PER_pulse; // unit: mV

                VALVE_PWM_VALVE_DZ = VALVE_PWM_RAW + (double)VALVE_CENTER * mV_PER_pulse; // unit: mV

            } else {
                VALVE_PWM_VALVE_DZ = VALVE_PWM_RAW;
            }

            // Output Voltage Linearization
            double CUR_PWM_nonlin = VALVE_PWM_VALVE_DZ; // Unit : mV
            double CUR_PWM_lin = PWM_duty_byLT(CUR_PWM_nonlin);  // -8000~8000

            // Dead Zone Cancellation (Electrical dead-zone)
            if (CUR_PWM_lin > 0) V_out = (float) (CUR_PWM_lin + 169.0f);
            else if (CUR_PWM_lin < 0) V_out = (float) (CUR_PWM_lin - 174.0f);
            else V_out = (float) (CUR_PWM_lin);
        } else {            //////////////////////////sw valve
            // Output Voltage Linearization
//            double CUR_PWM_nonlin = V_out; // Unit : mV
//            double CUR_PWM_lin = PWM_duty_byLT(CUR_PWM_nonlin);  // -8000~8000

            // Dead Zone Cancellation (Electrical dead-zone)
//            if (CUR_PWM_lin > 0) V_out = (float) (CUR_PWM_lin + 169.0f);
//            else if (CUR_PWM_lin < 0) V_out = (float) (CUR_PWM_lin - 174.0f);
//            else V_out = (float) (CUR_PWM_lin);

            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
        ********************************************************/
        if(DIR_VALVE<0) {
            V_out = -V_out;
        }

        if (V_out >= VALVE_VOLTAGE_LIMIT*1000.0f) {
            V_out = VALVE_VOLTAGE_LIMIT*1000.0f;
        } 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

        // Saturation of output voltage to 12.0V
        if(PWM_out > 1.0f) PWM_out=1.0f;
        else if (PWM_out < -1.0f) PWM_out=-1.0f;

        if (PWM_out>0.0f) {
            dtc_v=0.0f;
            dtc_w=PWM_out;
        } else {
            dtc_v=-PWM_out;
            dtc_w=0.0f;
        }

        //pwm
        TIM4->CCR2 = (PWM_ARR)*(1.0f-dtc_v);
        TIM4->CCR1 = (PWM_ARR)*(1.0f-dtc_w);


        if (TMR2_COUNT_CAN_TX % (int) ((int) TMR_FREQ_5k/CAN_FREQ) == 0) {

            // Position, Velocity, and Torque (ID:1200)
            if (flag_data_request[0] == HIGH) {
                if ((OPERATING_MODE & 0b01) == 0) { // Rotary Actuator
                    if (SENSING_MODE == 0) {
                        CAN_TX_POSITION_FT((int16_t) (pos.sen), (int16_t) (vel.sen/10.0f), (int16_t) (torq.sen*10.0f));
                    } else if (SENSING_MODE == 1) {
                        CAN_TX_POSITION_PRESSURE((int16_t) (pos.sen), (int16_t) (vel.sen/10.0f), (int16_t) ((pres_A.sen)*5.0f), (int16_t) ((pres_B.sen)*5.0f));
                    }
                } else if ((OPERATING_MODE & 0b01) == 1) { // Linear Actuator
                    if (SENSING_MODE == 0) {
                        CAN_TX_POSITION_FT((int16_t) (pos.sen/10.0f), (int16_t) (vel.sen/256.0f), (int16_t) (torq.sen * 10.0f * (float)(TORQUE_SENSOR_PULSE_PER_TORQUE)));
                    } else if (SENSING_MODE == 1) {
                        CAN_TX_POSITION_PRESSURE((int16_t) (pos.sen/10.0f), (int16_t) (vel.sen/256.0f), (int16_t) ((pres_A.sen)*5.0f), (int16_t) ((pres_B.sen)*5.0f));
                    }
                }
            }
            if (flag_data_request[1] == HIGH) {
                //valve position
                double t_value = 0.0f;
                if(valve_pos.ref>=(float) VALVE_CENTER) {
                    t_value = 10000.0f*((double)valve_pos.ref - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
                } else {
                    t_value = -10000.0f*((double)valve_pos.ref - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
                }
                CAN_TX_TORQUE((int16_t) (t_value)); //1300
            }


            if (flag_data_request[2] == HIGH) {
                double t_value = 0.0f;
                if(value>=(float) VALVE_CENTER) {
                    t_value = 10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
                } else {
                    t_value = -10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
                }
                double t_value_ref = 0.0f;
                if(valve_pos.ref>=(float) VALVE_CENTER) {
                    t_value_ref = 10000.0f*((double)valve_pos.ref - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
                } else {
                    t_value_ref = -10000.0f*((double)valve_pos.ref - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
                }


                CAN_TX_PRES((int16_t) (t_value), (int16_t) (t_value_ref)); // 1400
            }

            //If it doesn't rest, below can can not work.
            for (can_rest = 0; can_rest < 10000; can_rest++) {
                ;
            }

            if (flag_data_request[3] == HIGH) {
                //PWM
                //CAN_TX_PWM((int16_t) value); //1500
                CAN_TX_PWM((int16_t) gamma_hat); //1500
            }
            //for (i = 0; i < 10000; i++) {
//                ;
//            }
            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) 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++;

    }
    TIM3->SR = 0x0;  // reset the status register

}