Sungwoo Kim
/
HydraulicControlBoard_Base
distribution-201229
main.cpp
- Committer:
- Lightvalve
- Date:
- 2020-12-24
- Revision:
- 215:9aa288c10f68
- Parent:
- 214:231d27008443
- Child:
- 216:a81419fb58ea
File content as of revision 215:9aa288c10f68:
//201224_2 #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 torq_dot; 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] = { {-0.3518959879875183f,-1.0181971788406372f,0.5238839387893677f,0.07460802793502808f,0.4083598852157593f,0.5267895460128784f,-0.24204020202159882f,0.022494137287139893f,-0.38182884454727173f,0.1710560917854309f,-0.6304952502250671f,-0.24469460546970367f,0.07800555229187012f,-0.11156265437602997f,0.9230948686599731f,0.01127579715102911f}, {-0.23303905129432678f,-0.24711905419826508f,0.4181930422782898f,-0.2855757474899292f,-0.4139590263366699f,0.6357643604278564f,-0.33242931962013245f,0.33744025230407715f,0.019223570823669434f,0.025203019380569458f,0.0015196951571851969f,-0.32244545221328735f,0.07627367973327637f,0.36681148409843445f,0.2662626802921295f,-0.055823683738708496f}, {0.054309576749801636f,-0.49540218710899353f,0.3860630691051483f,-0.3997206389904022f,0.37840962409973145f,-0.14458975195884705f,-0.3337523639202118f,-0.21087387204170227f,0.18194907903671265f,-0.15486115217208862f,-0.48218241333961487f,0.30044838786125183f,-0.10916683077812195f,0.13324618339538574f,-0.018999867141246796f,0.2987367808818817f}, {-0.28941866755485535f,0.2667725384235382f,-0.4305540919303894f,-0.3544938564300537f,-0.3382750153541565f,0.1611849069595337f,-0.4222949147224426f,0.2507844567298889f,0.405910849571228f,0.15534931421279907f,0.0912986472249031f,-0.21454837918281555f,-0.35986700654029846f,-0.4057389199733734f,-0.28181108832359314f,-0.042290735989809036f}, {0.260015070438385f,0.32970598340034485f,-0.8912553787231445f,-0.3760731518268585f,0.08130717277526855f,-0.6682697534561157f,0.35346728563308716f,0.05169829726219177f,0.39578813314437866f,0.3265618085861206f,0.1725350022315979f,-0.23878204822540283f,0.3847886323928833f,0.3495698571205139f,-0.6733472347259521f,0.2500562071800232f}, {0.07367211580276489f,0.7450180053710938f,-0.6315812468528748f,0.21967214345932007f,0.4170142412185669f,-0.770605206489563f,0.16131609678268433f,-0.05181002616882324f,0.03649970889091492f,0.3132137656211853f,0.716629147529602f,0.09533099830150604f,-0.004373282194137573f,0.35536396503448486f,-0.6000161170959473f,0.3825781047344208f}, {-0.1849803626537323f,-0.40095481276512146f,-0.2245466113090515f,0.10853719711303711f,-0.34670042991638184f,-0.6805928349494934f,-0.07871395349502563f,-0.3424152731895447f,-0.0723131000995636f,-0.09276700019836426f,-0.2896198034286499f,0.384247362613678f,0.1583765149116516f,0.25456663966178894f,-0.6039044260978699f,0.12134073674678802f}, {0.3363311290740967f,-0.12490702420473099f,-0.04714484512805939f,0.2931549549102783f,-0.2531799077987671f,-0.3935620188713074f,-0.15988385677337646f,-0.16074800491333008f,-0.3888390362262726f,-0.03829273581504822f,-0.06867220997810364f,0.09743418544530869f,-0.03030523657798767f,0.038140591233968735f,0.038169119507074356f,-0.34604939818382263f}, {-0.008942186832427979f,0.6577344536781311f,-0.4952816069126129f,-0.26002514362335205f,0.369967520236969f,0.021473055705428123f,0.06158176064491272f,0.3959408402442932f,-0.011539667844772339f,-0.3851383328437805f,0.126651793718338f,-0.17609961330890656f,-0.3491899371147156f,-0.46013858914375305f,0.06334633380174637f,-0.24532243609428406f}, {-0.23328730463981628f,0.4614630937576294f,-0.2081146091222763f,-0.14789578318595886f,-0.1547950804233551f,-0.39302149415016174f,-0.09938845038414001f,0.10942506790161133f,-0.3328583538532257f,0.32593780755996704f,-0.3129696547985077f,0.019227905198931694f,0.025072604417800903f,-0.15357577800750732f,-0.2597353756427765f,-0.10979597270488739f}, {-0.2889084219932556f,0.35974031686782837f,-0.487824410200119f,0.358765184879303f,-0.4070855379104614f,-0.48963862657546997f,-0.14795801043510437f,0.12666010856628418f,0.2193526029586792f,0.2858560085296631f,-0.6543271541595459f,0.16494837403297424f,-0.35532402992248535f,-0.06058239936828613f,0.07391873747110367f,0.29227620363235474f}, {-0.349159836769104f,0.23408935964107513f,-0.28113874793052673f,-0.09636816382408142f,-0.3470844030380249f,0.09159677475690842f,-0.24872183799743652f,-0.3441091775894165f,-0.20228171348571777f,-0.3132234513759613f,-0.38526651263237f,-0.07960613816976547f,0.11759966611862183f,0.10377488285303116f,0.2513485848903656f,-0.263491153717041f}, {0.38546842336654663f,0.1190636157989502f,-0.05863933265209198f,-0.41764265298843384f,-0.4134422838687897f,-0.09244964271783829f,0.298126757144928f,-0.39963799715042114f,-0.06526103615760803f,0.03604122996330261f,-0.409576952457428f,0.09560509771108627f,-0.30289945006370544f,0.14713193476200104f,-0.0909358337521553f,0.1905267983675003f}, {-0.42283523082733154f,0.17752918601036072f,0.05169850215315819f,-0.14728012681007385f,-0.37331435084342957f,0.32072553038597107f,-0.09241300821304321f,-0.04799109697341919f,-0.17356249690055847f,-0.053030580282211304f,0.2975623309612274f,-0.12490103393793106f,-0.3399311900138855f,0.17119969427585602f,0.3467433452606201f,-0.32378605008125305f}, {0.2842629551887512f,0.14254522323608398f,-0.07260823994874954f,-0.1726883053779602f,-0.16769343614578247f,0.362951397895813f,-0.18842191994190216f,0.35883063077926636f,-0.32441917061805725f,0.3678022027015686f,0.19621485471725464f,0.4039776921272278f,-0.006959974765777588f,-0.07163886725902557f,0.17139792442321777f,-0.4028019607067108f}, {0.30670469999313354f,-0.07149137556552887f,-0.06005222350358963f,-0.24774791300296783f,0.2930166721343994f,0.0734730213880539f,-0.2875429093837738f,0.34532618522644043f,-0.07908278703689575f,0.264565646648407f,-0.24093548953533173f,-0.3791404664516449f,0.24430310726165771f,0.11721959710121155f,-0.20590196549892426f,-0.20737025141716003f}, {0.06869709491729736f,-0.28333309292793274f,-0.42365720868110657f,-0.3430131673812866f,-0.4249112606048584f,-0.367571085691452f,-0.2120281457901001f,-0.19189448654651642f,0.18253427743911743f,-0.026109665632247925f,0.29364481568336487f,-0.049624159932136536f,0.24209386110305786f,-0.28560784459114075f,0.2603754699230194f,-0.24946027994155884f}, }; const float h2[16][16] = { {-0.055980950593948364f,0.23325034976005554f,0.1310378611087799f,0.3538874685764313f,-0.3786364793777466f,0.3037426769733429f,-0.17743819952011108f,0.03198641538619995f,-0.25820767879486084f,-0.025972992181777954f,-0.1812897026538849f,-0.19700877368450165f,-0.23905162513256073f,0.3336930572986603f,-0.2611466646194458f,-0.14968061447143555f}, {0.6830940842628479f,0.3085605204105377f,-1.0774949789047241f,-0.63385409116745f,-0.9465451836585999f,-0.005713187158107758f,-1.1153970956802368f,-0.6576376557350159f,-0.18814027309417725f,0.2273702323436737f,-0.2186730057001114f,-0.09930881857872009f,0.3377574682235718f,-0.9058500528335571f,-0.21292872726917267f,0.6135957837104797f}, {-0.8244589567184448f,0.3188628852367401f,0.4108174741268158f,-0.4539192020893097f,-0.16654692590236664f,0.10132119059562683f,0.5420822501182556f,0.13426877558231354f,-0.1720905601978302f,0.229490727186203f,-0.29371505975723267f,-0.13699811697006226f,-0.28904634714126587f,0.337862104177475f,0.056768983602523804f,-0.5893235802650452f}, {-0.28563398122787476f,0.07789990305900574f,0.40358296036720276f,0.3720850646495819f,-0.03832319378852844f,-0.1494518518447876f,-0.11764177680015564f,0.34294649958610535f,0.054388612508773804f,0.3634087145328522f,0.1569826900959015f,0.28783395886421204f,-0.13846668601036072f,0.12138035893440247f,-0.3007376194000244f,0.12193700671195984f}, {0.1812863051891327f,0.25741907954216003f,-0.005224883556365967f,0.3340524137020111f,0.024127095937728882f,0.11559751629829407f,0.13140985369682312f,-0.02607312798500061f,0.060811251401901245f,0.1730591356754303f,0.4128219783306122f,0.03628826141357422f,-0.040624260902404785f,0.2442089021205902f,-0.39249828457832336f,-0.21546570956707f}, {0.30592480301856995f,-0.3289546072483063f,0.2873966097831726f,0.3854629099369049f,0.35946568846702576f,-0.36090072989463806f,0.3797028660774231f,-0.31257379055023193f,0.018147015944123268f,0.17989537119865417f,-0.191977858543396f,0.26149240136146545f,-0.5889873504638672f,0.4767233431339264f,-0.4196912348270416f,-0.6381170749664307f}, {0.03675055503845215f,-0.05131736397743225f,-0.2540779709815979f,-0.4151476323604584f,-0.3318796753883362f,0.2645241320133209f,0.06107431650161743f,-0.3474422097206116f,0.4012340009212494f,0.12852928042411804f,0.2119675576686859f,0.39421865344047546f,-0.14612942934036255f,0.4053405821323395f,-0.15860587358474731f,-0.00642770528793335f}, {-0.011466562747955322f,-0.293976753950119f,-0.2703247666358948f,0.13940533995628357f,-0.3086448609828949f,-0.10881850123405457f,-0.18203827738761902f,-0.3606947958469391f,0.05907437205314636f,0.17521318793296814f,0.16556969285011292f,-0.017545759677886963f,0.4063515365123749f,0.1637323796749115f,0.0436977744102478f,0.21962454915046692f}, {0.1453019678592682f,0.31070712208747864f,0.10406997799873352f,-0.34301185607910156f,-0.14203324913978577f,0.1393299400806427f,-0.07359349727630615f,-0.4255761206150055f,-0.24196511507034302f,0.4100019037723541f,-0.2432931661605835f,0.4171271026134491f,0.26163145899772644f,0.24838712811470032f,-0.31029027700424194f,0.24932292103767395f}, {-0.09909564256668091f,-0.22814129292964935f,0.18748918175697327f,-0.08129695057868958f,0.17022588849067688f,0.2918822467327118f,-0.3036908507347107f,-0.09228748083114624f,0.024910658597946167f,-0.4239048957824707f,0.050207048654556274f,-0.4021540582180023f,0.4068380892276764f,-0.20195016264915466f,0.35390153527259827f,0.03321918845176697f}, {0.27012309432029724f,0.11061021685600281f,-0.11031246930360794f,-0.2462926208972931f,-0.47244739532470703f,-0.11755365878343582f,-0.8120853900909424f,-0.5518144965171814f,-0.44141459465026855f,0.08167347311973572f,0.41236647963523865f,-0.19175507128238678f,0.17540761828422546f,-0.7689425349235535f,0.2710213363170624f,0.032591644674539566f}, {-0.34531110525131226f,-0.39544427394866943f,-0.40925148129463196f,0.07428228110074997f,0.16746854782104492f,-0.011973470449447632f,0.15573780238628387f,0.4095241129398346f,-0.11885038018226624f,0.2575679123401642f,-0.36203885078430176f,0.2510797083377838f,0.17548120021820068f,-0.001581403543241322f,0.10656675696372986f,-0.06930389255285263f}, {-0.01594102382659912f,-0.19719429314136505f,0.2015570104122162f,0.23486098647117615f,0.36742570996284485f,0.19432035088539124f,-0.24415965378284454f,0.16870906949043274f,-0.1409781575202942f,-0.15576940774917603f,-0.05214834213256836f,-0.16751256585121155f,0.12201771140098572f,0.031148135662078857f,-0.22613362967967987f,-0.3668502867221832f}, {-0.05743904411792755f,-0.10105487704277039f,0.37456682324409485f,-0.04381980374455452f,-0.24536658823490143f,-0.25192296504974365f,-0.2841794490814209f,-0.34860795736312866f,-0.12634605169296265f,-0.19223688542842865f,-0.13938084244728088f,-0.1388394832611084f,-0.24564625322818756f,-0.08797869831323624f,0.04871204495429993f,0.18949538469314575f}, {0.29601532220840454f,-0.008572280406951904f,0.4535497725009918f,0.3231527507305145f,0.7357798218727112f,-0.31015023589134216f,0.43387073278427124f,0.3858222961425781f,0.3131316900253296f,0.11613044142723083f,-0.22509463131427765f,-0.3847343325614929f,-0.512644350528717f,0.13419762253761292f,0.06784489750862122f,-0.3282114565372467f}, {-0.009295972064137459f,-0.35415053367614746f,-0.3785935640335083f,0.04678218811750412f,-0.05916179344058037f,0.028057783842086792f,-0.19932891428470612f,-0.004681884776800871f,0.27984046936035156f,0.021969109773635864f,-0.42253369092941284f,-0.02782580256462097f,-0.2832367718219757f,0.035722918808460236f,-0.08373728394508362f,0.2868802547454834f}, }; const float h3[16][16] = { {-0.011498991400003433f,-0.14559394121170044f,-0.06966331601142883f,-0.5719305872917175f,-0.21907491981983185f,0.7517984509468079f,0.6887433528900146f,0.0904630720615387f,-1.0889477729797363f,-0.28902721405029297f,-2.3065438270568848f,-0.10159772634506226f,0.23481115698814392f,-0.032193321734666824f,-0.060674071311950684f,0.22100424766540527f}, {0.11036357283592224f,-0.3038245439529419f,0.057057321071624756f,0.08777192234992981f,-0.35503754019737244f,-0.29007279872894287f,-0.33918139338493347f,-0.2990124225616455f,-0.33757925033569336f,0.2895788848400116f,-0.3337714970111847f,-0.37158891558647156f,0.33698758482933044f,0.16647490859031677f,-0.3480874300003052f,-0.2740727365016937f}, {-0.2946450114250183f,0.003037691116333008f,-0.061119019985198975f,0.4629787802696228f,0.05568113923072815f,-0.3591650128364563f,-0.3925563097000122f,-0.08465918898582458f,0.46576768159866333f,0.1319389045238495f,0.4200381338596344f,0.3004753887653351f,0.29665684700012207f,-0.5471781492233276f,0.08652284741401672f,-0.1951722800731659f}, {0.014514091424643993f,-0.38710832595825195f,-0.2894435524940491f,0.40405750274658203f,0.08946844935417175f,0.17319494485855103f,-0.3548906445503235f,0.4122363030910492f,0.28641819953918457f,0.18554691970348358f,0.14541564881801605f,0.4110986292362213f,-0.45408642292022705f,-0.2165788859128952f,0.27305224537849426f,-0.047836560755968094f}, {-0.2806110680103302f,0.40231046080589294f,-0.25313520431518555f,0.5885722637176514f,0.036378175020217896f,-0.22483457624912262f,-0.6083595752716064f,-0.08570799231529236f,0.30782198905944824f,-0.6609525084495544f,-0.08430586755275726f,-0.4229513108730316f,-0.23955631256103516f,-0.19798928499221802f,-0.2544192671775818f,-0.6755768060684204f}, {0.5131750702857971f,0.294185608625412f,-0.3519742488861084f,0.19928856194019318f,-0.3015052080154419f,-0.024108221754431725f,-0.23793454468250275f,-0.019414573907852173f,-0.42064279317855835f,0.5497127175331116f,-0.10041175037622452f,0.001658409833908081f,-0.023390205577015877f,0.3993215262889862f,0.15392538905143738f,-0.18064595758914948f}, {-0.2636679708957672f,-0.02554568648338318f,-0.3260969817638397f,1.400650143623352f,-0.38453540205955505f,-3.0441176891326904f,-1.0309864282608032f,0.12387624382972717f,1.327842354774475f,0.8234207034111023f,1.1026571989059448f,-0.32796353101730347f,-1.0295908451080322f,0.049302369356155396f,-0.27088475227355957f,-1.773733377456665f}, {0.15550771355628967f,0.33974209427833557f,0.33083590865135193f,0.21785464882850647f,-0.14358049631118774f,-1.6028454303741455f,-0.49285537004470825f,-0.3003333508968353f,0.8130767941474915f,-0.45922738313674927f,0.9424108266830444f,-0.2890920341014862f,-0.968544602394104f,0.36012205481529236f,0.048003822565078735f,-0.24998000264167786f}, {-0.25820738077163696f,0.35453304648399353f,-0.11379697918891907f,0.07942168414592743f,0.041274964809417725f,-0.33757007122039795f,-0.06726410984992981f,0.0019084513187408447f,0.024072596803307533f,-0.35254228115081787f,0.03284132853150368f,-0.3197441101074219f,-0.3433385193347931f,-0.30194157361984253f,-0.4068881571292877f,-0.1724976897239685f}, {-0.14576366543769836f,0.22098979353904724f,-0.13502129912376404f,0.1006976068019867f,0.12987366318702698f,0.11301741003990173f,0.2711336314678192f,-0.3632148504257202f,-0.13619378209114075f,0.16938945651054382f,0.24499371647834778f,0.39862415194511414f,0.3811538517475128f,-0.23332324624061584f,0.011877655982971191f,-0.23860150575637817f}, {-0.2709399461746216f,-0.006022721529006958f,0.0457797646522522f,-0.38090792298316956f,-0.03321319818496704f,-0.4148826003074646f,0.17873415350914001f,-0.20421427488327026f,-0.050184011459350586f,0.12480869889259338f,-0.20706263184547424f,0.3545852601528168f,-0.3647043704986572f,0.42127421498298645f,-0.39804020524024963f,-0.2870290279388428f}, {0.33538809418678284f,0.3494977056980133f,0.3954955041408539f,0.3170476257801056f,0.0033026933670043945f,0.3035760819911957f,-0.18492193520069122f,-0.11795541644096375f,0.3487861454486847f,-0.32520344853401184f,0.3952759802341461f,-0.15237495303153992f,0.0820283591747284f,-0.3793424367904663f,0.2430708110332489f,0.24988999962806702f}, {-0.37207356095314026f,-0.180922269821167f,-0.15798500180244446f,0.36838704347610474f,-0.37393757700920105f,0.44713646173477173f,0.025694025680422783f,-0.2947862446308136f,-0.39739224314689636f,0.1606505811214447f,-0.09350364655256271f,-0.2837170362472534f,0.4245411455631256f,-0.19196075201034546f,-0.15901821851730347f,0.014467512257397175f}, {-0.28947749733924866f,0.26506301760673523f,-0.2018718123435974f,0.5882180333137512f,0.07545611262321472f,-1.3561453819274902f,-0.4799374043941498f,-0.21416273713111877f,0.24524515867233276f,0.2077748328447342f,0.7775342464447021f,-0.25593626499176025f,-0.112045519053936f,0.27643296122550964f,-0.23556609451770782f,-0.41434746980667114f}, {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.46387147903442383f,0.3827712833881378f,0.12081471085548401f,-0.26810991764068604f,0.29976895451545715f,0.5951269268989563f,-0.09479555487632751f,0.31089308857917786f,-0.5688030123710632f,-0.46812617778778076f,0.21434427797794342f,-0.11613789200782776f,-0.19970247149467468f,-0.02543884515762329f,0.22754064202308655f,0.0740114152431488f}, }; const float hout[16] = { -0.158200204372406f,-0.17660260200500488f,-0.05137401819229126f,-0.5410199761390686f,-0.20271384716033936f,0.35903048515319824f,0.3810136020183563f,0.4165375232696533f,-0.4397028386592865f,0.12780319154262543f,-0.3604712188243866f,0.5489715337753296f,0.19251443445682526f,0.3525826036930084f,-0.480579137802124f,0.23442186415195465f }; const float b1[16] = { -0.31192219257354736f,0.268393874168396f,1.7755248546600342f,-0.407010555267334f,-0.8632325530052185f,1.3653104305267334f,-0.8388656973838806f,-0.8200502991676331f,-0.2854437828063965f,-1.6282782554626465f,0.8953557014465332f,-0.12085551768541336f,-1.5856122970581055f,-0.6190592050552368f,0.3934020400047302f,-0.36230528354644775f }; const float b2[16] = { -0.40527141094207764f,-1.3118138313293457f,0.9577730298042297f,1.5444650650024414f,0.5990768074989319f,-0.10386185348033905f,0.4417823553085327f,0.181562602519989f,-0.16907061636447906f,-1.6486880779266357f,-0.22539173066616058f,-2.15936541557312f,1.5229467153549194f,0.11918190121650696f,-0.6625781655311584f,0.4921003580093384f }; const float b3[16] = { 0.6422635316848755f,-0.1894310712814331f,0.21861673891544342f,0.1256403774023056f,-0.4563063681125641f,-0.5133413076400757f,1.4254883527755737f,-0.7025120258331299f,0.6852500438690186f,-0.6245395541191101f,-0.17192035913467407f,-0.7519525289535522f,-0.22238163650035858f,0.17018213868141174f,-0.45795938372612f,1.070515513420105f }; const float bout[1] = { 0.5118825435638428f }; /////////////////////////////////////////////////////////////////////////////////////////////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; input_NN[ind] = f_past[time_interval*i] / 10000.0f + 0.5f; ind = ind + 1; } // input_NN[ind] = torq.sen / 10000.0f * 8.0f + 0.5f; input_NN[ind] = torq.sen / 10000.0f + 0.5f; ind = ind + 1; for(int i=0; i<numfuture_f; i++) { // input_NN[ind] = (f_future[time_interval*i+time_interval] - torq.sen)/10000.0f * 8.0f + 0.5f; // input_NN[ind] = (f_future[time_interval*i+time_interval] - torq.sen)/10000.0f + 0.5f; // input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f*8.0f+0.5f; input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f + 0.5f; ind = ind + 1; } float output1[16] = { 0.0f }; float output2[16] = { 0.0f }; float output3[16] = { 0.0f }; float output = 0.0f; for (int index2 = 0; index2 < 16; index2++) { for (int index1 = 0; index1 < num_input; index1++) { output1[index2] = output1[index2] + h1[index1][index2] * input_NN[index1]; } output1[index2] = output1[index2] + b1[index2]; if (output1[index2] < 0) { output1[index2] = 0; } } for (int index2 = 0; index2 < 16; index2++) { for (int index1 = 0; index1 < 16; index1++) { output2[index2] = output2[index2] + h2[index1][index2] * output1[index1]; } output2[index2] = output2[index2] + b2[index2]; if (output2[index2] < 0) { output2[index2] = 0; } } for (int index2 = 0; index2 < 16; index2++) { for (int index1 = 0; index1 < 16; index1++) { output3[index2] = output3[index2] + h3[index1][index2] * output2[index1]; } output3[index2] = output3[index2] + b3[index2]; if (output3[index2] < 0) { output3[index2] = 0; } } for (int index2 = 0; index2 < 1; index2++) { for (int index1 = 0; index1 < 16; index1++) { output = output + hout[index1] * output3[index1]; } output = output + bout[index2]; } 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 + (float) D_GAIN_JOINT_TORQUE * (torq.ref_diff - torq_dot.sen)) * 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 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 = 2000.0f; //2000 //20000 float k4 = 10.0f; float rho3 = 3.2f; float rho4 = 10000000.0f; //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; float V_input = 0.0f; V_out = (-f4 + x_4_des_dot - k4*(x_v-x_4_des)- rho3/rho4*gamma_hat*g3_prime*(-torq.err))/g4; // //V_out LPF // float alpha_V_out = 1.0f/(1.0f + 5000.0f/(2.0f*3.14f*50.0f)); // f_cutoff : 50Hz // V_out = V_out*(1.0f-alpha_V_out)+V_input*(alpha_V_out); float rho_gamma = 5000.0f;//5000 for change //50000 for not change float gamma_hat_dot = rho3*(-torq.err)/rho_gamma*((-f3+torq_ref_dot-k3*(-torq.err))/gamma_hat + g3_prime*(x_v-x_4_des)); gamma_hat = gamma_hat + gamma_hat_dot / (float) TMR_FREQ_5k; if(gamma_hat > 10000.0f) gamma_hat = 10000.0f; else if(gamma_hat < 100.0f) gamma_hat = 100.0f; 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) (torq.ref)); //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) gamma_hat, (int16_t) 0, (int16_t) 0, (int16_t) 0); //1600 } // Others : Reference position, Reference FT, PWM, Current (ID:1300) // if (flag_data_request[1] == HIGH) { // CAN_TX_SOMETHING((int) (FORCE_VREF), (int16_t) (1), (int16_t) (2), (int16_t) (3)); // } //if (flag_delay_test == 1){ //CAN_TX_PRES((int16_t) (0),(int16_t) torq_ref); //} TMR2_COUNT_CAN_TX = 0; } TMR2_COUNT_CAN_TX++; } TIM3->SR = 0x0; // reset the status register }