Sungwoo Kim
/
HydraulicControlBoard_Base
distribution-201229
main.cpp
- Committer:
- Lightvalve
- Date:
- 2020-12-18
- Revision:
- 195:dde3bb8e0d81
- Parent:
- 194:b31951919b55
- Child:
- 196:56a7e26a4a8a
File content as of revision 195:dde3bb8e0d81:
//201218_5 #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> #include <cmath> 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.5049792528152466f,1.3884327411651611f,0.12903714179992676f,0.891964316368103f,-2.0343658924102783f,2.1200127601623535f,-0.17472904920578003f,0.1945325881242752f,-0.6159688234329224f,-2.1421313285827637f,0.646172046661377f,-1.4796212911605835f,-1.6515940427780151f,-1.0867961645126343f,-0.2571594715118408f,-0.6423998475074768f}, {-0.8074502348899841f,0.6986951231956482f,-0.3927857577800751f,0.10117524862289429f,-1.0908969640731812f,0.9588668346405029f,-0.4054011106491089f,0.027100883424282074f,-0.20849254727363586f,-0.7737641334533691f,-0.0007267668261192739f,-0.559249222278595f,-0.34011590480804443f,-0.9275782108306885f,-0.20967772603034973f,0.00843813456594944f}, {-0.1761643886566162f,-0.00044299568980932236f,0.36391180753707886f,-0.6050712466239929f,0.10568452626466751f,0.08904145658016205f,0.2872133255004883f,-0.04633462801575661f,-0.18011713027954102f,0.3201780915260315f,-0.6315233707427979f,0.2315744310617447f,0.21526654064655304f,0.2692757546901703f,0.05590221285820007f,0.1846989542245865f}, {0.3208276033401489f,-0.5977734327316284f,0.39742106199264526f,-0.13856913149356842f,0.6892843246459961f,-0.9602494835853577f,-0.11584559082984924f,-0.06512385606765747f,0.1462620198726654f,0.9997460842132568f,-0.4601175785064697f,1.0265581607818604f,0.409962922334671f,0.5716820359230042f,-0.2961459457874298f,0.6279282569885254f}, {1.2834209203720093f,-0.7100825905799866f,-0.0051451027393341064f,-0.48592910170555115f,1.3144265413284302f,-1.2957475185394287f,0.1294034719467163f,-0.3098825216293335f,0.4540647268295288f,1.3852906227111816f,-0.3826965093612671f,1.0702041387557983f,0.8663880825042725f,0.983588457107544f,-0.3865056037902832f,0.2630000412464142f}, {0.7572326064109802f,-0.704451322555542f,0.21773302555084229f,0.2423843890428543f,0.74943608045578f,-1.221998691558838f,0.16514194011688232f,0.40929198265075684f,0.4561389982700348f,0.43248844146728516f,0.2699551284313202f,-0.26172181963920593f,0.477117657661438f,0.22961737215518951f,-0.4132833778858185f,-0.5123910307884216f}, {0.10581762343645096f,1.3901673555374146f,-0.2501986622810364f,-0.1542971432209015f,-0.35934504866600037f,0.5287187695503235f,0.06014183163642883f,-0.40914610028266907f,0.3122667670249939f,0.3267156779766083f,0.07723409682512283f,0.10168510675430298f,-0.9989253282546997f,2.5577051639556885f,-0.15618428587913513f,-0.9690904021263123f}, {-2.7382125854492188f,0.4130338430404663f,-0.26619744300842285f,1.700432538986206f,-1.3281302452087402f,-1.8974241018295288f,-0.17925891280174255f,-0.9012918472290039f,-0.07043382525444031f,-0.48516932129859924f,2.527921438217163f,-1.9383374452590942f,0.09208452701568604f,0.08270622044801712f,0.04303058981895447f,-1.6846622228622437f}, {1.0545861721038818f,-1.4685617685317993f,0.10248100757598877f,-0.7680048942565918f,0.7788065075874329f,-0.5541813373565674f,-0.07246989011764526f,-3.9993937015533447f,-1.7258435487747192f,1.5052671432495117f,-2.6104493141174316f,2.101834535598755f,1.8155968189239502f,1.0661120414733887f,-0.30555272102355957f,2.365203619003296f}, {-0.8168604373931885f,2.0169551372528076f,0.18462657928466797f,-3.2892398834228516f,1.213491439819336f,0.017481716349720955f,-0.2990540862083435f,1.388200283050537f,3.561858892440796f,-0.5190175771713257f,-0.29394879937171936f,-2.029303550720215f,1.6247004270553589f,0.7122467160224915f,0.3484981060028076f,-2.1400225162506104f}, {1.007614254951477f,-0.9092363715171814f,0.37182438373565674f,1.7689789533615112f,-0.4636596143245697f,0.44717833399772644f,-0.20339298248291016f,1.655295729637146f,-2.704533576965332f,0.4038698971271515f,1.1270475387573242f,-0.9903129935264587f,-0.006957195699214935f,0.191023051738739f,0.26688337326049805f,-0.8353675007820129f}, {0.3204830288887024f,-0.3771741986274719f,-0.40320003032684326f,0.8849078416824341f,-0.39249494671821594f,-0.11090171337127686f,0.1533789038658142f,-0.33072859048843384f,0.2818801701068878f,0.6622859239578247f,0.36905643343925476f,-0.027050090953707695f,0.031340520828962326f,0.22625774145126343f,0.10493969917297363f,1.2014644145965576f}, {-0.027245059609413147f,-0.12394643574953079f,0.19847965240478516f,0.049304619431495667f,0.21819953620433807f,0.5548239350318909f,-0.2404318004846573f,0.34036731719970703f,0.2525804936885834f,-0.22883126139640808f,-0.282358318567276f,0.26164373755455017f,0.054766684770584106f,-0.10002446919679642f,-0.22268100082874298f,0.2973868250846863f}, {0.06438226252794266f,-0.07111430168151855f,0.4127817749977112f,-0.06975249946117401f,-0.26233044266700745f,-0.24256393313407898f,-0.32001304626464844f,-0.22010767459869385f,0.21593058109283447f,0.0920371562242508f,-0.02842799946665764f,0.06874515116214752f,0.13893914222717285f,0.04359567537903786f,0.0479682981967926f,0.15775953233242035f}, {-0.1833210438489914f,0.18803685903549194f,0.20282304286956787f,0.1314825862646103f,0.10088987648487091f,0.17484170198440552f,0.04202890396118164f,0.11449118703603745f,0.14355172216892242f,-0.01671559177339077f,-0.07656802237033844f,0.04497041553258896f,-0.010590135119855404f,-0.04078643396496773f,0.0668090283870697f,-0.31613799929618835f}, {0.03417176753282547f,-0.3786371052265167f,-0.40439701080322266f,-0.0856500118970871f,-0.07531658560037613f,-0.010137107223272324f,-0.15568238496780396f,-0.07548399269580841f,-0.09875830262899399f,-0.022417474538087845f,-0.19422344863414764f,0.024653606116771698f,-0.006860379129648209f,0.06817493587732315f,-0.08245879411697388f,-0.16006922721862793f}, {-0.02824515290558338f,-0.056637030094861984f,0.16706281900405884f,0.02173255942761898f,-0.07349086552858353f,0.11741489917039871f,-0.041414469480514526f,-0.003831858281046152f,0.17465364933013916f,0.020348260179162025f,0.14337372779846191f,0.13839061558246613f,0.052412476390600204f,-0.013077993877232075f,0.29427415132522583f,0.19772164523601532f}, }; const float h2[16][16] = { {-0.09101764857769012f,0.4054962396621704f,-0.06966331601142883f,0.9045584797859192f,-0.21907491981983185f,3.1151559352874756f,0.0655006542801857f,0.0446651317179203f,-0.43008196353912354f,-0.1415480375289917f,-0.7361615896224976f,-5.880949974060059f,-0.02717401273548603f,0.7095373868942261f,0.7991701364517212f,0.32784658670425415f}, {0.4075763523578644f,-0.16204024851322174f,0.057057321071624756f,0.28799089789390564f,-0.35503754019737244f,-0.3077959418296814f,-0.667557954788208f,-0.3348168432712555f,-0.33757925033569336f,0.2895788848400116f,-0.10099255293607712f,0.3099772334098816f,0.17714782059192657f,0.2539375424385071f,-1.1278986930847168f,-0.3848106861114502f}, {-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.16781355440616608f,-1.205681324005127f,-0.2894435524940491f,-3.0178229808807373f,0.08946844935417175f,0.8701988458633423f,-0.5534926652908325f,0.3662342131137848f,0.26211628317832947f,0.2953031361103058f,-0.7005969882011414f,-0.9946783781051636f,-0.4869251847267151f,-0.010542111471295357f,0.6177319884300232f,0.12078813463449478f}, {-0.7870347499847412f,1.358780026435852f,-0.25313520431518555f,1.5327919721603394f,0.036378175020217896f,0.3244888186454773f,-0.4755769968032837f,-0.13222959637641907f,-0.024399548768997192f,-0.39465832710266113f,0.3770657181739807f,-2.188513994216919f,-0.18945904076099396f,-1.564217448234558f,0.08839760720729828f,0.8966508507728577f}, {0.5386860370635986f,0.5304108262062073f,-0.3519742488861084f,0.8151957988739014f,-0.3015052080154419f,0.10101134330034256f,-0.6611042618751526f,-0.06323602795600891f,-0.23047015070915222f,0.3579089343547821f,1.0146384239196777f,-1.816729187965393f,-0.39870911836624146f,1.8494337797164917f,1.6129482984542847f,-0.654404878616333f}, {-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.10344250500202179f,0.8851874470710754f,0.33083590865135193f,-0.9450300931930542f,-0.14358049631118774f,-0.8879885077476501f,-0.33660444617271423f,-0.3461519777774811f,0.2600560486316681f,-0.37898191809654236f,-2.4927995204925537f,0.6799273490905762f,-0.44419312477111816f,0.22575414180755615f,0.7631748914718628f,0.8120167851448059f}, {-0.24644257128238678f,0.17985285818576813f,-0.11379697918891907f,1.467590570449829f,0.041274964809417725f,-1.0506867170333862f,-0.34555327892303467f,-0.042685262858867645f,0.06103590130805969f,-0.38046833872795105f,-1.560768485069275f,-0.37289687991142273f,-0.6082977652549744f,-0.3297945559024811f,-1.903340220451355f,0.07766012102365494f}, {0.3750182092189789f,0.9095179438591003f,-0.13502129912376404f,-1.1646559238433838f,0.12987366318702698f,0.48973721265792847f,-0.14360187947750092f,-0.3632148504257202f,-0.13619378209114075f,0.16938945651054382f,0.9756120443344116f,1.5680875778198242f,0.015860414132475853f,-1.8316001892089844f,0.03364758938550949f,-0.6048874258995056f}, {0.001020657131448388f,-0.5778871774673462f,0.0457797646522522f,-1.3335444927215576f,-0.03321319818496704f,0.22450630366802216f,-0.2756686508655548f,-0.20421427488327026f,-0.050184011459350586f,0.12480869889259338f,-1.364320993423462f,-4.172216415405273f,-0.5792499780654907f,-0.1589745730161667f,-1.0930994749069214f,0.12804484367370605f}, {0.6292679309844971f,0.45306727290153503f,0.3954955041408539f,0.12690812349319458f,0.0033026933670043945f,0.39511117339134216f,-0.47955650091171265f,-0.1643170565366745f,0.3487861454486847f,-0.32520344853401184f,1.591291069984436f,-0.9511956572532654f,-0.10463692247867584f,-0.5788776278495789f,0.9301892518997192f,0.7921565175056458f}, {-1.9094338417053223f,1.0912913084030151f,-0.15798500180244446f,-0.20790745317935944f,-0.37393757700920105f,1.779664158821106f,-0.11615815758705139f,-0.3357280492782593f,-0.3764709532260895f,0.2424570620059967f,0.11706706136465073f,-0.4618774652481079f,0.0839148759841919f,0.1465109884738922f,0.07200270146131516f,0.1898588389158249f}, {1.2760099172592163f,0.2635939121246338f,-0.2018718123435974f,-0.21050289273262024f,0.07545611262321472f,0.15267306566238403f,-0.41120466589927673f,-0.22413749992847443f,-0.24509364366531372f,0.19522181153297424f,-0.168448343873024f,-0.49023303389549255f,-0.43267005681991577f,-0.11180825531482697f,-2.4520909786224365f,-2.2206997871398926f}, {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.3850473165512085f,0.60502028465271f,0.12081471085548401f,0.05673016980290413f,0.29976895451545715f,0.07498054951429367f,-0.19028231501579285f,0.2637995183467865f,-0.3893685042858124f,-0.02222958207130432f,1.285120964050293f,0.1741940826177597f,-0.5410208106040955f,0.5510839223861694f,0.7903842926025391f,0.19116832315921783f}, }; const float h3[16][16] = { {-0.36079341173171997f,-2.0394980907440186f,0.027777254581451416f,-0.22982019186019897f,-0.01932685822248459f,0.07987586408853531f,0.16453437507152557f,0.1481759250164032f,-1.8260695934295654f,-0.12922662496566772f,-0.10849133133888245f,0.08728101849555969f,0.167767733335495f,0.313822865486145f,-0.535399854183197f,-0.027188511565327644f}, {0.047732532024383545f,0.9618076086044312f,0.3481678366661072f,-0.8452519774436951f,-0.9864906072616577f,0.6582698225975037f,-0.35969480872154236f,-0.16095684468746185f,0.8305681943893433f,-0.3994109034538269f,0.29745107889175415f,-0.647723376750946f,-0.30517578125f,0.9108673930168152f,-0.5965732336044312f,-1.6962358951568604f}, {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,-1.4941678047180176f,-1.079818844795227f,0.9250527620315552f,0.06139156222343445f,0.08592525869607925f,0.027424758300185204f,0.04547649249434471f,-1.5056060552597046f,-0.365601509809494f,-0.16192401945590973f,0.15959054231643677f,-1.0692600011825562f,0.4283374547958374f,-0.47111794352531433f,-0.4709107577800751f}, {-0.39607733488082886f,-0.05481579899787903f,0.1976260244846344f,0.022423356771469116f,0.16892847418785095f,-0.27518749237060547f,0.16012099385261536f,0.3626593053340912f,-0.08640444278717041f,-0.11053556203842163f,-0.10529157519340515f,-0.31317979097366333f,-0.1530032455921173f,-0.1336749792098999f,0.22959044575691223f,0.19986507296562195f}, {-0.37449589371681213f,-0.4369526505470276f,-1.208013892173767f,0.7252630591392517f,0.5089448690414429f,0.3422243297100067f,-0.3449169099330902f,0.055282652378082275f,-0.3138900697231293f,-0.3560298979282379f,-0.20816515386104584f,-0.054754588752985f,-0.012407035566866398f,0.49851128458976746f,-0.5612673759460449f,-0.7927249073982239f}, {0.4110594093799591f,0.1920347660779953f,-0.21054792404174805f,0.23240651190280914f,0.1802571415901184f,-0.16077619791030884f,-0.08670487999916077f,-0.25336313247680664f,-0.030661463737487793f,-0.06259563565254211f,-0.1344406008720398f,0.35313835740089417f,0.38961368799209595f,0.008103481493890285f,0.12098627537488937f,-0.28980788588523865f}, {-0.40892091393470764f,0.07973587512969971f,-0.4225347340106964f,0.22082245349884033f,0.30674463510513306f,-0.015164071694016457f,-0.23312048614025116f,-0.390264093875885f,0.28059282898902893f,-0.1559126079082489f,-0.14134526252746582f,-0.0003446042537689209f,-0.30998891592025757f,-0.33052098751068115f,0.11553362011909485f,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,1.2427574396133423f,0.193179652094841f,-0.7398805618286133f,-0.4817911982536316f,-0.0939035415649414f,-0.055489517748355865f,-0.13401247560977936f,1.5515689849853516f,-0.47839227318763733f,-0.03722834214568138f,-0.6830673217773438f,0.958594024181366f,-0.6970508098602295f,0.15626497566699982f,1.2517952919006348f}, {-0.408692330121994f,-0.6441293358802795f,0.3579084873199463f,0.5667678117752075f,1.1648471355438232f,1.0393614768981934f,0.03285527229309082f,0.38763079047203064f,-0.6279672384262085f,-0.25883403420448303f,0.12809070944786072f,0.03996849060058594f,0.23974189162254333f,0.6196199059486389f,0.9762318730354309f,-0.3892173171043396f}, {-0.2991822361946106f,-0.009154408238828182f,0.13385441899299622f,-0.05932474136352539f,0.32624977827072144f,-0.14997488260269165f,-0.11253207921981812f,0.34576353430747986f,0.04814547300338745f,-0.35770976543426514f,-0.044228196144104004f,-0.36229726672172546f,0.37819206714630127f,-0.2522141933441162f,0.1280381679534912f,0.020418301224708557f}, {-0.2675279378890991f,0.22752805054187775f,0.9918881058692932f,-0.3263375759124756f,-0.49688720703125f,-0.6219033002853394f,-0.5266007781028748f,-0.5405108332633972f,1.1606967449188232f,-0.6998274326324463f,-0.6930839419364929f,-0.783081591129303f,0.5205210447311401f,-0.2892443835735321f,-0.4750079810619354f,1.0206432342529297f}, {-0.015470266342163086f,-1.648854374885559f,-0.2384277582168579f,-2.0957741737365723f,-1.6361477375030518f,0.43126505613327026f,0.05196094512939453f,-0.18505549430847168f,-2.268740653991699f,-0.5114141702651978f,-0.03054753504693508f,-0.11511552333831787f,-0.7582811713218689f,0.5420505404472351f,-0.5685442090034485f,-0.9316728711128235f}, {0.1863725483417511f,0.7245519161224365f,0.3409687578678131f,-0.9061988592147827f,1.1212410926818848f,-0.5218710899353027f,0.04860696196556091f,0.12026743590831757f,-1.0126233100891113f,0.03679993748664856f,-0.3252358138561249f,0.10295852273702621f,0.978594183921814f,-0.625475287437439f,1.5447208881378174f,-0.03620874881744385f}, }; const float hout[16] = { 0.45773375034332275f,0.17375539243221283f,-0.23764771223068237f,-0.09143640846014023f,-0.16163280606269836f,0.23837842047214508f,-0.05339581519365311f,-0.03423803672194481f,-0.15247350931167603f,0.0028862894978374243f,-0.025371452793478966f,0.005703639704734087f,-0.16284745931625366f,-0.11569779366254807f,0.14603784680366516f,-0.16416245698928833f }; const float b1[16] = { 0.6616275310516357f,-0.13481281697750092f,-1.7145336866378784f,0.07440292090177536f,0.8951196074485779f,1.0816856622695923f,-0.058932315558195114f,1.3293917179107666f,0.020480668172240257f,-0.5892835259437561f,0.21089354157447815f,1.3534598350524902f,-1.2202963829040527f,-1.9916216135025024f,-1.087764859199524f,0.9760429859161377f }; const float b2[16] = { -0.09380006790161133f,-1.064509630203247f,-1.4564176797866821f,0.2678755223751068f,-0.6939148902893066f,-0.12803801894187927f,0.10122966021299362f,-0.35512855648994446f,-1.20063054561615f,-1.912178635597229f,0.1515641063451767f,0.8412038087844849f,-0.415097177028656f,1.7469533681869507f,0.5643869042396545f,1.505944848060608f }; const float b3[16] = { -1.963319182395935f,-0.021264158189296722f,-1.0536612272262573f,0.7838545441627502f,-0.9922052621841431f,1.3160772323608398f,-0.6213743686676025f,-0.8503386974334717f,-1.0721707344055176f,0.18971462547779083f,-0.4227040708065033f,-0.3531782329082489f,-1.2684650421142578f,-0.21604318916797638f,-0.9929291605949402f,-0.17358574271202087f }; const float bout[1] = { -0.18828609585762024f }; /////////////////////////////////////////////////////////////////////////////////////////////RL float input_RL[num_input_RL] = { 0.0f }; //Critic Networks float hc1[num_input_RL][num_hidden_unit1] = {0.0f}; float bc1[num_hidden_unit1] = {0.0f}; float hc2[num_hidden_unit1][num_hidden_unit2] = {0.0f}; float bc2[num_hidden_unit2] = {0.0f}; float hc3[num_hidden_unit2] = {0.0f}; float bc3 = 0.0f; //Critic Networks Temporary float hc1_temp[num_input_RL][num_hidden_unit1] = {0.0f}; float bc1_temp[num_hidden_unit1] = {0.0f}; float hc2_temp[num_hidden_unit1][num_hidden_unit2] = {0.0f}; float bc2_temp[num_hidden_unit2] = {0.0f}; float hc3_temp[num_hidden_unit2] = {0.0f}; float bc3_temp = 0.0f; //Actor Networks float ha1[num_input_RL][num_hidden_unit1] = {0.0f}; float ba1[num_hidden_unit1] = {0.0f}; float ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f}; float ba2[num_hidden_unit2] = {0.0f}; float ha3[num_hidden_unit2][2] = {0.0f}; float ba3[2] = {0.0f}; //Actor Networks Temporary float ha1_temp[num_input_RL][num_hidden_unit1] = {0.0f}; float ba1_temp[num_hidden_unit1] = {0.0f}; float ha2_temp[num_hidden_unit1][num_hidden_unit2] = {0.0f}; float ba2_temp[num_hidden_unit2] = {0.0f}; float ha3_temp[num_hidden_unit2][2] = {0.0f}; float ba3_temp[2] = {0.0f}; float VALVE_POS_RAW_NN = 0.0f; float DDV_JOINT_POS_FF(float REF_JOINT_VEL); /////////////////////////////////////////////RL tuning float Gradient_Limit = 0.5f; float gradient_rate_actor = 0.001f; float gradient_rate_critic = 0.001f; ////////////////////////////////////////////////////////////////////////////// float Critic_Network_Temp(float *arr) { float output1[num_hidden_unit1] = { 0.0f }; float output2[num_hidden_unit2] = { 0.0f }; float output = 0.0f; for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { output1[index2] = output1[index2] + hc1_temp[index1][index2] * arr[index1]; } //ReLU output1[index2] = output1[index2] + bc1_temp[index2]; hx_c_sum[index2] = output1[index2]; if (output1[index2] < 0) { output1[index2] = 0; } //tanh //output1[index2] = tanh(output1[index2] + bc1_temp[index2]); } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { output2[index2] = output2[index2] + hc2_temp[index1][index2] * output1[index1]; } //ReLU output2[index2] = output2[index2] + bc2_temp[index2]; hxh_c_sum[index2] = output2[index2]; if (output2[index2] < 0) { output2[index2] = 0; } //tanh //output2[index2] = tanh(output2[index2] + bc2_temp[index2]); } for (int index2 = 0; index2 < 1; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { output = output + hc3_temp[index1] * output2[index1]; } output = output + bc3_temp; hxhh_c_sum = output; } return output; } void Actor_Network(float *arr) { float output1[num_hidden_unit1] = {0.0f}; float output2[num_hidden_unit2] = {0.0f}; float output[2] = {0.0f}; for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { output1[index2] = output1[index2] + ha1_temp[index1][index2] * arr[index1]; } output1[index2] = output1[index2] + ba1_temp[index2]; hx_a_sum[index2] = output1[index2]; if (output1[index2] < 0) { output1[index2] = 0; } } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { output2[index2] = output2[index2] + ha2_temp[index1][index2] * output1[index1]; } output2[index2] = output2[index2] + ba2_temp[index2]; hxh_a_sum[index2] = output2[index2]; if (output2[index2] < 0) { output2[index2] = 0; } } for (int index2 = 0; index2 < 2; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { output[index2] = output[index2] + ha3_temp[index1][index2] * output2[index1]; } hxhh_a_sum[index2] = output[index2] + ba3_temp[index2]; } mean_before_SP = output[0] + ba3_temp[0]; //SP = softplus deviation_before_SP = output[1] + ba3_temp[1]; //Softplus mean = log(1.0f+exp(mean_before_SP)); deviation = log(1.0f+exp(deviation_before_SP)); logging2 = mean; logging4 = deviation; } void Actor_Network_Old(float *arr) { float output1[num_hidden_unit1] = {0.0f}; float output2[num_hidden_unit2] = {0.0f}; float output[2] = {0.0f}; for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { output1[index2] = output1[index2] + ha1[index1][index2] * arr[index1]; } output1[index2] = output1[index2] + ba1[index2]; if (output1[index2] < 0) { output1[index2] = 0; } } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { output2[index2] = output2[index2] + ha2[index1][index2] * output1[index1]; } output2[index2] = output2[index2] + ba2[index2]; if (output2[index2] < 0) { output2[index2] = 0; } } for (int index2 = 0; index2 < 2; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { output[index2] = output[index2] + ha3[index1][index2] * output2[index1]; } } mean_old = output[0] + ba3[0]; deviation_old = output[1] + ba3[1]; //Softplus mean_old = log(1.0f+exp(mean_old)); deviation_old = log(1.0f+exp(deviation_old)); } float Grad_Normal_Dist_Mean(float mean, float deviation, float action) { float grad_mean = 0.0f; grad_mean = (action-mean)*exp(-(action-mean)*(action-mean)/(2.0f*deviation*deviation))/(sqrt(2.0f*PI)*deviation*deviation*deviation); return grad_mean; } float Grad_Normal_Dist_Deviation(float mean, float deviation, float action) { float grad_dev = 0.0f; grad_dev = exp(-(action-mean)*(action-mean)/(2.0f*deviation*deviation))*(-1.0f/(sqrt(2.0f*PI)*deviation*deviation) + (action-mean)*(action-mean)/(sqrt(2.0f*PI)*deviation*deviation*deviation*deviation)); return grad_dev; } float ReLU(float x) { if (x >= 0) { return x; } else { return 0.0f; } } void update_Critic_Networks(float (*arr)[num_input_RL]) { float G_hc1[num_input_RL][num_hidden_unit1] = {0.0f}; float G_bc1[num_hidden_unit1] = {0.0f}; for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { for (int n=0; n<batch_size; n++) { float d_V_d_hc1 = 0.0f; for(int k=0; k<num_hidden_unit2; k++) { if (hxh_c_sum_array[n][k] >= 0) { if (hx_c_sum_array[n][index2] > 0) { d_V_d_hc1 = d_V_d_hc1 + arr[n][index1]*hc2_temp[index2][k]*hc3_temp[k]; } } } G_hc1[index1][index2] = G_hc1[index1][index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc1); } G_hc1[index1][index2] = G_hc1[index1][index2] / batch_size; if(G_hc1[index1][index2] > Gradient_Limit) G_hc1[index1][index2] = Gradient_Limit; else if (G_hc1[index1][index2] < -Gradient_Limit) G_hc1[index1][index2] = -Gradient_Limit; //hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate_critic * G_hc1[index1][index2]; } for (int n=0; n<batch_size; n++) { float d_V_d_bc1 = 0.0f; for(int k=0; k<num_hidden_unit2; k++) { if (hxh_c_sum_array[n][k] >= 0) { if (hx_c_sum_array[n][index2] > 0) { d_V_d_bc1 = d_V_d_bc1 + hc2_temp[index2][k]*hc3_temp[k]; } } } G_bc1[index2] = G_bc1[index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc1); } G_bc1[index2] = G_bc1[index2] / batch_size; if(G_bc1[index2] > Gradient_Limit) G_bc1[index2] = Gradient_Limit; else if (G_bc1[index2] < -Gradient_Limit) G_bc1[index2] = -Gradient_Limit; //bc1_temp[index2] = bc1_temp[index2] - gradient_rate_critic * G_bc1[index2]; } float G_hc2[num_hidden_unit1][num_hidden_unit2] = {0.0f}; float G_bc2[num_hidden_unit2] = {0.0f}; for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { for (int n=0; n<batch_size; n++) { float d_V_d_hc2 = 0.0f; if (hxh_c_sum_array[n][index2] >= 0) { if (hx_c_sum_array[n][index1] > 0) { d_V_d_hc2 = hx_c_sum_array[n][index1]*hc3_temp[index2]; } } G_hc2[index1][index2] = G_hc2[index1][index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc2); } G_hc2[index1][index2] = G_hc2[index1][index2] / batch_size; if(G_hc2[index1][index2] > Gradient_Limit) G_hc2[index1][index2] = Gradient_Limit; else if (G_hc2[index1][index2] < -Gradient_Limit) G_hc2[index1][index2] = -Gradient_Limit; //hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate_critic * G_hc2[index1][index2]; } for (int n=0; n<batch_size; n++) { float d_V_d_bc2 = 0.0f; if (hxh_c_sum_array[n][index2] >= 0) { d_V_d_bc2 = hc3_temp[index2]; } G_bc2[index2] = G_bc2[index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc2); } G_bc2[index2] = G_bc2[index2] / batch_size; if(G_bc2[index2] > Gradient_Limit) G_bc2[index2] = Gradient_Limit; else if (G_bc2[index2] < -Gradient_Limit) G_bc2[index2] = -Gradient_Limit; //bc2_temp[index2] = bc2_temp[index2] - gradient_rate_critic * G_bc2[index2]; } float G_hc3[num_hidden_unit2]= {0.0f}; float G_bc3 = 0.0f; for (int index2 = 0; index2 < 1; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { for (int n=0; n<batch_size; n++) { float d_V_d_hc3 = 0.0f; if (hxh_c_sum_array[n][index1] >= 0) { d_V_d_hc3 = d_V_d_hc3 + hxh_c_sum_array[n][index1]; } G_hc3[index1] = G_hc3[index1] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc3); } G_hc3[index1] = G_hc3[index1] / batch_size; if(G_hc3[index1] > Gradient_Limit) G_hc3[index1] = Gradient_Limit; else if (G_hc3[index1] < -Gradient_Limit) G_hc3[index1] = -Gradient_Limit; //hc3_temp[index1] = hc3_temp[index1] - gradient_rate_critic * G_hc3[index1]; } for (int n=0; n<batch_size; n++) { float d_V_d_bc3 = 0.0f; d_V_d_bc3 = 1.0f; G_bc3 = G_bc3 + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc3); } G_bc3 = G_bc3 / batch_size; if(G_bc3 > Gradient_Limit) G_bc3 = Gradient_Limit; else if (G_bc3 < -Gradient_Limit) G_bc3 = -Gradient_Limit; //bc3_temp = bc3_temp - gradient_rate_critic * G_bc3; } // Simultaneous Update for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate_critic * G_hc1[index1][index2]; } bc1_temp[index2] = bc1_temp[index2] - gradient_rate_critic * G_bc1[index2]; } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate_critic * G_hc2[index1][index2]; } bc2_temp[index2] = bc2_temp[index2] - gradient_rate_critic * G_bc2[index2]; } for (int index2 = 0; index2 < 1; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { hc3_temp[index1] = hc3_temp[index1] - gradient_rate_critic * G_hc3[index1]; } bc3_temp = bc3_temp - gradient_rate_critic * G_bc3; } } ///////////////////////////Softplus////////////////////////////////// void update_Actor_Networks(float (*arr)[num_input_RL]) { float G_ha1[num_input_RL][num_hidden_unit1] = {0.0f}; float G_ba1[num_hidden_unit1] = {0.0f}; for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { for (int n=0; n<batch_size; n++) { float d_x_d_ha1 = 0.0f; float d_y_d_ha1 = 0.0f; if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) { G_ha1[index1][index2] = G_ha1[index1][index2]; } else { for(int k=0; k<num_hidden_unit2; k++) { if (hxh_a_sum_array[n][k] >= 0) { if (hx_a_sum_array[n][index2] > 0) { d_x_d_ha1 = d_x_d_ha1 + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][0]; d_y_d_ha1 = d_y_d_ha1 + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][1]; } } } float d_mean_d_ha1 = 0.0f; float d_dev_d_ha1 = 0.0f; d_mean_d_ha1 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha1; d_dev_d_ha1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha1; G_ha1[index1][index2] = G_ha1[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha1*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha1*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n])); } } G_ha1[index1][index2] = -G_ha1[index1][index2] / batch_size; if(G_ha1[index1][index2] > Gradient_Limit) G_ha1[index1][index2] = Gradient_Limit; else if (G_ha1[index1][index2] < -Gradient_Limit) G_ha1[index1][index2] = -Gradient_Limit; //ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate_actor * G_ha1[index1][index2]; } for (int n=0; n<batch_size; n++) { float d_x_d_ba1 = 0.0f; float d_y_d_ba1 = 0.0f; if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) { G_ba1[index2] = G_ba1[index2]; } else { for(int k=0; k<num_hidden_unit2; k++) { if (hxh_a_sum_array[n][k] >= 0) { if (hx_a_sum_array[n][index2] > 0) { d_x_d_ba1 = d_x_d_ba1 + ha2_temp[index2][k]*ha3_temp[k][0]; d_y_d_ba1 = d_y_d_ba1 + ha2_temp[index2][k]*ha3_temp[k][1]; } } } float d_mean_d_ba1 = 0.0f; float d_dev_d_ba1 = 0.0f; d_mean_d_ba1 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba1; d_dev_d_ba1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba1; G_ba1[index2] = G_ba1[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba1*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba1*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n])); } } G_ba1[index2] = -G_ba1[index2] / batch_size; if(G_ba1[index2] > Gradient_Limit) G_ba1[index2] = Gradient_Limit; else if (G_ba1[index2] < -Gradient_Limit) G_ba1[index2] = -Gradient_Limit; //ba1_temp[index2] = ba1_temp[index2] - gradient_rate_actor * G_ba1[index2]; } float G_ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f}; float G_ba2[num_hidden_unit2] = {0.0f}; for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { for (int n=0; n<batch_size; n++) { float d_x_d_ha2 = 0.0f; float d_y_d_ha2 = 0.0f; if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) { G_ha2[index1][index2] = G_ha2[index1][index2]; } else { if (hxh_a_sum_array[n][index2] >= 0) { if (hx_a_sum_array[n][index1] > 0) { d_x_d_ha2 = hx_a_sum_array[n][index1]*ha3_temp[index2][0]; d_y_d_ha2 = hx_a_sum_array[n][index1]*ha3_temp[index2][1]; } } float d_mean_d_ha2 = 0.0f; float d_dev_d_ha2 = 0.0f; d_mean_d_ha2 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha2; d_dev_d_ha2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha2; G_ha2[index1][index2] = G_ha2[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha2*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha2*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n])); } } G_ha2[index1][index2] = -G_ha2[index1][index2] / batch_size; if(G_ha2[index1][index2] > Gradient_Limit) G_ha2[index1][index2] = Gradient_Limit; else if (G_ha2[index1][index2] < -Gradient_Limit) G_ha2[index1][index2] = -Gradient_Limit; //ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate_actor * G_ha2[index1][index2]; } for (int n=0; n<batch_size; n++) { float d_x_d_ba2 = 0.0f; float d_y_d_ba2 = 0.0f; if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) { G_ba2[index2] = G_ba2[index2]; } else { if (hxh_a_sum_array[n][index2] >= 0) { d_x_d_ba2 = ha3_temp[index2][0]; d_y_d_ba2 = ha3_temp[index2][1]; } float d_mean_d_ba2= 0.0f; float d_dev_d_ba2= 0.0f; d_mean_d_ba2 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba2; d_dev_d_ba2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba2; G_ba2[index2] = G_ba2[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba2*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba2*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n])); } } G_ba2[index2] = -G_ba2[index2] / batch_size; if(G_ba2[index2] > Gradient_Limit) G_ba2[index2] = Gradient_Limit; else if (G_ba2[index2] < -Gradient_Limit) G_ba2[index2] = -Gradient_Limit; //ba2_temp[index2] = ba2_temp[index2] - gradient_rate_actor * G_ba2[index2]; } float G_ha3[num_hidden_unit2][2] = {0.0f}; float G_ba3[2] = {0.0f}; for (int index2 = 0; index2 < 2; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { for (int n=0; n<batch_size; n++) { float d_x_d_ha3 = 0.0f; float d_y_d_ha3 = 0.0f; if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) { G_ha3[index1][index2] = G_ha3[index1][index2]; } else { if (hxh_a_sum_array[n][index1] >= 0) { if (hx_a_sum_array[n][index1] > 0) { d_x_d_ha3 = hxh_a_sum_array[n][index1]; d_y_d_ha3 = hxh_a_sum_array[n][index1]; } } float d_mean_d_ha3 = 0.0f; float d_dev_d_ha3 = 0.0f; d_mean_d_ha3 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha3; d_dev_d_ha3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha3; G_ha3[index1][index2] = G_ha3[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha3*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha3*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n])); } } G_ha3[index1][index2] = -G_ha3[index1][index2] / batch_size; if(G_ha3[index1][index2] > Gradient_Limit) G_ha3[index1][index2] = Gradient_Limit; else if (G_ha3[index1][index2] < -Gradient_Limit) G_ha3[index1][index2] = -Gradient_Limit; //ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate_actor * G_ha3[index1][index2]; } for (int n=0; n<batch_size; n++) { float d_x_d_ba3 = 0.0f; float d_y_d_ba3 = 0.0f; if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) { G_ba3[index2] = G_ba3[index2]; } else { d_x_d_ba3 = 1.0f; d_y_d_ba3 = 1.0f; float d_mean_d_ba3= 0.0f; float d_dev_d_ba3= 0.0f; d_mean_d_ba3 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba3; d_dev_d_ba3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba3; G_ba3[index2] = G_ba3[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba3*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba3*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n])); } } G_ba3[index2] = -G_ba3[index2] / batch_size; if(G_ba3[index2] > Gradient_Limit) G_ba3[index2] = Gradient_Limit; else if (G_ba3[index2] < -Gradient_Limit) G_ba3[index2] = -Gradient_Limit; //ba3_temp[index2] = ba3_temp[index2] - gradient_rate_actor * G_ba3[index2]; } // Simultaneous Update for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate_actor * G_ha1[index1][index2]; } ba1_temp[index2] = ba1_temp[index2] - gradient_rate_actor * G_ba1[index2]; } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate_actor * G_ha2[index1][index2]; } ba2_temp[index2] = ba2_temp[index2] - gradient_rate_actor * G_ba2[index2]; } for (int index2 = 0; index2 < 2; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate_actor * G_ha3[index1][index2]; } ba3_temp[index2] = ba3_temp[index2] - gradient_rate_actor * G_ba3[index2]; } } float rand_normal(double mean, double stddev) { //Box muller method static double n2 = 0.0f; static int n2_cached = 0; if (!n2_cached) { double x, y, r; do { x = 2.0f*rand()/RAND_MAX - 1; y = 2.0f*rand()/RAND_MAX - 1; r = x*x + y*y; } while (r == 0.0f || r > 1.0f); { double d = sqrt(-2.0f*log(r)/r); double n1 = x*d; n2 = y*d; double result = n1*stddev + mean; n2_cached = 1; return result; } } else { n2_cached = 0; return n2*stddev + mean; } } float mean_adv(float x[], int size) { float add = 0.0f; float result; for (int i=0; i<size; i++) { add += x[i]; } result = (float) add/size; return result; } float deviation_adv(float x[], int size) { float sigma = 0.0f; float resultDeb = 0.0f; for (int k=0; k<size; k++) { sigma = pow((float)x[k]-mean_adv(x,size), (float)2.0f)/(size-1); resultDeb += sqrt(sigma); } return resultDeb; } void Overwirte_Critic_Networks() { for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { hc1[index1][index2] = hc1_temp[index1][index2]; } bc1[index2] = bc1_temp[index2]; } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { hc2[index1][index2] = hc2_temp[index1][index2]; } bc2[index2] = bc2_temp[index2]; hc3[index2] = hc3_temp[index2]; } bc3 = bc3_temp; } void Overwirte_Actor_Networks() { for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { ha1[index1][index2] = ha1_temp[index1][index2]; } ba1[index2] = ba1_temp[index2]; } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { ha2[index1][index2] = ha2_temp[index1][index2]; } ba2[index2] = ba2_temp[index2]; } for (int index2 = 0; index2 < 2; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { ha3[index1][index2] = ha3_temp[index1][index2]; } ba3[index2] = ba3_temp[index2]; } } int main() { HAL_Init(); SystemClock_Config(); /********************************* *** Initialization *********************************/ 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.007f ; } bc1_temp[index2] = (float) (rand()%100) * 0.007f; } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { hc2_temp[index1][index2] = (float) (rand()%100) * 0.007f; } bc2_temp[index2] = (float) (rand()%100) * 0.007f; hc3_temp[index2] = (float) (rand()%100) * 0.007f; } bc3_temp = (float) (rand()%100) * 0.007f; for (int index2 = 0; index2 < num_hidden_unit1; index2++) { for (int index1 = 0; index1 < num_input_RL; index1++) { ha1_temp[index1][index2] = (float) (rand()%100) * 0.007f; } ba1_temp[index2] = (float) (rand()%100) * 0.007f; } for (int index2 = 0; index2 < num_hidden_unit2; index2++) { for (int index1 = 0; index1 < num_hidden_unit1; index1++) { ha2_temp[index1][index2] = (float) (rand()%100) * 0.007f; } ba2_temp[index2] = (float) (rand()%100) * 0.007f; } for (int index2 = 0; index2 < 2; index2++) { for (int index1 = 0; index1 < num_hidden_unit2; index1++) { ha3_temp[index1][index2] = (float) (rand()%100) * 0.007f; } ba3_temp[index2] = (float) (rand()%100) * 0.007f; } Overwirte_Critic_Networks(); Overwirte_Actor_Networks(); /************************************ *** Program is operating! *************************************/ while(1) { // if(timer_while==27491) { // 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 * 8.0f + 0.5f; ind = ind + 1; } input_NN[ind] = torq.sen / 10000.0f * 8.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 * 8.0f + 0.5f; // input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f*8.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 n=batch_size-1; n>=0; n--) { //Calculate Estimated V //float temp_array[3] = {state_array[n][0], state_array[n][1], state_array[n][2]}; float temp_array[2] = {state_array[n][0], state_array[n][1]}; V[n] = Critic_Network_Temp(temp_array); for (int i=0; i<num_hidden_unit1; i++) { hx_c_sum_array[n][i] = hx_c_sum[i]; } for (int i=0; i<num_hidden_unit2; i++) { hxh_c_sum_array[n][i] = hxh_c_sum[i]; } hxhh_c_sum_array[n] = hxhh_c_sum; pi[n] = exp(-(action_array[n]-mean_array[n])*(action_array[n]-mean_array[n])/(2.0f*deviation_array[n]*deviation_array[n]))/(sqrt(2.0f*PI)*deviation_array[n]); Actor_Network_Old(temp_array); pi_old[n] = exp(-(action_array[n]-mean_old)*(action_array[n]-mean_old)/(2.0f*deviation_old*deviation_old))/(sqrt(2.0f*PI)*deviation_old); r[n] = exp(-0.25f * 5.0f * state_array[n][1] * state_array[n][1]); if(n == batch_size-1) return_G[n] = 0.0f; else return_G[n] = gamma * return_G[n+1] + r[n]; if(n == batch_size-1) td_target[n] = r[n]; else td_target[n] = r[n] + gamma * V[n+1]; delta[n] = td_target[n] - V[n]; if(n == batch_size-1) advantage[n] = 0.0f; else advantage[n] = gamma * lmbda * advantage[n+1] + delta[n]; // return_G[n] = advantage[n] + V[n]; ratio[n] = pi[n]/pi_old[n]; } float mean_advantage = 0.0f; float dev_advantage = 0.0f; mean_advantage = mean_adv(advantage, batch_size); dev_advantage = deviation_adv(advantage, batch_size); for (int n=batch_size-1; n>=0; n--) { //advantage[n] = (advantage[n]-mean_advantage)/dev_advantage; surr1[n] = ratio[n] * advantage[n]; if (ratio[n] > 1.0f + epsilon) { surr2[n] = (1.0f + epsilon)*advantage[n]; } else if( ratio[n] < 1.0f - epsilon) { surr2[n] = (1.0f - epsilon)*advantage[n]; } else { surr2[n] = ratio[n]*advantage[n]; } loss[n] = -min(surr1[n], surr2[n]); loss_sum = loss_sum + loss[n]; } reward_sum = 0.0f; for (int i=0; i<batch_size; i++) { reward_sum = reward_sum + r[i]; } logging5 = reward_sum; //loss_batch = loss_sum / (float) batch_size; loss_batch = loss_sum; //Update Networks update_Critic_Networks(state_array); update_Actor_Networks(state_array); } Update_Done_Flag = 1; Update_Case = 0; //logging1 = V[0]; break; } case 2: { //Network apply to next Network Overwirte_Critic_Networks(); Overwirte_Actor_Networks(); virt_pos = 10.0f; Update_Done_Flag = 1; Update_Case = 0; break; } } } } 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; action_array[RL_timer] = rand_normal(mean_array[RL_timer], deviation_array[RL_timer]); virt_pos = virt_pos + (action_array[RL_timer] - 5.0f) * 1000.0f * 0.0002f; if (virt_pos > 70 ) { virt_pos = 70.0f; }else if(virt_pos < -70) { virt_pos = -70.0f; } RL_timer++; if (RL_timer >= batch_size) { RL_timer = 0; batch++; for(int i=0; i<batch_size; i++) { state_array[i][0] = train_set_x[i]; state_array[i][1] = train_set_error[i]; //state_array[i][2] = train_set_count[i]; } Update_Case = 1; Update_Done_Flag = 0; logging1 = virt_pos; if(batch >= num_batch) { batch = 0; RL_timer = 0; Update_Case = 2; Update_Done_Flag = 0; virt_pos = 10.0f; } } } else { pos.err = pos.sen/(float)(ENC_PULSE_PER_POSITION) - virt_pos; //[mm] float temp_array[3] = {0.0f}; temp_array[0] = virt_pos/70.0f; //-1.0~1.0 temp_array[1] = pos.err/70.0f; //-1.0~1.0 //temp_array[2] = (float) RL_timer / (batch_size *num_batch); //-1.0~1.0 Actor_Network(temp_array); action = rand_normal(mean, deviation); //logging1 = action; //logging2 = mean; //logging4 = deviation; virt_pos = virt_pos + (action-5.0f) * 1000.0f * 0.0002f; if (virt_pos > 70) { virt_pos = 70.0f; }else if(virt_pos < -70) { virt_pos = -70.0f; } logging3 = virt_pos; } //t.stop(); //logging1 = t.read()*1000.0f; //msec break; } default: break; } 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) { CAN_TX_TORQUE((int16_t) (return_G[0]*100.0f)); //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) (V[0]*100.0f)); //1500 CAN_TX_PWM((int16_t) (f_future[1])); //1500 } if (flag_data_request[4] == HIGH) { //valve position CAN_TX_VALVE_POSITION((int16_t) pos.sen/(float)(ENC_PULSE_PER_POSITION), (int16_t) virt_pos, (int16_t) (logging2*1000.0f), (int16_t) (logging4*1000.0f)); //1600 //CAN_TX_VALVE_POSITION((int16_t) action_array[20], (int16_t) virt_pos, (int16_t) Update_Case*1000, (int16_t) (logging4*1000.0f)); //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 }