Sungwoo Kim
/
HydraulicControlBoard_Learning
for learning
main.cpp
- Committer:
- Lightvalve
- Date:
- 2021-01-08
- Revision:
- 249:21430e06f706
- Parent:
- 248:c925c863ea87
- Child:
- 250:ae6e0c80029d
File content as of revision 249:21430e06f706:
//210108_3 500Hz num_input 9 210105 data #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.29663917422294617f,0.41587597131729126f,-0.40238484740257263f,-0.31135293841362f,0.09028628468513489f,-0.15008357167243958f,0.0060180313885211945f,-0.25428661704063416f,-0.38775452971458435f,-0.08711326122283936f,0.029678843915462494f,-0.5523331761360168f,0.17435714602470398f,0.049568623304367065f,-0.11123791337013245f,0.11293289065361023f}, {-0.13885954022407532f,0.008150720968842506f,0.47685256600379944f,0.2796906530857086f,0.32721421122550964f,-0.15552201867103577f,0.13772499561309814f,-0.03211083635687828f,-0.33916792273521423f,0.5187415480613708f,-0.2988690733909607f,-0.5000523328781128f,-0.3222626745700836f,-0.22863739728927612f,-0.3115236759185791f,0.08912834525108337f}, {-0.36185380816459656f,-0.01113466639071703f,-0.17586973309516907f,-0.40819093585014343f,-0.25984901189804077f,0.016262324526906013f,-0.5287548899650574f,-0.0727643221616745f,0.21207480132579803f,-0.2510138154029846f,-0.3024713099002838f,-0.2796802222728729f,-0.0891394317150116f,0.3824678361415863f,-0.12040254473686218f,0.056863874197006226f}, {0.15546533465385437f,0.4914516508579254f,-0.2568590044975281f,-0.43472781777381897f,0.2994142472743988f,0.15819527208805084f,0.14573554694652557f,-0.2842216193675995f,-0.3083231747150421f,-0.3176731467247009f,-0.17488853633403778f,0.20977792143821716f,-0.2630729377269745f,-0.27504676580429077f,-0.4301341474056244f,-0.08075663447380066f}, {0.48212262988090515f,0.40492209792137146f,-0.06806144118309021f,-0.3792468011379242f,-0.11923012137413025f,-0.23530688881874084f,-0.21158641576766968f,-0.42907828092575073f,-0.14715367555618286f,0.4203021228313446f,0.006408415734767914f,0.3745218813419342f,-0.419051855802536f,-0.40804523229599f,0.24169525504112244f,0.03659626841545105f}, {-0.12619352340698242f,0.19174300134181976f,-0.31877976655960083f,-0.04390779882669449f,-0.14006736874580383f,-0.21398991346359253f,-0.7291432619094849f,-0.2562205493450165f,0.44291412830352783f,0.6389468312263489f,-0.16900624334812164f,0.3231842815876007f,-0.35098129510879517f,-0.15950220823287964f,-0.2785465717315674f,-0.2435975819826126f}, {0.04468771815299988f,0.2694479525089264f,0.3779745399951935f,0.10625391453504562f,-0.286765992641449f,-0.6106315851211548f,0.06032551825046539f,0.1240493655204773f,0.04552985727787018f,0.20586301386356354f,0.5519559979438782f,-1.0102519989013672f,0.4520128071308136f,0.11482951045036316f,-0.1275120973587036f,-0.1722896695137024f}, {-0.4707544147968292f,-0.39714711904525757f,-0.1917957365512848f,-0.021674744784832f,-0.18413209915161133f,-0.8700361847877502f,0.5609602928161621f,0.2770845890045166f,0.09915876388549805f,-0.2328445464372635f,0.6780804991722107f,0.27046671509742737f,-0.347939670085907f,-0.42903608083724976f,0.1774953305721283f,0.2401047646999359f}, {-0.15439578890800476f,-0.5200294256210327f,-0.2624427080154419f,0.3273162245750427f,-0.2676073908805847f,0.20046526193618774f,0.03604237735271454f,-0.1507950872182846f,0.8252518177032471f,0.06839548051357269f,-0.2259593904018402f,1.0545680522918701f,0.23076865077018738f,-0.04404708743095398f,-0.44072574377059937f,0.15690186619758606f}, }; const float h2[16][16] = { {-0.3888300061225891f,-0.33301249146461487f,-0.1355518400669098f,-0.37952423095703125f,0.21257463097572327f,-0.36136317253112793f,0.24208763241767883f,0.33804598450660706f,-0.2569337487220764f,-0.08110451698303223f,-0.27817511558532715f,0.35469159483909607f,-0.29972952604293823f,0.15880760550498962f,-0.35889360308647156f,-0.08369413018226624f}, {0.9094585180282593f,-0.20084045827388763f,-0.2232477068901062f,0.022348403930664062f,-0.31344151496887207f,0.9187012314796448f,0.08110490441322327f,-0.796314001083374f,-0.6019505262374878f,1.4344419240951538f,2.078198194503784f,0.12826785445213318f,0.08236726373434067f,0.513929009437561f,-0.7852200269699097f,0.7756533026695251f}, {-0.03531843423843384f,-0.4267989993095398f,-0.33276697993278503f,0.0032796859741210938f,-0.4177505671977997f,0.3844440281391144f,-0.3362900912761688f,0.37579968571662903f,0.3336181938648224f,0.019254565238952637f,-0.053793132305145264f,-0.04763022065162659f,0.2717372477054596f,0.3915339410305023f,-0.4008266031742096f,0.008691728115081787f}, {0.829369306564331f,-0.037088543176651f,0.3303629159927368f,-0.10298678278923035f,0.03958216309547424f,1.1753311157226562f,-0.39364370703697205f,-1.0809330940246582f,-1.399806022644043f,0.812737226486206f,-2.776177406311035f,-0.06223180890083313f,-1.3906004428863525f,0.9751940965652466f,-0.8362966179847717f,0.7644394040107727f}, {0.0065080225467681885f,0.4084913432598114f,0.34083792567253113f,0.08630749583244324f,-0.18584498763084412f,-0.10108181834220886f,0.1392066776752472f,0.14020100235939026f,0.12382212281227112f,0.31817105412483215f,-0.24523776769638062f,-0.4109385013580322f,-0.041146427392959595f,-0.1336672306060791f,0.19239845871925354f,-0.1465291678905487f}, {0.19369199872016907f,0.10641822218894958f,-0.21756651997566223f,-0.16729947924613953f,0.3574720323085785f,0.22665399312973022f,0.10581281781196594f,0.268216073513031f,0.06638725847005844f,-0.05752768740057945f,-0.3020212650299072f,0.37810656428337097f,0.036901701241731644f,0.1635662168264389f,0.05745241418480873f,0.0073737651109695435f}, {-0.4029591679573059f,-0.26807457208633423f,-0.1728709638118744f,-0.22050951421260834f,-0.299405962228775f,0.017986953258514404f,0.3826618492603302f,0.5415890216827393f,0.20813074707984924f,-0.21721883118152618f,-0.3750367760658264f,0.3528025448322296f,-0.015163726173341274f,0.01980692148208618f,0.4643106758594513f,-0.44261613488197327f}, {-0.1553884893655777f,0.0929887592792511f,0.07923837006092072f,0.1415313184261322f,-0.24100345373153687f,0.035420484840869904f,-0.23515468835830688f,0.48955461382865906f,-0.22871027886867523f,-0.6616853475570679f,-0.35328409075737f,-0.0841493010520935f,-0.6434178352355957f,-0.2802467942237854f,0.02801680937409401f,-0.43440064787864685f}, {-0.07246144115924835f,-0.18326310813426971f,0.16720524430274963f,0.011525928974151611f,-0.12579655647277832f,0.5384641289710999f,0.26028844714164734f,0.030630944296717644f,0.1539444476366043f,0.4313714802265167f,-1.2241016626358032f,-0.08900067210197449f,-0.5645046234130859f,-0.23248566687107086f,0.24500861763954163f,0.4273317754268646f}, {0.10190009325742722f,-0.21384187042713165f,0.07577396184206009f,-0.05684670805931091f,0.34398868680000305f,0.054179057478904724f,0.10196617245674133f,0.15645906329154968f,-0.22546876966953278f,0.0037930342368781567f,0.4444926083087921f,-0.4265243709087372f,0.39087945222854614f,0.3117143511772156f,-0.46703991293907166f,0.2941291034221649f}, {-0.37670740485191345f,-0.3690805435180664f,0.3855787217617035f,0.21942487359046936f,-0.0013443827629089355f,-0.08459454774856567f,0.37341418862342834f,0.25538870692253113f,0.45563217997550964f,-0.36620602011680603f,-0.10484421253204346f,-0.15164825320243835f,-0.13352882862091064f,-0.8643376231193542f,0.13016673922538757f,-0.2567961513996124f}, {0.008839505724608898f,-0.0046111345291137695f,-0.16272638738155365f,-0.18568435311317444f,-0.2280530333518982f,0.138400599360466f,0.07191351056098938f,0.4081989824771881f,0.08220343291759491f,0.27161240577697754f,-0.28040406107902527f,0.0015468299388885498f,-0.008710266090929508f,0.11106086522340775f,0.31602251529693604f,0.270530641078949f}, {0.20316341519355774f,-0.01405063271522522f,0.09861764311790466f,-0.16879788041114807f,-0.404694527387619f,0.13892611861228943f,-0.17759200930595398f,0.3851688802242279f,0.24458882212638855f,-0.2915504574775696f,0.22550490498542786f,-0.24272814393043518f,0.14730152487754822f,-0.4137716591358185f,0.17881467938423157f,-0.2877027690410614f}, {-0.2195536345243454f,0.02955836057662964f,0.40262481570243835f,-0.40885308384895325f,-0.12887510657310486f,-0.4060956835746765f,0.17089977860450745f,-0.3749438524246216f,0.028164535760879517f,0.030858129262924194f,0.07867559790611267f,-0.39648905396461487f,-0.040825873613357544f,-0.08236381411552429f,-0.013542592525482178f,-0.10870978236198425f}, {-0.12072217464447021f,-0.375680148601532f,-0.2350127398967743f,0.20186755061149597f,-0.36594828963279724f,0.13954707980155945f,0.3276398479938507f,0.22214189171791077f,0.22335270047187805f,-0.051959723234176636f,-0.27821671962738037f,-0.41584086418151855f,0.3025414049625397f,-0.21118895709514618f,-0.36947399377822876f,0.1889876425266266f}, {0.12349763512611389f,0.10101905465126038f,-0.3979831337928772f,-0.23517636954784393f,0.4234168231487274f,-0.21465477347373962f,0.2610546052455902f,0.05005693435668945f,-0.016834020614624023f,-0.349880188703537f,0.2895679771900177f,0.38406917452812195f,0.1496359407901764f,0.029400497674942017f,0.21077695488929749f,-0.10674196481704712f}, }; const float h3[16][16] = { {0.20138880610466003f,0.31971320509910583f,-0.573394775390625f,-0.31132131814956665f,-0.3762798309326172f,-0.4261515736579895f,-0.2775144875049591f,-0.10658112168312073f,0.5168919563293457f,0.07961633056402206f,0.40829774737358093f,0.06363576650619507f,-0.20960833132266998f,0.3711947202682495f,0.13634565472602844f,-0.38112565875053406f}, {0.19051507115364075f,0.16294768452644348f,0.4160015881061554f,0.05116799473762512f,-0.2918829917907715f,-0.14418381452560425f,-0.35893499851226807f,0.09588906168937683f,-0.2242071032524109f,0.1678912341594696f,0.05509382486343384f,-0.02252596616744995f,-0.40007027983665466f,0.4086398780345917f,-0.3398894965648651f,0.3448427617549896f}, {0.004781484603881836f,0.057733599096536636f,-0.40068915486335754f,-0.12630119919776917f,0.2725552022457123f,0.029532641172409058f,0.24218353629112244f,0.059943556785583496f,-0.4218027591705322f,0.1711505651473999f,0.232928067445755f,0.2649426758289337f,-0.1096067950129509f,-0.25758618116378784f,0.1579485833644867f,0.34988483786582947f}, {0.14744046330451965f,-0.14954188466072083f,-0.2823004126548767f,-0.20482586324214935f,-0.3508032262325287f,-0.3688071668148041f,0.01029101014137268f,0.03582140803337097f,0.1944337785243988f,0.39723339676856995f,0.0812627375125885f,-0.07741960883140564f,-0.25062668323516846f,-0.17132753133773804f,-0.32584911584854126f,-0.10801076889038086f}, {-0.23801851272583008f,-0.32108113169670105f,-0.347549170255661f,-0.16850975155830383f,0.4027153551578522f,-0.381073534488678f,-0.2942546606063843f,0.12287876009941101f,-0.20644505321979523f,0.1990034282207489f,-0.2864486277103424f,-0.25635671615600586f,0.38671061396598816f,-0.33340561389923096f,-0.14622977375984192f,0.11676457524299622f}, {-0.28616175055503845f,-0.12695540487766266f,-0.30583456158638f,-0.03626849874854088f,0.24763250350952148f,-0.03751462697982788f,-0.3386254608631134f,0.169498473405838f,0.47662490606307983f,0.3614100217819214f,0.06764152646064758f,-0.015877217054367065f,0.2642289698123932f,-0.35798028111457825f,0.20222005248069763f,0.30211254954338074f}, {0.2333069145679474f,0.0017639398574829102f,-0.30106985569000244f,-0.027164578437805176f,-0.24558454751968384f,0.3476872742176056f,-0.12298372387886047f,0.12251326441764832f,-0.4255034625530243f,-0.3266092538833618f,-0.3107597827911377f,0.28408458828926086f,0.06578537821769714f,-0.09853100776672363f,-0.25814658403396606f,-0.013455241918563843f}, {0.6252551674842834f,-1.7136082649230957f,1.6249260902404785f,1.672523856163025f,-0.28755253553390503f,0.13177838921546936f,0.13568851351737976f,-0.11005973815917969f,-1.5778653621673584f,-1.6947146654129028f,0.264227956533432f,-0.36500003933906555f,-1.7246160507202148f,0.5941118001937866f,0.2957947552204132f,0.07755979895591736f}, {0.18169909715652466f,-0.19895386695861816f,-0.05671519413590431f,0.36275410652160645f,0.06176760792732239f,0.07695844769477844f,0.12766453623771667f,0.0817842185497284f,-0.7237305045127869f,-0.6087480187416077f,-0.12001633644104004f,-0.08554613590240479f,-0.0011166516924276948f,0.027426540851593018f,-0.387156218290329f,-0.2686024308204651f}, {-1.7639572620391846f,0.9937340021133423f,-0.762538492679596f,-1.1919790506362915f,0.22843122482299805f,0.14367392659187317f,0.43251314759254456f,-0.11276862025260925f,0.9715967774391174f,0.7894815802574158f,-0.17702773213386536f,-0.42824557423591614f,1.2783340215682983f,0.0824713259935379f,0.10247305035591125f,0.11768892407417297f}, {-4.242254257202148f,3.9532933235168457f,-4.220984935760498f,-3.2578203678131104f,-0.28594839572906494f,-0.2543869614601135f,0.3854757249355316f,-0.35510146617889404f,3.874885082244873f,3.38134503364563f,0.025140076875686646f,-0.09252285957336426f,3.5076000690460205f,0.020325958728790283f,-0.2821711599826813f,-0.31494733691215515f}, {-0.19829243421554565f,-0.036789268255233765f,0.40402278304100037f,0.08938947319984436f,-0.3003213703632355f,-0.13985875248908997f,-0.05300605297088623f,0.2158009111881256f,-0.045280009508132935f,0.3853699862957001f,-0.28284311294555664f,-0.38101786375045776f,0.20273366570472717f,-0.2851206660270691f,-0.23302911221981049f,-0.04975670576095581f}, {-2.3402528762817383f,2.251093626022339f,-1.8143333196640015f,-1.686104416847229f,0.28627198934555054f,-0.05089947581291199f,-0.21972325444221497f,-0.12107464671134949f,1.4696484804153442f,1.7204586267471313f,0.42002591490745544f,0.2625511586666107f,2.0771658420562744f,0.20424117147922516f,-0.14932382106781006f,0.05037429928779602f}, {0.01017003320157528f,0.5383520722389221f,0.09068045765161514f,-0.3059485852718353f,-0.1828690618276596f,0.12154242396354675f,-0.3135022222995758f,-0.05303463339805603f,0.2918146252632141f,0.4535827040672302f,0.19363173842430115f,0.17974761128425598f,0.21057143807411194f,0.3842782974243164f,0.1783216893672943f,0.15743878483772278f}, {0.2572315037250519f,-0.7767909169197083f,0.5495519042015076f,0.8770574331283569f,0.29163259267807007f,0.3491267263889313f,0.2651456296443939f,0.27459242939949036f,-0.37017369270324707f,-0.9690517783164978f,0.0338018536567688f,-0.015062451362609863f,-0.9156760573387146f,-0.31157001852989197f,-0.1419163942337036f,-0.4173831343650818f}, {-0.7403416633605957f,0.7024995684623718f,-0.38165247440338135f,-0.6589585542678833f,0.18063348531723022f,0.4021502435207367f,-0.18067532777786255f,0.0808744728565216f,0.13344483077526093f,0.5048403143882751f,0.1375615894794464f,-0.3139927089214325f,0.32810354232788086f,-0.28314903378486633f,0.295305460691452f,0.26069560647010803f}, }; const float hout[16] = { -4.399260997772217f,0.904973030090332f,-1.0306147336959839f,-1.186169147491455f,-0.24832315742969513f,-0.1935586929321289f,-0.5914010405540466f,0.5897116661071777f,2.2783241271972656f,0.4730304181575775f,-0.31953302025794983f,-0.20998573303222656f,0.40309593081474304f,-0.33466991782188416f,0.07082188129425049f,0.5935964584350586f }; const float b1[16] = { -0.5132032632827759f,-1.1938527822494507f,-0.7500218152999878f,1.0411573648452759f,-1.3620671033859253f,1.3940210342407227f,0.8505174517631531f,1.1860228776931763f,0.3311760723590851f,-0.16578342020511627f,0.41973596811294556f,1.2696189880371094f,-0.40242457389831543f,-0.13635645806789398f,-0.85361248254776f,-0.41521793603897095f }; const float b2[16] = { 0.5477832555770874f,-0.05469924956560135f,-0.36899566650390625f,-0.7305267453193665f,-0.6980655789375305f,0.3870934545993805f,-1.2705386877059937f,-0.5881870985031128f,1.4541643857955933f,0.053963299840688705f,0.042596764862537384f,-0.9409856796264648f,-0.49485892057418823f,0.5978859066963196f,0.21442629396915436f,-0.16960793733596802f }; const float b3[16] = { 0.8192553520202637f,0.4740256071090698f,1.4711703062057495f,1.393757939338684f,-0.5335577726364136f,-0.5553005933761597f,-0.5806921124458313f,-1.019081473350525f,-0.13486835360527039f,1.6698031425476074f,-1.9048346281051636f,-2.072582483291626f,1.185135006904602f,-0.8330573439598083f,-0.9093554615974426f,-0.6499820947647095f }; const float bout[1] = { -0.06959325075149536f }; float valve_ref_pos_buffer[10] = {0.0f}; /////////////////////////////////////////////////////////////////////////////////////////////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; 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 ////For Test LIMC////////////////////////////////////////// VALVE_POS_CONTROL(valve_pos.ref); // for(int i=0; i<9; i++){ // valve_ref_pos_buffer[i] = valve_ref_pos_buffer[i+1]; // } // valve_ref_pos_buffer[9] = valve_pos.ref; // VALVE_POS_CONTROL(valve_ref_pos_buffer[0]); //////////////////////////////////////////////////////////// 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 f3_hat = -a_hat * 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 K_valve = 0.0002f; 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_hat + 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; float rho_a = 0.00001f; float a_hat_dot = -rho3/rho_a*vel.sen/(float)(ENC_PULSE_PER_POSITION)*0.001f*(-torq.err); a_hat = a_hat + a_hat_dot / (float) TMR_FREQ_5k; if(a_hat > -3000000.0f) a_hat = -3000000.0f; else if(a_hat < -30000000.0f) a_hat = -30000000.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 (int 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) (a_hat*0.0001f), (int16_t) 0, (int16_t) 0, (int16_t) 0); //1600 } // Others : Reference position, Reference FT, PWM, Current (ID:1300) if (flag_data_request[1] == HIGH) { CAN_TX_SOMETHING((int) (FORCE_VREF), (int16_t) (1), (int16_t) (2), (int16_t) (3)); } if (flag_delay_test == 1){ CAN_TX_PRES((int16_t) (0),(int16_t) torq_ref); } TMR2_COUNT_CAN_TX = 0; } TMR2_COUNT_CAN_TX++; */ } TIM3->SR = 0x0; // reset the status register }