Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
main.cpp
- Committer:
- Lightvalve
- Date:
- 2020-12-23
- Revision:
- 209:ebc69d6ee6f1
- Parent:
- 208:408f9f15c486
- Child:
- 210:efc3a92cc6be
File content as of revision 209:ebc69d6ee6f1:
//201223_1
#include "mbed.h"
#include "FastPWM.h"
#include "INIT_HW.h"
#include "function_CAN.h"
#include "SPI_EEP_ENC.h"
#include "I2C_AS5510.h"
#include "setting.h"
#include "function_utilities.h"
#include "stm32f4xx_flash.h"
#include "FlashWriter.h"
#include <string>
#include <iostream>
#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] = {
{-1.6000940799713135f,0.4413917660713196f,0.12903714179992676f,-0.07903441786766052f,-1.8977726697921753f,1.8713637590408325f,-0.17472904920578003f,0.4568611681461334f,-0.43561747670173645f,-0.04615814611315727f,-0.23684236407279968f,-1.5037455558776855f,-0.2676747143268585f,-0.6216555237770081f,-0.2571594715118408f,-0.4336307942867279f},
{-0.8367072343826294f,0.09323202818632126f,-0.3927857577800751f,-0.2727188766002655f,-1.0405902862548828f,0.8998438119888306f,-0.4054011106491089f,0.44874632358551025f,-0.29669591784477234f,0.21184058487415314f,-0.2736198306083679f,-0.8792054653167725f,0.23191256821155548f,-0.8017642498016357f,-0.20967772603034973f,-0.9694083333015442f},
{-0.8188105821609497f,0.49548420310020447f,0.36391180753707886f,-0.5226353406906128f,-0.6585426330566406f,0.8799821138381958f,0.2872133255004883f,0.012798400595784187f,-0.41921380162239075f,0.2234516143798828f,-0.3474748432636261f,-0.5087661147117615f,-0.00637056166306138f,-0.18617482483386993f,0.05590221285820007f,-0.8025757670402527f},
{-0.6304765939712524f,0.6922854781150818f,0.39742106199264526f,0.24299956858158112f,-0.42302995920181274f,0.14712309837341309f,-0.11584559082984924f,-0.5310759544372559f,-0.27385860681533813f,0.3663768470287323f,0.09638378769159317f,0.29256293177604675f,-0.16855108737945557f,-0.18148168921470642f,-0.2961459457874298f,0.8457931876182556f},
{0.7473434209823608f,0.48988762497901917f,-0.0051451027393341064f,0.3333152234554291f,0.5788547396659851f,-0.6460171937942505f,0.1294034719467163f,-0.9815593957901001f,-0.3184085786342621f,0.19254086911678314f,0.34836387634277344f,0.49276548624038696f,-0.07216952741146088f,0.27343443036079407f,-0.3865056037902832f,1.4092313051223755f},
{3.2342982292175293f,-2.2555158138275146f,0.21773302555084229f,0.5652960538864136f,3.146817207336426f,-3.1406891345977783f,0.16514194011688232f,0.6139293909072876f,-0.4235992729663849f,0.21656234562397003f,-0.24712057411670685f,1.274764895439148f,-0.2688344120979309f,1.1950470209121704f,-0.4132833778858185f,-0.059984441846609116f},
{-0.6526948809623718f,0.7561483383178711f,-0.2501986622810364f,-0.7059148550033569f,-0.7783506512641907f,0.33273711800575256f,0.06014183163642883f,-4.296197891235352f,0.15086668729782104f,-0.12566223740577698f,0.1482049971818924f,0.7200766205787659f,-0.17589396238327026f,-0.14634668827056885f,-0.15618428587913513f,4.646012783050537f},
{-0.7106614112854004f,-0.292780339717865f,-0.26619744300842285f,0.1277981847524643f,-0.9086422920227051f,0.2727634906768799f,-0.17925891280174255f,-2.5595145225524902f,-0.2821522653102875f,-0.020468801259994507f,0.1025993749499321f,0.01748223975300789f,0.36828503012657166f,0.025631556287407875f,0.04303058981895447f,1.733962059020996f},
{0.9920234084129333f,-1.627883791923523f,0.10248100757598877f,-0.08735460788011551f,0.6591731309890747f,-0.48275211453437805f,-0.07246989011764526f,0.49826139211654663f,-0.6757456660270691f,0.2720978260040283f,-0.29995009303092957f,0.6254252791404724f,0.22595258057117462f,1.0093032121658325f,-0.30555272102355957f,-3.7689568996429443f},
{0.14623138308525085f,-1.3082497119903564f,0.18462657928466797f,0.06593218445777893f,0.38641560077667236f,0.006398537661880255f,-0.2990540862083435f,0.5669264197349548f,-0.25464093685150146f,-0.5164272785186768f,-0.010852855630218983f,-0.6049553751945496f,0.36904722452163696f,0.27233806252479553f,0.3484981060028076f,-2.143152952194214f},
{0.26631736755371094f,-0.37726837396621704f,0.37182438373565674f,0.2574600577354431f,-0.09127864241600037f,-0.01836557500064373f,-0.20339298248291016f,0.23786002397537231f,-0.49957215785980225f,-0.008945263922214508f,0.3458111584186554f,-0.824551522731781f,-0.06989830732345581f,0.1074192151427269f,0.26688337326049805f,-0.8953605890274048f},
{-0.23877182602882385f,-0.7098087072372437f,-0.40320003032684326f,-0.1078604906797409f,0.28780120611190796f,-0.42413681745529175f,0.1533789038658142f,0.40164631605148315f,-0.1681622713804245f,0.16031795740127563f,-0.4167521595954895f,-0.43077829480171204f,0.1412402093410492f,0.07915178686380386f,0.10493969917297363f,-0.07492798566818237f},
{-0.03229803964495659f,-0.42042604088783264f,0.19847965240478516f,-0.0030563066247850657f,0.36559855937957764f,-0.1463041454553604f,-0.2404318004846573f,0.20067740976810455f,-0.1734953671693802f,-0.2558341920375824f,-0.1115814819931984f,-0.7943522334098816f,0.08852691203355789f,0.1106438934803009f,-0.22268100082874298f,-0.1786385029554367f},
{-0.11297377943992615f,-0.43093106150627136f,0.4127817749977112f,-0.24888765811920166f,-0.21446679532527924f,-0.5084688663482666f,-0.32001304626464844f,0.04496301710605621f,-0.12302793562412262f,-0.3023318648338318f,-0.19743306934833527f,-0.7400186061859131f,-0.3162824809551239f,0.03880959749221802f,0.0479682981967926f,-0.08672763407230377f},
{-0.02818325348198414f,-0.06082405894994736f,0.20282304286956787f,-0.12476225942373276f,0.10320129990577698f,-0.1304563730955124f,0.04202890396118164f,0.21194368600845337f,0.32223421335220337f,-0.0071917143650352955f,-0.28180214762687683f,-1.0684038400650024f,0.09998573362827301f,-0.12126590311527252f,0.0668090283870697f,-0.012993170879781246f},
{-0.005457713268697262f,-0.446575790643692f,-0.40439701080322266f,-0.2776923179626465f,-0.21002432703971863f,-0.2032385915517807f,-0.15568238496780396f,-0.06614420562982559f,0.19860975444316864f,-0.10510893166065216f,-0.4762294590473175f,-0.7791360020637512f,-0.27474963665008545f,-0.020535530522465706f,-0.08245879411697388f,0.022347593680024147f},
{-0.11706838756799698f,-0.6494715213775635f,0.16706281900405884f,-0.1073165163397789f,-0.16269126534461975f,-0.41736364364624023f,-0.041414469480514526f,0.182882621884346f,-0.049576375633478165f,-0.01950126886367798f,-0.355907678604126f,-0.59775710105896f,0.10836437344551086f,0.30783337354660034f,0.29427415132522583f,0.02123108133673668f},
};
const float h2[16][16] = {
{-3.323141574859619f,2.0404324531555176f,-0.06966331601142883f,1.7146148681640625f,-0.21907491981983185f,0.3013889193534851f,-0.20208165049552917f,0.0904630720615387f,-0.43008196353912354f,-0.1415480375289917f,1.703560709953308f,-1.0790513753890991f,0.12968102097511292f,-4.26299524307251f,-0.03616251423954964f,1.0661470890045166f},
{0.12045703083276749f,0.15307354927062988f,0.057057321071624756f,3.0073626041412354f,-0.35503754019737244f,-1.694530725479126f,-0.34237051010131836f,-0.2990124225616455f,-0.33757925033569336f,0.2895788848400116f,-1.596266746520996f,-0.9465551376342773f,0.33698758482933044f,1.5713340044021606f,0.2106013149023056f,0.14802111685276031f},
{-0.22745239734649658f,0.003037691116333008f,-0.061119019985198975f,0.35696902871131897f,0.05568113923072815f,0.011741191148757935f,-0.20225946605205536f,-0.08465918898582458f,0.3489862382411957f,0.0687277615070343f,0.31964078545570374f,0.3004753887653351f,0.36063823103904724f,-0.42892736196517944f,0.08652284741401672f,0.027493387460708618f},
{-0.0038494274485856295f,-0.27630358934402466f,-0.2894435524940491f,0.4252559542655945f,0.08946844935417175f,0.27233457565307617f,-0.3439287841320038f,0.4122363030910492f,0.26211628317832947f,0.2953031361103058f,0.2075938880443573f,0.2481931746006012f,-0.404754102230072f,-0.39094415307044983f,0.12583167850971222f,0.12181642651557922f},
{-0.8256309032440186f,1.8575127124786377f,-0.25313520431518555f,0.03169454261660576f,0.036378175020217896f,0.14327585697174072f,-0.7250795960426331f,-0.08570799231529236f,-0.024399548768997192f,-0.39465832710266113f,-0.36996984481811523f,-1.1260812282562256f,0.10077962279319763f,-1.170457363128662f,-0.640777051448822f,0.3631480038166046f},
{1.3197550773620605f,-1.6532154083251953f,-0.3519742488861084f,-0.4759509563446045f,-0.3015052080154419f,-0.37989047169685364f,-1.0408955812454224f,-0.019414573907852173f,-0.23047015070915222f,0.3579089343547821f,-0.4645023047924042f,-0.7267597317695618f,-0.20959392189979553f,-0.8655065298080444f,-0.023840362206101418f,-0.2557324171066284f},
{-0.1828227937221527f,-0.02554568648338318f,-0.3260969817638397f,0.08422836661338806f,-0.38453540205955505f,-0.25432005524635315f,0.285016268491745f,0.12387624382972717f,-0.0982072651386261f,0.13111665844917297f,-0.03692615032196045f,-0.32796353101730347f,-0.21546880900859833f,0.049302369356155396f,-0.27088475227355957f,-0.4124959409236908f},
{-0.07586349546909332f,-0.36089158058166504f,0.33083590865135193f,-0.2909453213214874f,-0.14358049631118774f,1.0950231552124023f,-0.025492865592241287f,-0.3003333508968353f,0.2600560486316681f,-0.37898191809654236f,0.6435545086860657f,-0.5071706771850586f,-0.31673234701156616f,0.11079536378383636f,-11.455972671508789f,0.5229361057281494f},
{0.004702992737293243f,-0.1820937544107437f,-0.11379697918891907f,0.14139454066753387f,0.041274964809417725f,-0.14186520874500275f,-0.10284432768821716f,0.0019084513187408447f,0.06103590130805969f,-0.38046833872795105f,0.3429935574531555f,-0.34765779972076416f,-0.37024784088134766f,0.1993687003850937f,-0.2297692447900772f,-0.23237699270248413f},
{-0.34216949343681335f,0.23496045172214508f,-0.13502129912376404f,0.08847349882125854f,0.12987366318702698f,0.14208538830280304f,0.2711336314678192f,-0.3632148504257202f,-0.13619378209114075f,0.16938945651054382f,0.2009814977645874f,0.44322916865348816f,0.3811538517475128f,-0.24470730125904083f,0.04349624365568161f,-0.24874821305274963f},
{-0.28599539399147034f,0.0020868044812232256f,0.0457797646522522f,-0.3547317385673523f,-0.03321319818496704f,-0.42137426137924194f,0.17873415350914001f,-0.20421427488327026f,-0.050184011459350586f,0.12480869889259338f,-0.2116698920726776f,0.3545852601528168f,-0.3647043704986572f,0.40816983580589294f,-0.4018280804157257f,-0.27432969212532043f},
{0.1522299200296402f,-0.45329317450523376f,0.3954955041408539f,-0.48470574617385864f,0.0033026933670043945f,0.572025716304779f,-0.31212282180786133f,-0.11795541644096375f,0.3487861454486847f,-0.32520344853401184f,-3.3134469985961914f,-0.530846357345581f,0.0820283591747284f,-2.0381298065185547f,1.0461171865463257f,0.4835590124130249f},
{-0.2670588493347168f,-0.21156641840934753f,-0.15798500180244446f,0.38131895661354065f,-0.37393757700920105f,0.3658103048801422f,0.11292675137519836f,-0.2947862446308136f,-0.3764709532260895f,0.2424570620059967f,-0.10874747484922409f,-0.2837170362472534f,0.41839322447776794f,-0.016431119292974472f,-0.1284826099872589f,0.10878776758909225f},
{-0.08318141847848892f,0.9871321320533752f,-0.2018718123435974f,-1.6108821630477905f,0.07545611262321472f,0.18611471354961395f,-0.43937158584594727f,-0.21416273713111877f,-0.24509364366531372f,0.19522181153297424f,-0.010126939043402672f,-0.5335819721221924f,-0.16718891263008118f,-1.5700724124908447f,0.43778514862060547f,-0.32085344195365906f},
{0.4138670265674591f,0.1604653298854828f,0.056746453046798706f,0.036025404930114746f,0.3228367865085602f,-0.07083973288536072f,0.018455177545547485f,0.0059362053871154785f,0.40515169501304626f,0.014240056276321411f,-0.07738298177719116f,0.1407785713672638f,-0.13024571537971497f,-0.29546058177948f,-0.11976784467697144f,-0.35825538635253906f},
{-0.7150428295135498f,1.2618980407714844f,0.12081471085548401f,0.5926679968833923f,0.29976895451545715f,-1.5232646465301514f,-0.25536221265792847f,0.31089308857917786f,-0.3893685042858124f,-0.02222958207130432f,-1.6488481760025024f,-0.8796235918998718f,-0.19991017878055573f,1.0744037628173828f,0.49341896176338196f,-2.339517593383789f},
};
const float h3[16][16] = {
{-0.36079341173171997f,-4.516791343688965f,0.9862267971038818f,-0.4074249267578125f,-1.7838587760925293f,1.4453092813491821f,0.3332441747188568f,0.36921602487564087f,-0.3300304710865021f,-0.19002185761928558f,-0.40770405530929565f,0.4001283347606659f,2.8152735233306885f,-1.6125714778900146f,4.618896961212158f,0.12741845846176147f},
{0.047732532024383545f,-0.34105879068374634f,0.20525789260864258f,-0.2253294587135315f,0.3607877194881439f,0.141396164894104f,-0.3198729455471039f,-0.08264346420764923f,0.07495583593845367f,-0.02900463528931141f,0.32022908329963684f,-0.5149437785148621f,-1.6438157558441162f,-1.3210893869400024f,-2.072963237762451f,-0.2941063344478607f},
{0.07903262972831726f,0.2790505588054657f,-0.07798504829406738f,0.04248586297035217f,-0.1963958442211151f,-0.19260792434215546f,-0.4038352966308594f,0.015906542539596558f,0.15353140234947205f,0.030178606510162354f,0.2488909661769867f,0.13805970549583435f,-0.0816211998462677f,-0.20733052492141724f,-0.3036302626132965f,0.054825395345687866f},
{-0.30922991037368774f,-0.0848562940955162f,-0.2771536707878113f,-0.39299437403678894f,-0.501600980758667f,-0.07938367873430252f,0.20021501183509827f,-0.019295204430818558f,-0.5755168795585632f,-0.46145495772361755f,0.06848174333572388f,0.11526546627283096f,-0.9005468487739563f,-0.6515923142433167f,-0.5762438774108887f,-0.04038632661104202f},
{-0.39607733488082886f,-0.05481579899787903f,0.1976260244846344f,0.022423356771469116f,0.16892847418785095f,-0.27518749237060547f,0.16012099385261536f,0.3626593053340912f,-0.08640444278717041f,-0.11053556203842163f,-0.10529157519340515f,-0.31317979097366333f,-0.1530032455921173f,-0.1336749792098999f,0.22959044575691223f,0.19986507296562195f},
{-0.37449589371681213f,-0.9064159989356995f,-0.6610195636749268f,0.0874672383069992f,-0.5877532362937927f,0.3902459144592285f,-0.18732719123363495f,0.19508449733257294f,-0.6848570704460144f,-0.31486886739730835f,-0.0473649837076664f,-0.07467646896839142f,-0.5057598948478699f,1.9025719165802002f,0.09490102529525757f,-0.36226871609687805f},
{0.4110594093799591f,0.2790789306163788f,-0.31044068932533264f,0.37246426939964294f,0.21461978554725647f,-0.05120496079325676f,-0.08670487999916077f,-0.25336313247680664f,-0.030661463737487793f,-0.06259563565254211f,-0.1344406008720398f,0.35313835740089417f,0.19873254001140594f,0.11977154016494751f,0.3239758014678955f,-0.3391006588935852f},
{-0.40892091393470764f,0.043769627809524536f,-0.3867315948009491f,0.25968697667121887f,0.3424709737300873f,-0.051169753074645996f,-0.23312048614025116f,-0.390264093875885f,0.28059282898902893f,-0.1559126079082489f,-0.14134526252746582f,-0.0003446042537689209f,-0.2742875814437866f,-0.36560842394828796f,0.07994696497917175f,0.005298197269439697f},
{0.10697010159492493f,-0.12228584289550781f,-0.37870171666145325f,0.21184906363487244f,-0.37222859263420105f,-0.17138728499412537f,-0.1382003128528595f,0.3493293821811676f,-0.360889196395874f,-0.3875247836112976f,0.42142823338508606f,-0.3482915461063385f,-0.3289247751235962f,-0.2186824083328247f,0.09620395302772522f,-0.06898030638694763f},
{0.2847062647342682f,0.018552124500274658f,0.11435768008232117f,0.36562982201576233f,-0.047046810388565063f,0.30447837710380554f,0.2430230677127838f,0.2909286320209503f,-0.2802048921585083f,0.18043199181556702f,0.41849127411842346f,-0.287167489528656f,0.24394884705543518f,-0.14084559679031372f,-0.10168051719665527f,0.010465055704116821f},
{0.15459725260734558f,0.2614503502845764f,-0.8414085507392883f,-0.252727746963501f,-0.6894345283508301f,1.0636138916015625f,-0.08742031455039978f,0.06376123428344727f,-0.1714128702878952f,-0.47240930795669556f,0.1268840730190277f,-0.44391879439353943f,0.12466016411781311f,-0.9005870819091797f,-0.9095998406410217f,0.30346015095710754f},
{-0.408692330121994f,-0.10330183058977127f,-0.03088713251054287f,-0.04910988733172417f,-0.14289908111095428f,-0.08836136758327484f,0.03285527229309082f,0.38763079047203064f,-0.20705322921276093f,-0.26367273926734924f,0.12809070944786072f,0.03996849060058594f,-0.6194682121276855f,-0.3420376479625702f,-0.15302342176437378f,0.334671288728714f},
{-0.2991822361946106f,0.3794580399990082f,-0.07897943258285522f,-0.05932474136352539f,0.08582660555839539f,0.24227938055992126f,-0.11253207921981812f,0.34576353430747986f,0.04814547300338745f,-0.35770976543426514f,-0.044228196144104004f,-0.36229726672172546f,0.015840977430343628f,-0.13475483655929565f,0.36124154925346375f,-0.16869547963142395f},
{-0.2675279378890991f,-0.2572242021560669f,-0.008989264257252216f,-0.14364181458950043f,2.3832051753997803f,0.2777503728866577f,-0.32875844836235046f,-0.2555496394634247f,-0.6392947435379028f,-0.7831358909606934f,-0.5172973275184631f,-0.6818525195121765f,0.8480085134506226f,-0.1394871473312378f,-1.3122553825378418f,0.1775851845741272f},
{-0.015470266342163086f,0.5476723909378052f,0.4976131021976471f,0.19412125647068024f,-1.3260929584503174f,-1.7757221460342407f,0.05196094512939453f,0.09510938823223114f,-0.42801159620285034f,-0.7967047095298767f,0.13606210052967072f,-0.11511552333831787f,-0.7240217924118042f,-0.9549937844276428f,-0.9997981190681458f,-0.45693734288215637f},
{0.1863725483417511f,0.9262488484382629f,-0.6855837106704712f,-0.577112078666687f,-0.642444372177124f,-0.24064891040325165f,0.04860696196556091f,0.14380735158920288f,-0.2648492157459259f,-0.029172860085964203f,-0.3929237127304077f,-0.10258594900369644f,1.1357184648513794f,0.016820937395095825f,1.862500786781311f,-0.1434863805770874f},
};
const float hout[16] = { 0.45773375034332275f,0.22148412466049194f,-0.22813020646572113f,-0.08917035162448883f,-0.21528248488903046f,0.29861685633659363f,0.0030125975608825684f,0.1412937343120575f,0.04779195412993431f,0.05501026287674904f,0.13024552166461945f,-0.04984400048851967f,-0.304860919713974f,-0.14634203910827637f,0.23745152354240417f,-0.16097530722618103f };
const float b1[16] = { 0.3074471652507782f,2.836015224456787f,-1.7145336866378784f,0.2683033347129822f,0.6529231071472168f,0.9833991527557373f,-0.058932315558195114f,2.29449462890625f,0.9298062920570374f,-0.9408509135246277f,0.5694966912269592f,1.5112576484680176f,-0.3744742274284363f,-1.0548338890075684f,-1.087764859199524f,0.6528083682060242f };
const float b2[16] = { 0.6096800565719604f,-0.6226189136505127f,-1.4564176797866821f,-0.5512577891349792f,-0.6939148902893066f,0.9173181653022766f,-0.0477285161614418f,-0.30969977378845215f,-1.200630784034729f,-1.912178635597229f,0.6023832559585571f,-0.04530715569853783f,-0.07918518036603928f,0.8115787506103516f,0.43986114859580994f,1.1172503232955933f };
const float b3[16] = { -1.963319182395935f,0.43098294734954834f,1.14909827709198f,-0.260453462600708f,-0.3398900330066681f,0.9021360874176025f,-0.45353031158447266f,-0.7342051267623901f,0.2843529284000397f,0.16309885680675507f,-0.24944843351840973f,-0.24138091504573822f,-0.16837841272354126f,-0.15490709245204926f,-0.771912157535553f,-0.42885565757751465f };
const float bout[1] = { -0.08879395574331284f };
/////////////////////////////////////////////////////////////////////////////////////////////RL
float input_RL[num_input_RL] = { 0.0f };
//Critic Networks
float hc1[num_input_RL][num_hidden_unit1] = {0.0f};
float bc1[num_hidden_unit1] = {0.0f};
float hc2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
float bc2[num_hidden_unit2] = {0.0f};
float hc3[num_hidden_unit2] = {0.0f};
float bc3 = 0.0f;
//Critic Networks Temporary
float hc1_temp[num_input_RL][num_hidden_unit1] = {0.0f};
float bc1_temp[num_hidden_unit1] = {0.0f};
float hc2_temp[num_hidden_unit1][num_hidden_unit2] = {0.0f};
float bc2_temp[num_hidden_unit2] = {0.0f};
float hc3_temp[num_hidden_unit2] = {0.0f};
float bc3_temp = 0.0f;
//Actor Networks
float ha1[num_input_RL][num_hidden_unit1] = {0.0f};
float ba1[num_hidden_unit1] = {0.0f};
float ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
float ba2[num_hidden_unit2] = {0.0f};
float ha3[num_hidden_unit2][2] = {0.0f};
float ba3[2] = {0.0f};
//Actor Networks Temporary
float ha1_temp[num_input_RL][num_hidden_unit1] = {0.0f};
float ba1_temp[num_hidden_unit1] = {0.0f};
float ha2_temp[num_hidden_unit1][num_hidden_unit2] = {0.0f};
float ba2_temp[num_hidden_unit2] = {0.0f};
float ha3_temp[num_hidden_unit2][2] = {0.0f};
float ba3_temp[2] = {0.0f};
float VALVE_POS_RAW_NN = 0.0f;
float DDV_JOINT_POS_FF(float REF_JOINT_VEL);
/////////////////////////////////////////////RL tuning
float Gradient_Limit = 0.5f;
float gradient_rate_actor = 0.001f;
float gradient_rate_critic = 0.001f;
//////////////////////////////////////////////////////////////////////////////
float Critic_Network_Temp(float *arr)
{
float output1[num_hidden_unit1] = { 0.0f };
float output2[num_hidden_unit2] = { 0.0f };
float output = 0.0f;
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
output1[index2] = output1[index2] + hc1_temp[index1][index2] * arr[index1];
}
//ReLU
output1[index2] = output1[index2] + bc1_temp[index2];
hx_c_sum[index2] = output1[index2];
if (output1[index2] < 0) {
output1[index2] = 0;
}
//tanh
//output1[index2] = tanh(output1[index2] + bc1_temp[index2]);
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
output2[index2] = output2[index2] + hc2_temp[index1][index2] * output1[index1];
}
//ReLU
output2[index2] = output2[index2] + bc2_temp[index2];
hxh_c_sum[index2] = output2[index2];
if (output2[index2] < 0) {
output2[index2] = 0;
}
//tanh
//output2[index2] = tanh(output2[index2] + bc2_temp[index2]);
}
for (int index2 = 0; index2 < 1; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
output = output + hc3_temp[index1] * output2[index1];
}
output = output + bc3_temp;
hxhh_c_sum = output;
}
return output;
}
void Actor_Network(float *arr)
{
float output1[num_hidden_unit1] = {0.0f};
float output2[num_hidden_unit2] = {0.0f};
float output[2] = {0.0f};
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
output1[index2] = output1[index2] + ha1_temp[index1][index2] * arr[index1];
}
output1[index2] = output1[index2] + ba1_temp[index2];
hx_a_sum[index2] = output1[index2];
if (output1[index2] < 0) {
output1[index2] = 0;
}
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
output2[index2] = output2[index2] + ha2_temp[index1][index2] * output1[index1];
}
output2[index2] = output2[index2] + ba2_temp[index2];
hxh_a_sum[index2] = output2[index2];
if (output2[index2] < 0) {
output2[index2] = 0;
}
}
for (int index2 = 0; index2 < 2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
output[index2] = output[index2] + ha3_temp[index1][index2] * output2[index1];
}
hxhh_a_sum[index2] = output[index2] + ba3_temp[index2];
}
mean_before_SP = output[0] + ba3_temp[0]; //SP = softplus
deviation_before_SP = output[1] + ba3_temp[1];
//Softplus
mean = log(1.0f+exp(mean_before_SP));
deviation = log(1.0f+exp(deviation_before_SP));
logging2 = mean;
logging4 = deviation;
}
void Actor_Network_Old(float *arr)
{
float output1[num_hidden_unit1] = {0.0f};
float output2[num_hidden_unit2] = {0.0f};
float output[2] = {0.0f};
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
output1[index2] = output1[index2] + ha1[index1][index2] * arr[index1];
}
output1[index2] = output1[index2] + ba1[index2];
if (output1[index2] < 0) {
output1[index2] = 0;
}
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
output2[index2] = output2[index2] + ha2[index1][index2] * output1[index1];
}
output2[index2] = output2[index2] + ba2[index2];
if (output2[index2] < 0) {
output2[index2] = 0;
}
}
for (int index2 = 0; index2 < 2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
output[index2] = output[index2] + ha3[index1][index2] * output2[index1];
}
}
mean_old = output[0] + ba3[0];
deviation_old = output[1] + ba3[1];
//Softplus
mean_old = log(1.0f+exp(mean_old));
deviation_old = log(1.0f+exp(deviation_old));
}
float Grad_Normal_Dist_Mean(float mean, float deviation, float action)
{
float grad_mean = 0.0f;
grad_mean = (action-mean)*exp(-(action-mean)*(action-mean)/(2.0f*deviation*deviation))/(sqrt(2.0f*PI)*deviation*deviation*deviation);
return grad_mean;
}
float Grad_Normal_Dist_Deviation(float mean, float deviation, float action)
{
float grad_dev = 0.0f;
grad_dev = exp(-(action-mean)*(action-mean)/(2.0f*deviation*deviation))*(-1.0f/(sqrt(2.0f*PI)*deviation*deviation) + (action-mean)*(action-mean)/(sqrt(2.0f*PI)*deviation*deviation*deviation*deviation));
return grad_dev;
}
float ReLU(float x)
{
if (x >= 0) {
return x;
} else {
return 0.0f;
}
}
void update_Critic_Networks(float (*arr)[num_input_RL])
{
float G_hc1[num_input_RL][num_hidden_unit1] = {0.0f};
float G_bc1[num_hidden_unit1] = {0.0f};
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
for (int n=0; n<batch_size; n++) {
float d_V_d_hc1 = 0.0f;
for(int k=0; k<num_hidden_unit2; k++) {
if (hxh_c_sum_array[n][k] >= 0) {
if (hx_c_sum_array[n][index2] > 0) {
d_V_d_hc1 = d_V_d_hc1 + arr[n][index1]*hc2_temp[index2][k]*hc3_temp[k];
}
}
}
G_hc1[index1][index2] = G_hc1[index1][index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc1);
}
G_hc1[index1][index2] = G_hc1[index1][index2] / batch_size;
if(G_hc1[index1][index2] > Gradient_Limit) G_hc1[index1][index2] = Gradient_Limit;
else if (G_hc1[index1][index2] < -Gradient_Limit) G_hc1[index1][index2] = -Gradient_Limit;
//hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate_critic * G_hc1[index1][index2];
}
for (int n=0; n<batch_size; n++) {
float d_V_d_bc1 = 0.0f;
for(int k=0; k<num_hidden_unit2; k++) {
if (hxh_c_sum_array[n][k] >= 0) {
if (hx_c_sum_array[n][index2] > 0) {
d_V_d_bc1 = d_V_d_bc1 + hc2_temp[index2][k]*hc3_temp[k];
}
}
}
G_bc1[index2] = G_bc1[index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc1);
}
G_bc1[index2] = G_bc1[index2] / batch_size;
if(G_bc1[index2] > Gradient_Limit) G_bc1[index2] = Gradient_Limit;
else if (G_bc1[index2] < -Gradient_Limit) G_bc1[index2] = -Gradient_Limit;
//bc1_temp[index2] = bc1_temp[index2] - gradient_rate_critic * G_bc1[index2];
}
float G_hc2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
float G_bc2[num_hidden_unit2] = {0.0f};
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
for (int n=0; n<batch_size; n++) {
float d_V_d_hc2 = 0.0f;
if (hxh_c_sum_array[n][index2] >= 0) {
if (hx_c_sum_array[n][index1] > 0) {
d_V_d_hc2 = hx_c_sum_array[n][index1]*hc3_temp[index2];
}
}
G_hc2[index1][index2] = G_hc2[index1][index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc2);
}
G_hc2[index1][index2] = G_hc2[index1][index2] / batch_size;
if(G_hc2[index1][index2] > Gradient_Limit) G_hc2[index1][index2] = Gradient_Limit;
else if (G_hc2[index1][index2] < -Gradient_Limit) G_hc2[index1][index2] = -Gradient_Limit;
//hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate_critic * G_hc2[index1][index2];
}
for (int n=0; n<batch_size; n++) {
float d_V_d_bc2 = 0.0f;
if (hxh_c_sum_array[n][index2] >= 0) {
d_V_d_bc2 = hc3_temp[index2];
}
G_bc2[index2] = G_bc2[index2] + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc2);
}
G_bc2[index2] = G_bc2[index2] / batch_size;
if(G_bc2[index2] > Gradient_Limit) G_bc2[index2] = Gradient_Limit;
else if (G_bc2[index2] < -Gradient_Limit) G_bc2[index2] = -Gradient_Limit;
//bc2_temp[index2] = bc2_temp[index2] - gradient_rate_critic * G_bc2[index2];
}
float G_hc3[num_hidden_unit2]= {0.0f};
float G_bc3 = 0.0f;
for (int index2 = 0; index2 < 1; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
for (int n=0; n<batch_size; n++) {
float d_V_d_hc3 = 0.0f;
if (hxh_c_sum_array[n][index1] >= 0) {
d_V_d_hc3 = d_V_d_hc3 + hxh_c_sum_array[n][index1];
}
G_hc3[index1] = G_hc3[index1] + 2.0f*(return_G[n]-V[n])*(-d_V_d_hc3);
}
G_hc3[index1] = G_hc3[index1] / batch_size;
if(G_hc3[index1] > Gradient_Limit) G_hc3[index1] = Gradient_Limit;
else if (G_hc3[index1] < -Gradient_Limit) G_hc3[index1] = -Gradient_Limit;
//hc3_temp[index1] = hc3_temp[index1] - gradient_rate_critic * G_hc3[index1];
}
for (int n=0; n<batch_size; n++) {
float d_V_d_bc3 = 0.0f;
d_V_d_bc3 = 1.0f;
G_bc3 = G_bc3 + 2.0f*(return_G[n]-V[n])*(-d_V_d_bc3);
}
G_bc3 = G_bc3 / batch_size;
if(G_bc3 > Gradient_Limit) G_bc3 = Gradient_Limit;
else if (G_bc3 < -Gradient_Limit) G_bc3 = -Gradient_Limit;
//bc3_temp = bc3_temp - gradient_rate_critic * G_bc3;
}
// Simultaneous Update
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
hc1_temp[index1][index2] = hc1_temp[index1][index2] - gradient_rate_critic * G_hc1[index1][index2];
}
bc1_temp[index2] = bc1_temp[index2] - gradient_rate_critic * G_bc1[index2];
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
hc2_temp[index1][index2] = hc2_temp[index1][index2] - gradient_rate_critic * G_hc2[index1][index2];
}
bc2_temp[index2] = bc2_temp[index2] - gradient_rate_critic * G_bc2[index2];
}
for (int index2 = 0; index2 < 1; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
hc3_temp[index1] = hc3_temp[index1] - gradient_rate_critic * G_hc3[index1];
}
bc3_temp = bc3_temp - gradient_rate_critic * G_bc3;
}
}
///////////////////////////Softplus//////////////////////////////////
void update_Actor_Networks(float (*arr)[num_input_RL])
{
float G_ha1[num_input_RL][num_hidden_unit1] = {0.0f};
float G_ba1[num_hidden_unit1] = {0.0f};
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
for (int n=0; n<batch_size; n++) {
float d_x_d_ha1 = 0.0f;
float d_y_d_ha1 = 0.0f;
if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
G_ha1[index1][index2] = G_ha1[index1][index2];
} else {
for(int k=0; k<num_hidden_unit2; k++) {
if (hxh_a_sum_array[n][k] >= 0) {
if (hx_a_sum_array[n][index2] > 0) {
d_x_d_ha1 = d_x_d_ha1 + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][0];
d_y_d_ha1 = d_y_d_ha1 + arr[n][index1]*ha2_temp[index2][k]*ha3_temp[k][1];
}
}
}
float d_mean_d_ha1 = 0.0f;
float d_dev_d_ha1 = 0.0f;
d_mean_d_ha1 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha1;
d_dev_d_ha1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha1;
G_ha1[index1][index2] = G_ha1[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha1*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha1*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
}
}
G_ha1[index1][index2] = -G_ha1[index1][index2] / batch_size;
if(G_ha1[index1][index2] > Gradient_Limit) G_ha1[index1][index2] = Gradient_Limit;
else if (G_ha1[index1][index2] < -Gradient_Limit) G_ha1[index1][index2] = -Gradient_Limit;
//ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate_actor * G_ha1[index1][index2];
}
for (int n=0; n<batch_size; n++) {
float d_x_d_ba1 = 0.0f;
float d_y_d_ba1 = 0.0f;
if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
G_ba1[index2] = G_ba1[index2];
} else {
for(int k=0; k<num_hidden_unit2; k++) {
if (hxh_a_sum_array[n][k] >= 0) {
if (hx_a_sum_array[n][index2] > 0) {
d_x_d_ba1 = d_x_d_ba1 + ha2_temp[index2][k]*ha3_temp[k][0];
d_y_d_ba1 = d_y_d_ba1 + ha2_temp[index2][k]*ha3_temp[k][1];
}
}
}
float d_mean_d_ba1 = 0.0f;
float d_dev_d_ba1 = 0.0f;
d_mean_d_ba1 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba1;
d_dev_d_ba1 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba1;
G_ba1[index2] = G_ba1[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba1*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba1*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
}
}
G_ba1[index2] = -G_ba1[index2] / batch_size;
if(G_ba1[index2] > Gradient_Limit) G_ba1[index2] = Gradient_Limit;
else if (G_ba1[index2] < -Gradient_Limit) G_ba1[index2] = -Gradient_Limit;
//ba1_temp[index2] = ba1_temp[index2] - gradient_rate_actor * G_ba1[index2];
}
float G_ha2[num_hidden_unit1][num_hidden_unit2] = {0.0f};
float G_ba2[num_hidden_unit2] = {0.0f};
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
for (int n=0; n<batch_size; n++) {
float d_x_d_ha2 = 0.0f;
float d_y_d_ha2 = 0.0f;
if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
G_ha2[index1][index2] = G_ha2[index1][index2];
} else {
if (hxh_a_sum_array[n][index2] >= 0) {
if (hx_a_sum_array[n][index1] > 0) {
d_x_d_ha2 = hx_a_sum_array[n][index1]*ha3_temp[index2][0];
d_y_d_ha2 = hx_a_sum_array[n][index1]*ha3_temp[index2][1];
}
}
float d_mean_d_ha2 = 0.0f;
float d_dev_d_ha2 = 0.0f;
d_mean_d_ha2 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha2;
d_dev_d_ha2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha2;
G_ha2[index1][index2] = G_ha2[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha2*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha2*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
}
}
G_ha2[index1][index2] = -G_ha2[index1][index2] / batch_size;
if(G_ha2[index1][index2] > Gradient_Limit) G_ha2[index1][index2] = Gradient_Limit;
else if (G_ha2[index1][index2] < -Gradient_Limit) G_ha2[index1][index2] = -Gradient_Limit;
//ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate_actor * G_ha2[index1][index2];
}
for (int n=0; n<batch_size; n++) {
float d_x_d_ba2 = 0.0f;
float d_y_d_ba2 = 0.0f;
if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
G_ba2[index2] = G_ba2[index2];
} else {
if (hxh_a_sum_array[n][index2] >= 0) {
d_x_d_ba2 = ha3_temp[index2][0];
d_y_d_ba2 = ha3_temp[index2][1];
}
float d_mean_d_ba2= 0.0f;
float d_dev_d_ba2= 0.0f;
d_mean_d_ba2 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba2;
d_dev_d_ba2 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba2;
G_ba2[index2] = G_ba2[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba2*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba2*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
}
}
G_ba2[index2] = -G_ba2[index2] / batch_size;
if(G_ba2[index2] > Gradient_Limit) G_ba2[index2] = Gradient_Limit;
else if (G_ba2[index2] < -Gradient_Limit) G_ba2[index2] = -Gradient_Limit;
//ba2_temp[index2] = ba2_temp[index2] - gradient_rate_actor * G_ba2[index2];
}
float G_ha3[num_hidden_unit2][2] = {0.0f};
float G_ba3[2] = {0.0f};
for (int index2 = 0; index2 < 2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
for (int n=0; n<batch_size; n++) {
float d_x_d_ha3 = 0.0f;
float d_y_d_ha3 = 0.0f;
if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
G_ha3[index1][index2] = G_ha3[index1][index2];
} else {
if (hxh_a_sum_array[n][index1] >= 0) {
if (hx_a_sum_array[n][index1] > 0) {
d_x_d_ha3 = hxh_a_sum_array[n][index1];
d_y_d_ha3 = hxh_a_sum_array[n][index1];
}
}
float d_mean_d_ha3 = 0.0f;
float d_dev_d_ha3 = 0.0f;
d_mean_d_ha3 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ha3;
d_dev_d_ha3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ha3;
G_ha3[index1][index2] = G_ha3[index1][index2] + advantage[n]/pi_old[n]*(d_mean_d_ha3*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ha3*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
}
}
G_ha3[index1][index2] = -G_ha3[index1][index2] / batch_size;
if(G_ha3[index1][index2] > Gradient_Limit) G_ha3[index1][index2] = Gradient_Limit;
else if (G_ha3[index1][index2] < -Gradient_Limit) G_ha3[index1][index2] = -Gradient_Limit;
//ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate_actor * G_ha3[index1][index2];
}
for (int n=0; n<batch_size; n++) {
float d_x_d_ba3 = 0.0f;
float d_y_d_ba3 = 0.0f;
if((advantage[n] >= 0.0f && ratio[n] >= 1.0f + epsilon) || (advantage[n] < 0.0f && ratio[n] < 1.0f - epsilon)) {
G_ba3[index2] = G_ba3[index2];
} else {
d_x_d_ba3 = 1.0f;
d_y_d_ba3 = 1.0f;
float d_mean_d_ba3= 0.0f;
float d_dev_d_ba3= 0.0f;
d_mean_d_ba3 = exp(hxhh_a_sum_array[n][0])/(1.0f+exp(hxhh_a_sum_array[n][0]))*d_x_d_ba3;
d_dev_d_ba3 = exp(hxhh_a_sum_array[n][1])/(1.0f+exp(hxhh_a_sum_array[n][1]))*d_y_d_ba3;
G_ba3[index2] = G_ba3[index2] + advantage[n]/pi_old[n]*(d_mean_d_ba3*Grad_Normal_Dist_Mean(mean_array[n],deviation_array[n],action_array[n])+d_dev_d_ba3*Grad_Normal_Dist_Deviation(mean_array[n],deviation_array[n],action_array[n]));
}
}
G_ba3[index2] = -G_ba3[index2] / batch_size;
if(G_ba3[index2] > Gradient_Limit) G_ba3[index2] = Gradient_Limit;
else if (G_ba3[index2] < -Gradient_Limit) G_ba3[index2] = -Gradient_Limit;
//ba3_temp[index2] = ba3_temp[index2] - gradient_rate_actor * G_ba3[index2];
}
// Simultaneous Update
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
ha1_temp[index1][index2] = ha1_temp[index1][index2] - gradient_rate_actor * G_ha1[index1][index2];
}
ba1_temp[index2] = ba1_temp[index2] - gradient_rate_actor * G_ba1[index2];
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
ha2_temp[index1][index2] = ha2_temp[index1][index2] - gradient_rate_actor * G_ha2[index1][index2];
}
ba2_temp[index2] = ba2_temp[index2] - gradient_rate_actor * G_ba2[index2];
}
for (int index2 = 0; index2 < 2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
ha3_temp[index1][index2] = ha3_temp[index1][index2] - gradient_rate_actor * G_ha3[index1][index2];
}
ba3_temp[index2] = ba3_temp[index2] - gradient_rate_actor * G_ba3[index2];
}
}
float rand_normal(double mean, double stddev)
{
//Box muller method
static double n2 = 0.0f;
static int n2_cached = 0;
if (!n2_cached) {
double x, y, r;
do {
x = 2.0f*rand()/RAND_MAX - 1;
y = 2.0f*rand()/RAND_MAX - 1;
r = x*x + y*y;
} while (r == 0.0f || r > 1.0f);
{
double d = sqrt(-2.0f*log(r)/r);
double n1 = x*d;
n2 = y*d;
double result = n1*stddev + mean;
n2_cached = 1;
return result;
}
} else {
n2_cached = 0;
return n2*stddev + mean;
}
}
float mean_adv(float x[], int size)
{
float add = 0.0f;
float result;
for (int i=0; i<size; i++)
{
add += x[i];
}
result = (float) add/size;
return result;
}
float deviation_adv(float x[], int size)
{
float sigma = 0.0f;
float resultDeb = 0.0f;
for (int k=0; k<size; k++)
{
sigma = pow((float)x[k]-mean_adv(x,size), (float)2.0f)/(size-1);
resultDeb += sqrt(sigma);
}
return resultDeb;
}
void Overwirte_Critic_Networks()
{
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
hc1[index1][index2] = hc1_temp[index1][index2];
}
bc1[index2] = bc1_temp[index2];
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
hc2[index1][index2] = hc2_temp[index1][index2];
}
bc2[index2] = bc2_temp[index2];
hc3[index2] = hc3_temp[index2];
}
bc3 = bc3_temp;
}
void Overwirte_Actor_Networks()
{
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
ha1[index1][index2] = ha1_temp[index1][index2];
}
ba1[index2] = ba1_temp[index2];
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
ha2[index1][index2] = ha2_temp[index1][index2];
}
ba2[index2] = ba2_temp[index2];
}
for (int index2 = 0; index2 < 2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
ha3[index1][index2] = ha3_temp[index1][index2];
}
ba3[index2] = ba3_temp[index2];
}
}
int main()
{
HAL_Init();
SystemClock_Config();
/*********************************
*** Initialization
*********************************/
LED = 0;
pc.baud(9600);
// i2c init
i2c.frequency(400 * 1000); // 0.4 mHz
wait_ms(2); // Power Up wait
look_for_hardware_i2c(); // Hardware present
init_as5510(i2c_slave_addr1);
make_delay();
// // spi init
eeprom.format(8,3);
eeprom.frequency(5000000); //5M
enc.format(8,0);
enc.frequency(5000000); //5M
make_delay();
//rom
ROM_CALL_DATA();
make_delay();
// ADC init
Init_ADC();
make_delay();
// Pwm init
Init_PWM();
TIM4->CR1 ^= TIM_CR1_UDIS;
make_delay();
// TMR3 init
Init_TMR3();
TIM3->CR1 ^= TIM_CR1_UDIS;
make_delay();
// TMR2 init
// Init_TMR2();
// TIM2->CR1 ^= TIM_CR1_UDIS;
// make_delay();
// CAN
can.attach(&CAN_RX_HANDLER);
CAN_ID_INIT();
make_delay();
//Timer priority
NVIC_SetPriority(TIM3_IRQn, 2);
//NVIC_SetPriority(TIM2_IRQn, 3);
NVIC_SetPriority(TIM4_IRQn, 3);
//can.reset();
can.filter(msg.id, 0xFFFFF000, CANStandard);
// spi _ enc
spi_enc_set_init();
make_delay();
//DAC init
if (SENSING_MODE == 0) {
dac_1 = TORQUE_VREF / 3.3f;
dac_2 = 0.0f;
} else if (SENSING_MODE == 1) {
dac_1 = PRES_A_VREF / 3.3f;
dac_2 = PRES_B_VREF / 3.3f;
}
make_delay();
for (int i=0; i<50; i++) {
if(i%2==0)
ID_index_array[i] = - i * 0.5f;
else
ID_index_array[i] = (i+1) * 0.5f;
}
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
hc1_temp[index1][index2] = (float) (rand()%100) * 0.007f ;
}
bc1_temp[index2] = (float) (rand()%100) * 0.007f;
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
hc2_temp[index1][index2] = (float) (rand()%100) * 0.007f;
}
bc2_temp[index2] = (float) (rand()%100) * 0.007f;
hc3_temp[index2] = (float) (rand()%100) * 0.007f;
}
bc3_temp = (float) (rand()%100) * 0.007f;
for (int index2 = 0; index2 < num_hidden_unit1; index2++) {
for (int index1 = 0; index1 < num_input_RL; index1++) {
ha1_temp[index1][index2] = (float) (rand()%100) * 0.007f;
}
ba1_temp[index2] = (float) (rand()%100) * 0.007f;
}
for (int index2 = 0; index2 < num_hidden_unit2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit1; index1++) {
ha2_temp[index1][index2] = (float) (rand()%100) * 0.007f;
}
ba2_temp[index2] = (float) (rand()%100) * 0.007f;
}
for (int index2 = 0; index2 < 2; index2++) {
for (int index1 = 0; index1 < num_hidden_unit2; index1++) {
ha3_temp[index1][index2] = (float) (rand()%100) * 0.007f;
}
ba3_temp[index2] = (float) (rand()%100) * 0.007f;
}
Overwirte_Critic_Networks();
Overwirte_Actor_Networks();
/************************************
*** Program is operating!
*************************************/
while(1) {
// if(timer_while==27491) {
// timer_while = 0;
// pc.printf("ref : %f virt_pos : %f mean : %f deviation : %f Last_pos_of_batch : %f reward_sum : %f\n", pos.sen/(float)(ENC_PULSE_PER_POSITION), logging3, logging2, logging4, logging1, logging5);
// //pc.printf("%f\n", virt_pos);
// //pc.printf("%f\n", pos.sen/(float)(ENC_PULSE_PER_POSITION));
// //pc.printf("ref : %f virt_pos : %f\n", pos.sen/(float)(ENC_PULSE_PER_POSITION), virt_pos);
// }
//i2c
read_field(i2c_slave_addr1);
if(DIR_VALVE_ENC < 0) value = 1023 - value;
//timer_while ++;
///////////////////////////////////////////////////////Neural Network
if(NN_Control_Flag == 0) {
LED = 0;
}
else if(NN_Control_Flag == 1) {
int ind = 0;
for(int i=0; i<numpast_u; i++) {
input_NN[ind] = u_past[time_interval*i];
ind = ind + 1;
}
for(int i=0; i<numpast_x; i++) {
input_NN[ind] = x_past[time_interval*i] / 60.0f;
ind = ind + 1;
}
input_NN[ind] = (pos.sen / ENC_PULSE_PER_POSITION) / 60.0f;
ind = ind + 1;
// for(int i=0; i<numfuture_x; i++) {
// input_NN[ind] = x_future[time_interval*i+time_interval] / 60.0f;
// ind = ind + 1;
// }
for(int i=0; i<numpast_f; i++) {
// input_NN[ind] = f_past[time_interval*i] / 10000.0f * 8.0f + 0.5f;
input_NN[ind] = f_past[time_interval*i] / 10000.0f + 0.5f;
ind = ind + 1;
}
// input_NN[ind] = torq.sen / 10000.0f * 8.0f + 0.5f;
input_NN[ind] = torq.sen / 10000.0f + 0.5f;
ind = ind + 1;
for(int i=0; i<numfuture_f; i++) {
// input_NN[ind] = (f_future[time_interval*i+time_interval] - torq.sen)/10000.0f * 8.0f + 0.5f;
// input_NN[ind] = (f_future[time_interval*i+time_interval] - torq.sen)/10000.0f + 0.5f;
// input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f*8.0f+0.5f;
input_NN[ind] = (f_future[time_interval*i+time_interval])/10000.0f + 0.5f;
ind = ind + 1;
}
float output1[16] = { 0.0f };
float output2[16] = { 0.0f };
float output3[16] = { 0.0f };
float output = 0.0f;
for (int index2 = 0; index2 < 16; index2++) {
for (int index1 = 0; index1 < num_input; index1++) {
output1[index2] = output1[index2]
+ h1[index1][index2] * input_NN[index1];
}
output1[index2] = output1[index2] + b1[index2];
if (output1[index2] < 0) {
output1[index2] = 0;
}
}
for (int index2 = 0; index2 < 16; index2++) {
for (int index1 = 0; index1 < 16; index1++) {
output2[index2] = output2[index2]
+ h2[index1][index2] * output1[index1];
}
output2[index2] = output2[index2] + b2[index2];
if (output2[index2] < 0) {
output2[index2] = 0;
}
}
for (int index2 = 0; index2 < 16; index2++) {
for (int index1 = 0; index1 < 16; index1++) {
output3[index2] = output3[index2]
+ h3[index1][index2] * output2[index1];
}
output3[index2] = output3[index2] + b3[index2];
if (output3[index2] < 0) {
output3[index2] = 0;
}
}
for (int index2 = 0; index2 < 1; index2++) {
for (int index1 = 0; index1 < 16; index1++) {
output = output + hout[index1] * output3[index1];
}
output = output + bout[index2];
}
output = 1.0f/(1.0f+exp(-output));
output_normalized = output;
output = output * 20000.0f - 10000.0f;
if(output>=0) {
valve_pos.ref = output*0.0001f*((double)VALVE_MAX_POS - (double) VALVE_CENTER) + (double) VALVE_CENTER;
} else {
valve_pos.ref = -output*0.0001f*((double)VALVE_MIN_POS - (double) VALVE_CENTER) + (double) VALVE_CENTER;
}
if(LED==1) {
LED=0;
} else
LED = 1;
}
/////////////////////////////////////////////////////////////////////RL
switch (Update_Case) {
case 0: {
break;
}
case 1: {
//Network Update(just update and hold network)
for (int epoch = 0; epoch < num_epoch; epoch++) {
float loss_sum = 0.0f;
for (int n=batch_size-1; n>=0; n--) {
//Calculate Estimated V
//float temp_array[3] = {state_array[n][0], state_array[n][1], state_array[n][2]};
float temp_array[2] = {state_array[n][0], state_array[n][1]};
V[n] = Critic_Network_Temp(temp_array);
for (int i=0; i<num_hidden_unit1; i++) {
hx_c_sum_array[n][i] = hx_c_sum[i];
}
for (int i=0; i<num_hidden_unit2; i++) {
hxh_c_sum_array[n][i] = hxh_c_sum[i];
}
hxhh_c_sum_array[n] = hxhh_c_sum;
pi[n] = exp(-(action_array[n]-mean_array[n])*(action_array[n]-mean_array[n])/(2.0f*deviation_array[n]*deviation_array[n]))/(sqrt(2.0f*PI)*deviation_array[n]);
Actor_Network_Old(temp_array);
pi_old[n] = exp(-(action_array[n]-mean_old)*(action_array[n]-mean_old)/(2.0f*deviation_old*deviation_old))/(sqrt(2.0f*PI)*deviation_old);
r[n] = exp(-0.25f * 5.0f * state_array[n][1] * state_array[n][1]);
if(n == batch_size-1) return_G[n] = 0.0f;
else return_G[n] = gamma * return_G[n+1] + r[n];
if(n == batch_size-1) td_target[n] = r[n];
else td_target[n] = r[n] + gamma * V[n+1];
delta[n] = td_target[n] - V[n];
if(n == batch_size-1) advantage[n] = 0.0f;
else advantage[n] = gamma * lmbda * advantage[n+1] + delta[n];
// return_G[n] = advantage[n] + V[n];
ratio[n] = pi[n]/pi_old[n];
}
float mean_advantage = 0.0f;
float dev_advantage = 0.0f;
mean_advantage = mean_adv(advantage, batch_size);
dev_advantage = deviation_adv(advantage, batch_size);
for (int n=batch_size-1; n>=0; n--) {
//advantage[n] = (advantage[n]-mean_advantage)/dev_advantage;
surr1[n] = ratio[n] * advantage[n];
if (ratio[n] > 1.0f + epsilon) {
surr2[n] = (1.0f + epsilon)*advantage[n];
} else if( ratio[n] < 1.0f - epsilon) {
surr2[n] = (1.0f - epsilon)*advantage[n];
} else {
surr2[n] = ratio[n]*advantage[n];
}
loss[n] = -min(surr1[n], surr2[n]);
loss_sum = loss_sum + loss[n];
}
reward_sum = 0.0f;
for (int i=0; i<batch_size; i++) {
reward_sum = reward_sum + r[i];
}
logging5 = reward_sum;
//loss_batch = loss_sum / (float) batch_size;
loss_batch = loss_sum;
//Update Networks
update_Critic_Networks(state_array);
update_Actor_Networks(state_array);
}
Update_Done_Flag = 1;
Update_Case = 0;
//logging1 = V[0];
break;
}
case 2: {
//Network apply to next Network
Overwirte_Critic_Networks();
Overwirte_Actor_Networks();
virt_pos = 10.0f;
Update_Done_Flag = 1;
Update_Case = 0;
break;
}
}
}
}
float DDV_JOINT_POS_FF(float REF_JOINT_VEL)
{
int i = 0;
float Ref_Valve_Pos_FF = 0.0f;
for(i=0; i<VALVE_POS_NUM; i++) {
if(REF_JOINT_VEL >= min(JOINT_VEL[i],JOINT_VEL[i+1]) && REF_JOINT_VEL <= max(JOINT_VEL[i],JOINT_VEL[i+1])) {
if(i==0) {
if(JOINT_VEL[i+1] == JOINT_VEL[i]) {
Ref_Valve_Pos_FF = (float) VALVE_CENTER;
} else {
Ref_Valve_Pos_FF = ((float) 10/(JOINT_VEL[i+1] - JOINT_VEL[i]) * (REF_JOINT_VEL - JOINT_VEL[i])) + (float) VALVE_CENTER;
}
} else {
if(JOINT_VEL[i+1] == JOINT_VEL[i-1]) {
Ref_Valve_Pos_FF = (float) VALVE_CENTER;
} else {
Ref_Valve_Pos_FF = ((float) 10*(ID_index_array[i+1] - ID_index_array[i-1])/(JOINT_VEL[i+1] - JOINT_VEL[i-1]) * (REF_JOINT_VEL - JOINT_VEL[i-1])) + (float) VALVE_CENTER + (float) (10*ID_index_array[i-1]);
}
}
break;
}
}
if(REF_JOINT_VEL > max(JOINT_VEL[VALVE_POS_NUM-1], JOINT_VEL[VALVE_POS_NUM-2])) {
Ref_Valve_Pos_FF = (float) VALVE_MAX_POS;
} else if(REF_JOINT_VEL < min(JOINT_VEL[VALVE_POS_NUM-1], JOINT_VEL[VALVE_POS_NUM-2])) {
Ref_Valve_Pos_FF = (float) VALVE_MIN_POS;
}
Ref_Valve_Pos_FF = (float) VELOCITY_COMP_GAIN * 0.01f * (float) (Ref_Valve_Pos_FF - (float) VALVE_CENTER);
return Ref_Valve_Pos_FF;
}
void VALVE_POS_CONTROL(float REF_VALVE_POS)
{
int i = 0;
if(REF_VALVE_POS > VALVE_MAX_POS) {
REF_VALVE_POS = VALVE_MAX_POS;
} else if(REF_VALVE_POS < VALVE_MIN_POS) {
REF_VALVE_POS = VALVE_MIN_POS;
}
valve_pos_err = (float) (REF_VALVE_POS - value);
valve_pos_err_diff = valve_pos_err - valve_pos_err_old;
valve_pos_err_old = valve_pos_err;
valve_pos_err_sum += valve_pos_err;
if (valve_pos_err_sum > 1000.0f) valve_pos_err_sum = 1000.0f;
if (valve_pos_err_sum<-1000.0f) valve_pos_err_sum = -1000.0f;
VALVE_PWM_RAW_FB = P_GAIN_VALVE_POSITION * valve_pos_err + I_GAIN_VALVE_POSITION * valve_pos_err_sum + D_GAIN_VALVE_POSITION * valve_pos_err_diff;
for(i=0; i<24; i++) {
if(REF_VALVE_POS >= min(VALVE_POS_VS_PWM[i],VALVE_POS_VS_PWM[i+1]) && (float) REF_VALVE_POS <= max(VALVE_POS_VS_PWM[i],VALVE_POS_VS_PWM[i+1])) {
if(i==0) {
VALVE_PWM_RAW_FF = (float) 1000.0f / (float) (VALVE_POS_VS_PWM[i+1] - VALVE_POS_VS_PWM[i]) * ((float) REF_VALVE_POS - VALVE_POS_VS_PWM[i]);
} else {
VALVE_PWM_RAW_FF = (float) 1000.0f* (float) (ID_index_array[i+1] - ID_index_array[i-1])/(VALVE_POS_VS_PWM[i+1] - VALVE_POS_VS_PWM[i-1]) * ((float) REF_VALVE_POS - VALVE_POS_VS_PWM[i-1]) + 1000.0f * (float) ID_index_array[i-1];
}
break;
}
}
Vout.ref = VALVE_PWM_RAW_FF + VALVE_PWM_RAW_FB;
}
#define LT_MAX_IDX 57
float LT_PWM_duty[LT_MAX_IDX] = {-100.0f, -80.0f, -60.0f, -50.0f, -40.0f, -35.0f, -30.0f, -25.0f, -20.0f,
-19.0f, -18.0f, -17.0f, -16.0f, -15.0f, -14.0f, -13.0f, -12.0f, -11.0f, -10.0f,
-9.0f, -8.0f, -7.0f, -6.0f, -5.0f, -4.0f, -3.0f, -2.0f, -1.0f, 0.0f,
1.0f, 2.0f, 3.0f, 4.0f, 5.0f, 6.0f, 7.0f, 8.0f, 9.0f, 10.0f,
11.0f, 12.0f, 13.0f, 14.0f, 15.0f, 16.0f, 17.0f, 18.0f, 19.0f, 20.0f,
25.0f, 30.0f, 35.0f, 40.0f, 50.0f, 60.0f, 80.0f, 100.0f
}; // duty
float LT_Voltage_Output[LT_MAX_IDX] = {-230.0f, -215.0f, -192.5f, -185.0f, -177.5f, -170.0f, -164.0f, -160.0f, -150.0f,
-150.0f, -145.0f, -145.0f, -145.0f, -135.0f, -135.0f, -135.0f, -127.5f, -127.5f, -115.0f,
-115.0f, -115.0F, -100.0f, -100.0f, -100.0f, -60.0f, -60.0f, -10.0f, -5.0f, 0.0f,
7.5f, 14.0f, 14.0f, 14.0f, 42.5f, 42.5f, 42.5f, 80.0f, 80.0f, 105.0f,
105.0f, 105.0f, 120.0f, 120.0f, 120.0f, 131.0f, 131.0f, 140.0f, 140.0f, 140.0f,
155.0f, 160.0f, 170.0f, 174.0f, 182.0f, 191.0f, 212.0f, 230.0f
}; // mV
float PWM_duty_byLT(float Ref_V)
{
float PWM_duty = 0.0f;
if(Ref_V<LT_Voltage_Output[0]) {
PWM_duty = (Ref_V-LT_Voltage_Output[0])/1.5f+LT_PWM_duty[0];
} else if (Ref_V>=LT_Voltage_Output[LT_MAX_IDX-1]) {
PWM_duty = (Ref_V-LT_Voltage_Output[LT_MAX_IDX-1])/1.5f+LT_PWM_duty[LT_MAX_IDX-1];
} else {
int idx = 0;
for(idx=0; idx<LT_MAX_IDX-1; idx++) {
float ini_x = LT_Voltage_Output[idx];
float fin_x = LT_Voltage_Output[idx+1];
float ini_y = LT_PWM_duty[idx];
float fin_y = LT_PWM_duty[idx+1];
if(Ref_V>=ini_x && Ref_V<fin_x) {
PWM_duty = (fin_y-ini_y)/(fin_x-ini_x)*(Ref_V-ini_x) + ini_y;
break;
}
}
}
return PWM_duty;
}
/*******************************************************************************
TIMER INTERRUPT
*******************************************************************************/
float FREQ_TMR4 = (float)FREQ_20k;
float DT_TMR4 = (float)DT_20k;
long CNT_TMR4 = 0;
int TMR4_FREQ_10k = (int)FREQ_10k;
extern "C" void TIM4_IRQHandler(void)
{
if (TIM4->SR & TIM_SR_UIF ) {
/*******************************************************
*** Sensor Read & Data Handling
********************************************************/
//Encoder
if (CNT_TMR4 % (int) ((int) FREQ_TMR4/TMR4_FREQ_10k) == 0) {
ENC_UPDATE();
}
ADC1->CR2 |= 0x40000000;
if (SENSING_MODE == 0) {
// Torque Sensing (0~210)bar =============================================
float pres_A_new = (((float) ADC1->DR) - 2047.5f);
double alpha_update_ft = 1.0f / (1.0f + FREQ_TMR4 / (2.0f * 3.14f * 100.0f)); // f_cutoff : 200Hz
pres_A.sen = (1.0f - alpha_update_ft) * pres_A.sen + alpha_update_ft * pres_A_new;
torq.sen = -pres_A.sen / TORQUE_SENSOR_PULSE_PER_TORQUE;
// float alpha_update_pres_A = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*100.0f));
//// float pres_A_new = ((float)ADC1->DR - PRES_A_NULL) / PRES_SENSOR_A_PULSE_PER_BAR;
// float pres_A_new = ((float)ADC1->DR);
// pres_A.sen = pres_A.sen*(1.0f-alpha_update_pres_A)+pres_A_new*(alpha_update_pres_A);
// torq.sen = - (pres_A.sen-2048.0f); //pulse -2047~2047
} else if (SENSING_MODE == 1) {
// Pressure Sensing (0~210)bar =============================================
float pres_A_new = (((float)ADC1->DR) - PRES_A_NULL);
float pres_B_new = (((float)ADC2->DR) - PRES_B_NULL);
double alpha_update_pres = 1.0f / (1.0f + FREQ_TMR4 / (2.0f * 3.14f * 200.0f)); // f_cutoff : 500Hz
pres_A.sen = (1.0f - alpha_update_pres) * pres_A.sen + alpha_update_pres * pres_A_new;
pres_B.sen = (1.0f - alpha_update_pres) * pres_B.sen + alpha_update_pres * pres_B_new;
CUR_PRES_A_BAR = pres_A.sen / PRES_SENSOR_A_PULSE_PER_BAR;
CUR_PRES_B_BAR = pres_B.sen / PRES_SENSOR_B_PULSE_PER_BAR;
if ((OPERATING_MODE & 0x01) == 0) { // Rotary Actuator
torq.sen = (PISTON_AREA_A * CUR_PRES_A_BAR - PISTON_AREA_B * CUR_PRES_B_BAR) * 0.0001f; // mm^3*bar >> Nm
} else if ((OPERATING_MODE & 0x01) == 1) { // Linear Actuator
torq.sen = (PISTON_AREA_A * CUR_PRES_A_BAR - PISTON_AREA_B * CUR_PRES_B_BAR) * 0.1f; // mm^2*bar >> N
}
}
// //Pressure sensor A
// ADC1->CR2 |= 0x40000000; // adc _ 12bit
// //while((ADC1->SR & 0b10));
// float alpha_update_pres_A = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*100.0f));
// float pres_A_new = ((float)ADC1->DR);
// pres_A.sen = pres_A.sen*(1.0f-alpha_update_pres_A)+pres_A_new*(alpha_update_pres_A);
// torq.sen = - (pres_A.sen-2048.0f); //pulse -2047~2047 //SW just changed the sign to correct the direction of loadcell on LIGHT. Correct later.
//
//
// //Pressure sensor B
// float alpha_update_pres_B = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*100.0f));
// float pres_B_new = ((float)ADC2->DR);
// pres_B.sen = pres_B.sen*(1.0f-alpha_update_pres_B)+pres_B_new*(alpha_update_pres_B);
// //torq.sen = pres_A.sen * (float) PISTON_AREA_A - pres_B.sen * (float) PISTON_AREA_B;
//Current
//ADC3->CR2 |= 0x40000000; // adc _ 12bit
//int raw_cur = ADC3->DR;
//while((ADC3->SR & 0b10));
float alpha_update_cur = 1.0f/(1.0f + FREQ_TMR4/(2.0f*3.14f*500.0f)); // f_cutoff : 500Hz
float cur_new = ((float)ADC3->DR-2048.0f)*20.0f/4096.0f; // unit : mA
cur.sen=cur.sen*(1.0f-alpha_update_cur)+cur_new*(alpha_update_cur);
//cur.sen = raw_cur;
CNT_TMR4++;
}
TIM4->SR = 0x0; // reset the status register
}
int j =0;
float FREQ_TMR3 = (float)FREQ_5k;
float DT_TMR3 = (float)DT_5k;
int cnt_trans = 0;
double VALVE_POS_RAW_FORCE_FB_LOGGING = 0.0f;
int can_rest =0;
extern "C" void TIM3_IRQHandler(void)
{
if (TIM3->SR & TIM_SR_UIF ) {
if (((OPERATING_MODE&0b110)>>1) == 0) {
K_v = 0.4f; // Moog (LPM >> mA) , 100bar
mV_PER_mA = 500.0f; // 5000mV/10mA
mV_PER_pulse = 0.5f; // 5000mV/10000pulse
mA_PER_pulse = 0.001f; // 10mA/10000pulse
} else if (((OPERATING_MODE&0b110)>>1) == 1) {
K_v = 0.5f; // KNR (LPM >> mA) , 100bar
mV_PER_mA = 166.6666f; // 5000mV/30mA
mV_PER_pulse = 0.5f; // 5000mV/10000pulse
mA_PER_pulse = 0.003f; // 30mA/10000pulse
}
if(MODE_POS_FT_TRANS == 1) {
alpha_trans = (float)(1.0f - cos(3.141592f * (float)cnt_trans * DT_TMR3 /3.0f))/2.0f;
cnt_trans++;
torq.err_sum = 0;
if((float)cnt_trans * DT_TMR3 > 3.0f)
MODE_POS_FT_TRANS = 2;
} else if(MODE_POS_FT_TRANS == 3) {
alpha_trans = (float)(1.0f + cos(3.141592f * (float)cnt_trans * DT_TMR3 /3.0f))/2.0f;
cnt_trans++;
torq.err_sum = 0;
if((float) cnt_trans * DT_TMR3 > 3.0f )
MODE_POS_FT_TRANS = 0;
} else if(MODE_POS_FT_TRANS == 2) {
alpha_trans = 1.0f;
cnt_trans = 0;
} else {
alpha_trans = 0.0f;
cnt_trans = 0;
}
int UTILITY_MODE = 0;
int CONTROL_MODE = 0;
if (CONTROL_UTILITY_MODE >= 20 || CONTROL_UTILITY_MODE == 0) {
UTILITY_MODE = CONTROL_UTILITY_MODE;
CONTROL_MODE = MODE_NO_ACT;
} else {
CONTROL_MODE = CONTROL_UTILITY_MODE;
UTILITY_MODE = MODE_NO_ACT;
}
// UTILITY MODE ------------------------------------------------------------
switch (UTILITY_MODE) {
case MODE_NO_ACT: {
break;
}
case MODE_TORQUE_SENSOR_NULLING: {
// DAC Voltage reference set
if (TMR3_COUNT_TORQUE_NULL < TMR_FREQ_5k * 2) {
CUR_TORQUE_sum += torq.sen;
if (TMR3_COUNT_TORQUE_NULL % 10 == 0) {
CUR_TORQUE_mean = CUR_TORQUE_sum / 10.0f;
CUR_TORQUE_sum = 0;
TORQUE_VREF += 0.000003f * (0.0f - CUR_TORQUE_mean);
if (TORQUE_VREF > 3.3f) TORQUE_VREF = 3.3f;
if (TORQUE_VREF < 0.0f) TORQUE_VREF = 0.0f;
//spi_eeprom_write(RID_TORQUE_SENSOR_VREF, (int16_t) (TORQUE_VREF * 1000.0));
dac_1 = TORQUE_VREF / 3.3f;
}
} else {
CONTROL_UTILITY_MODE = MODE_NO_ACT;
TMR3_COUNT_TORQUE_NULL = 0;
CUR_TORQUE_sum = 0;
CUR_TORQUE_mean = 0;
// ROM_RESET_DATA();
spi_eeprom_write(RID_TORQUE_SENSOR_VREF, (int16_t) (TORQUE_VREF * 1000.0f));
dac_1 = TORQUE_VREF / 3.3f;
}
TMR3_COUNT_TORQUE_NULL++;
break;
}
// case MODE_VALVE_NULLING_AND_DEADZONE_SETTING: {
// if (TMR3_COUNT_DEADZONE == 0) {
// if (pos_plus_end == pos_minus_end) need_enc_init = true;
// else temp_time = 0;
// }
// if (need_enc_init) {
// if (TMR3_COUNT_DEADZONE < (int) (0.5f * (float) TMR_FREQ_5k)) {
// V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
// pos_plus_end = pos.sen;
// } else if (TMR3_COUNT_DEADZONE < TMR_FREQ_5k) {
// V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
// pos_minus_end = pos.sen;
// } else if (TMR3_COUNT_DEADZONE == TMR_FREQ_5k) need_enc_init = false;
// temp_time = TMR_FREQ_5k;
// }
//
// if (temp_time <= TMR3_COUNT_DEADZONE && TMR3_COUNT_DEADZONE < (temp_time + TMR_FREQ_5k)) {
// V_out = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen);
// VALVE_CENTER = VALVE_DEADZONE_PLUS = VALVE_DEADZONE_MINUS = 0;
//
// } else if (temp_time <= TMR3_COUNT_DEADZONE && TMR3_COUNT_DEADZONE < (temp_time + (int) (1.9f * (float) TMR_FREQ_5k))) {
// V_out = 0;
// CUR_VELOCITY_sum += CUR_VELOCITY;
// } else if (TMR3_COUNT_DEADZONE == (temp_time + 2 * TMR_FREQ_5k)) {
// if (CUR_VELOCITY_sum == 0) DZ_dir = 1;
// else if (CUR_VELOCITY_sum > 0) DZ_dir = 1;
// else if (CUR_VELOCITY_sum < 0) DZ_dir = -1;
// else DZ_temp_cnt2 = DZ_end;
// CUR_VELOCITY_sum = 0;
// } else if (TMR3_COUNT_DEADZONE > (temp_time + 2 * TMR_FREQ_5k)) {
// if (TMR3_COUNT_DEADZONE > (temp_time + 10 * TMR_FREQ_5k)) DZ_temp_cnt2 = DZ_end;
//
// // Position of Dead Zone
// // (CUR_VELOCITY < 0) (CUR_VELOCITY == 0) (CUR_VELOCITY > 0)
// // | / | / |/
// // | ______/ ___|___/ ______/|
// // |/ / | / |
// // /| / | / |
// // 0V 0V 0V
//
// if (DZ_temp_cnt2 < DZ_end) {
// if (TMR3_COUNT_DEADZONE % 20 != 0) {
// CUR_VELOCITY_sum += CUR_VELOCITY;
// } else {
// V_out -= DZ_dir;
// if (CUR_VELOCITY_sum * DZ_dir < 0) DZ_temp_cnt++;
// CUR_VELOCITY_sum = 0;
// }
// if (DZ_temp_cnt == 5) {
// if (DZ_dir >= 0) VALVE_DEADZONE_MINUS = (int16_t) V_out;
// else VALVE_DEADZONE_PLUS = (int16_t) V_out;
// DZ_dir = -DZ_dir;
// DZ_temp_cnt = 0;
// DZ_temp_cnt2++;
// }
// } else {
// TMR3_COUNT_DEADZONE = -1;
// VALVE_CENTER = VALVE_DEADZONE_PLUS / 2 + VALVE_DEADZONE_MINUS / 2;
// if (VALVE_DEADZONE_PLUS < VALVE_DEADZONE_MINUS) {
// VALVE_DEADZONE_PLUS = VALVE_CENTER;
// VALVE_DEADZONE_MINUS = VALVE_CENTER;
// }
// V_out = 0;
//
// ROM_RESET_DATA();
//
// //spi_eeprom_write(RID_VALVE_DEADZONE_PLUS, VALVE_DEADZONE_PLUS);
// //spi_eeprom_write(RID_VALVE_DEADZONE_MINUS, VALVE_DEADZONE_MINUS);
//
// CONTROL_MODE = MODE_NO_ACT;
// DZ_temp_cnt2 = 0;
// }
// }
// TMR3_COUNT_DEADZONE++;
// break;
// }
case MODE_FIND_HOME: {
if (FINDHOME_STAGE == FINDHOME_INIT) {
cnt_findhome = 0;
cnt_vel_findhome = 0;
//REFERENCE_MODE = MODE_REF_NO_ACT; // Stop taking reference data from PODO
pos.ref = pos.sen;
vel.ref = 0.0f;
FINDHOME_STAGE = FINDHOME_GOTOLIMIT;
} else if (FINDHOME_STAGE == FINDHOME_GOTOLIMIT) {
int cnt_check_enc = (TMR_FREQ_5k/20);
if(cnt_findhome%cnt_check_enc == 0) {
FINDHOME_POSITION = pos.sen;
FINDHOME_VELOCITY = FINDHOME_POSITION - FINDHOME_POSITION_OLD;
FINDHOME_POSITION_OLD = FINDHOME_POSITION;
}
cnt_findhome++;
if (abs(FINDHOME_VELOCITY) <= 1) {
cnt_vel_findhome = cnt_vel_findhome + 1;
} else {
cnt_vel_findhome = 0;
}
if ((cnt_vel_findhome < 3*TMR_FREQ_5k) && cnt_findhome < 10*TMR_FREQ_5k) { // wait for 3sec
//REFERENCE_MODE = MODE_REF_NO_ACT;
if (HOMEPOS_OFFSET > 0) pos.ref = pos.ref + 12.0f;
else pos.ref = pos.ref - 12.0f;
// pos.err = pos.ref_home_pos - pos.sen;
// float VALVE_POS_RAW_POS_FB = 0.0f;
// VALVE_POS_RAW_POS_FB = (float) P_GAIN_JOINT_POSITION * pos.err/(float) ENC_PULSE_PER_POSITION * 0.01f;
// valve_pos.ref = VALVE_POS_RAW_POS_FB + (float) VALVE_CENTER;
// VALVE_POS_CONTROL(valve_pos.ref);
CONTROL_MODE = MODE_JOINT_CONTROL;
alpha_trans = 0.0f;
} else {
ENC_SET(HOMEPOS_OFFSET);
// ENC_SET_ZERO();
INIT_REF_POS = HOMEPOS_OFFSET;
REF_POSITION = 0;
REF_VELOCITY = 0;
FINDHOME_POSITION = 0;
FINDHOME_POSITION_OLD = 0;
FINDHOME_VELOCITY = 0;
cnt_findhome = 0;
cnt_vel_findhome = 0;
FINDHOME_STAGE = FINDHOME_ZEROPOSE;
cnt_findhome = 0;
pos.ref = 0.0f;
vel.ref = 0.0f;
pos.ref_home_pos = 0.0f;
vel.ref_home_pos = 0.0f;
//FINDHOME_STAGE = FINDHOME_INIT;
//CONTROL_UTILITY_MODE = MODE_JOINT_CONTROL;
}
} else if (FINDHOME_STAGE == FINDHOME_ZEROPOSE) {
int T_move = 2*TMR_FREQ_5k;
pos.ref = (0.0f - (float)INIT_REF_POS)*0.5f*(1.0f - cos(3.14159f * (float)cnt_findhome / (float)T_move)) + (float)INIT_REF_POS;
//pos.ref = 0.0f;
vel.ref = 0.0f;
// input for position control
// CONTROL_MODE = MODE_JOINT_CONTROL;
alpha_trans = 0.0f;
double torq_ref = 0.0f;
pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
vel.err = (0.0f - vel.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm/s]
pos.err_sum += pos.err/(float) TMR_FREQ_5k; //[mm]
if (((OPERATING_MODE&0b110)>>1) == 0 || ((OPERATING_MODE&0b110)>>1) == 1) {
double I_REF_POS = 0.0f;
double I_REF_FORCE_FB = 0.0f; // I_REF by Force Feedback
double I_REF_VC = 0.0f; // I_REF for velocity compensation
double temp_vel_pos = 0.0f;
double temp_vel_torq = 0.0f;
double wn_Pos = 2.0f * PI * 5.0f; // f_cut : 5Hz Position Control
if ((OPERATING_MODE & 0x01) == 0) { // Rotary Mode
temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION) * 3.14159f / 180.0f; // rad/s
// L when P-gain = 100, f_cut = 10Hz L feedforward velocity
} else if ((OPERATING_MODE & 0x01) == 1) {
temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION); // mm/s
// L when P-gain = 100, f_cut = 10Hz L feedforward velocity
}
if (temp_vel_pos > 0.0f) I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_A * 0.00006f / (K_v * sqrt(2.0f * alpha3 / (alpha3 + 1.0f))));
else I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_B * 0.00006f / (K_v * sqrt(2.0f / (alpha3 + 1.0f))));
I_REF = I_REF_POS;
} else {
float VALVE_POS_RAW_FORCE_FB = 0.0f;
VALVE_POS_RAW_FORCE_FB = DDV_JOINT_POS_FF(vel.sen) + (P_GAIN_JOINT_POSITION * 0.01f * pos.err + DDV_JOINT_POS_FF(vel.ref));
if (VALVE_POS_RAW_FORCE_FB >= 0) {
valve_pos.ref = VALVE_POS_RAW_FORCE_FB + VALVE_DEADZONE_PLUS;
} else {
valve_pos.ref = VALVE_POS_RAW_FORCE_FB + VALVE_DEADZONE_MINUS;
}
VALVE_POS_CONTROL(valve_pos.ref);
V_out = (float) Vout.ref;
}
// pos.err = pos.ref - (float)pos.sen;
// float VALVE_POS_RAW_POS_FB = 0.0f;
// VALVE_POS_RAW_POS_FB = (float) P_GAIN_JOINT_POSITION * 0.01f * pos.err/(float) ENC_PULSE_PER_POSITION;
// valve_pos.ref = VALVE_POS_RAW_POS_FB + (float) VALVE_CENTER;
// VALVE_POS_CONTROL(valve_pos.ref);
cnt_findhome++;
if (cnt_findhome >= T_move) {
//REFERENCE_MODE = MODE_REF_DIRECT;
cnt_findhome = 0;
pos.ref = 0.0f;
vel.ref = 0.0f;
pos.ref_home_pos = 0.0f;
vel.ref_home_pos = 0.0f;
FINDHOME_STAGE = FINDHOME_INIT;
CONTROL_UTILITY_MODE = MODE_JOINT_CONTROL;
}
}
break;
}
// case MODE_VALVE_GAIN_SETTING: {
// if (TMR3_COUNT_FLOWRATE == 0) {
// if (pos_plus_end == pos_minus_end) need_enc_init = true;
// else {
// V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
// temp_time = (int) (0.5f * (float) TMR_FREQ_5k);
// }
// }
// if (need_enc_init) {
// if (TMR3_COUNT_FLOWRATE < (int) (0.5f * (float) TMR_FREQ_5k)) {
// V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
// pos_plus_end = pos.sen;
// } else if (TMR3_COUNT_FLOWRATE < TMR_FREQ_5k) {
// V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
// pos_minus_end = pos.sen;
// } else if (TMR3_COUNT_FLOWRATE == TMR_FREQ_5k) {
// need_enc_init = false;
// check_vel_pos_init = (int) (0.9f * (float) (pos_plus_end - pos_minus_end));
// check_vel_pos_fin = (int) (0.95f * (float) (pos_plus_end - pos_minus_end));
// check_vel_pos_interv = check_vel_pos_fin - check_vel_pos_init;
// }
// temp_time = TMR_FREQ_5k;
// }
// TMR3_COUNT_FLOWRATE++;
// if (TMR3_COUNT_FLOWRATE > temp_time) {
// if (flag_flowrate % 2 == 0) { // (+)
// VALVE_VOLTAGE = 1000.0f * (float) (flag_flowrate / 2 + 1);
// V_out = VALVE_VOLTAGE;
// if (pos.sen > (pos_minus_end + check_vel_pos_init) && pos.sen < (pos_minus_end + check_vel_pos_fin)) {
// fl_temp_cnt++;
// } else if (pos.sen >= (pos_minus_end + check_vel_pos_fin) && CUR_VELOCITY == 0) {
// VALVE_GAIN_LPM_PER_V[flag_flowrate] = 0.95873f * 0.5757f * (float) TMR_FREQ_5k / 10000.0 * (float) check_vel_pos_interv / (float) fl_temp_cnt / VALVE_VOLTAGE; // 0.9587=6*pi/65536*10000 0.5757=0.02525*0.02*0.0095*2*60*1000
// // VALVE_GAIN_LPM_PER_V[flag_flowrate] = (float) TMR_FREQ_10k * (float) check_vel_pos_interv / (float) fl_temp_cnt / VALVE_VOLTAGE; // PULSE/sec
// fl_temp_cnt2++;
// }
// } else if (flag_flowrate % 2 == 1) { // (-)
// VALVE_VOLTAGE = -1. * (float) (flag_flowrate / 2 + 1);
// V_out = VALVE_VOLTAGE;
// if (pos.sen < (pos_plus_end - check_vel_pos_init) && pos.sen > (pos_plus_end - check_vel_pos_fin)) {
// fl_temp_cnt++;
// } else if (pos.sen <= (pos_plus_end - check_vel_pos_fin) && CUR_VELOCITY == 0) {
// VALVE_GAIN_LPM_PER_V[flag_flowrate] = 0.95873f * 0.5757f * (float) TMR_FREQ_5k / 10000.0f * (float) check_vel_pos_interv / (float) fl_temp_cnt / (-VALVE_VOLTAGE);
// // VALVE_GAIN_LPM_PER_V[flag_flowrate] = (float) TMR_FREQ_10k * (float) check_vel_pos_interv / (float) fl_temp_cnt / (-VALVE_VOLTAGE); // PULSE/sec
// fl_temp_cnt2++;
// }
// }
// if (fl_temp_cnt2 == 100) {
//
// ROM_RESET_DATA();
//
// //spi_eeprom_write(RID_VALVE_GAIN_PLUS_1 + flag_flowrate, (int16_t) (VALVE_GAIN_LPM_PER_V[flag_flowrate] * 100.0f));
// cur_vel_sum = 0;
// fl_temp_cnt = 0;
// fl_temp_cnt2 = 0;
// flag_flowrate++;
// }
// if (flag_flowrate == 10) {
// V_out = 0;
// flag_flowrate = 0;
// TMR3_COUNT_FLOWRATE = 0;
// valve_gain_repeat_cnt++;
// if (valve_gain_repeat_cnt >= 1) {
// CONTROL_MODE = MODE_NO_ACT;
// valve_gain_repeat_cnt = 0;
// }
//
// }
// break;
// }
//
// }
case MODE_PRESSURE_SENSOR_NULLING: {
// DAC Voltage reference set
if (TMR3_COUNT_PRES_NULL < TMR_FREQ_5k * 2) {
CUR_PRES_A_sum += pres_A.sen;
CUR_PRES_B_sum += pres_B.sen;
if (TMR3_COUNT_PRES_NULL % 10 == 0) {
CUR_PRES_A_mean = CUR_PRES_A_sum / 10.0f;
CUR_PRES_B_mean = CUR_PRES_B_sum / 10.0f;
CUR_PRES_A_sum = 0;
CUR_PRES_B_sum = 0;
float VREF_NullingGain = 0.0003f;
PRES_A_VREF = PRES_A_VREF + VREF_NullingGain * CUR_PRES_A_mean;
PRES_B_VREF = PRES_B_VREF + VREF_NullingGain * CUR_PRES_B_mean;
if (PRES_A_VREF > 3.3f) PRES_A_VREF = 3.3f;
if (PRES_A_VREF < 0.0f) PRES_A_VREF = 0.0f;
if (PRES_B_VREF > 3.3f) PRES_B_VREF = 3.3f;
if (PRES_B_VREF < 0.0f) PRES_B_VREF = 0.0f;
dac_1 = PRES_A_VREF / 3.3f;
dac_2 = PRES_B_VREF / 3.3f;
}
} else {
CONTROL_UTILITY_MODE = MODE_NO_ACT;
TMR3_COUNT_PRES_NULL = 0;
CUR_PRES_A_sum = 0;
CUR_PRES_B_sum = 0;
CUR_PRES_A_mean = 0;
CUR_PRES_B_mean = 0;
// ROM_RESET_DATA();
spi_eeprom_write(RID_PRES_A_SENSOR_VREF, (int16_t) (PRES_A_VREF * 1000.0f));
spi_eeprom_write(RID_PRES_B_SENSOR_VREF, (int16_t) (PRES_B_VREF * 1000.0f));
dac_1 = PRES_A_VREF / 3.3f;
dac_2 = PRES_B_VREF / 3.3f;
//pc.printf("nulling end");
}
TMR3_COUNT_PRES_NULL++;
break;
}
// case MODE_PRESSURE_SENSOR_CALIB: {
// if (TMR3_COUNT_PRES_CALIB < 2 * TMR_FREQ_5k) {
// V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
// if (TMR3_COUNT_PRES_CALIB >= TMR_FREQ_5k) {
// CUR_PRES_A_sum += CUR_PRES_A;
// }
// } else if (TMR3_COUNT_PRES_CALIB < 4 * TMR_FREQ_5k) {
// V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
// if (TMR3_COUNT_PRES_CALIB >= 3 * TMR_FREQ_5k) {
// CUR_PRES_B_sum += CUR_PRES_B;
// }
// } else {
// CONTROL_MODE = MODE_NO_ACT;
// TMR3_COUNT_PRES_CALIB = 0;
// V_out = 0;
// PRES_SENSOR_A_PULSE_PER_BAR = CUR_PRES_A_sum / ((float) TMR_FREQ_5k - 1.0f) - PRES_A_NULL;
// PRES_SENSOR_A_PULSE_PER_BAR = PRES_SENSOR_A_PULSE_PER_BAR / ((float) PRES_SUPPLY - 1.0f);
// PRES_SENSOR_B_PULSE_PER_BAR = CUR_PRES_B_sum / ((float) TMR_FREQ_5k - 1.0f) - PRES_B_NULL;
// PRES_SENSOR_B_PULSE_PER_BAR = PRES_SENSOR_B_PULSE_PER_BAR / ((float) PRES_SUPPLY - 1.0f);
// CUR_PRES_A_sum = 0;
// CUR_PRES_B_sum = 0;
// CUR_PRES_A_mean = 0;
// CUR_PRES_B_mean = 0;
//
// ROM_RESET_DATA();
//
// //spi_eeprom_write(RID_PRES_SENSOR_A_PULSE_PER_BAR, (int16_t) (PRES_SENSOR_A_PULSE_PER_BAR * 100.0f));
// //spi_eeprom_write(RID_PRES_SENSOR_B_PULSE_PER_BAR, (int16_t) (PRES_SENSOR_B_PULSE_PER_BAR * 100.0f));
// }
// TMR3_COUNT_PRES_CALIB++;
// break;
// }
// case MODE_ROTARY_FRICTION_TUNING: {
// if (TMR3_COUNT_ROTARY_FRIC_TUNE % (5 * TMR_FREQ_5k) == 0) freq_fric_tune = 4.0f + 3.0f * sin(2 * 3.14159f * 0.5f * TMR3_COUNT_ROTARY_FRIC_TUNE * 0.0001f * 0.05f);
// V_out = PWM_out * sin(2 * 3.14159f * freq_fric_tune * TMR3_COUNT_ROTARY_FRIC_TUNE * 0.0001f);
// if (V_out > 0) V_out = VALVE_VOLTAGE_LIMIT * 1000.0f;
// else V_out = -VALVE_VOLTAGE_LIMIT * 1000.0f;
// TMR3_COUNT_ROTARY_FRIC_TUNE++;
// if (TMR3_COUNT_ROTARY_FRIC_TUNE > TUNING_TIME * TMR_FREQ_5k) {
// TMR3_COUNT_ROTARY_FRIC_TUNE = 0;
// V_out = 0.0f;
// CONTROL_MODE = MODE_NO_ACT;
// }
// break;
// }
case MODE_DDV_POS_VS_PWM_ID: {
CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
VALVE_ID_timer = VALVE_ID_timer + 1;
if(VALVE_ID_timer < TMR_FREQ_5k*1) {
Vout.ref = 3000.0f * sin(2.0f*3.14f*VALVE_ID_timer/TMR_FREQ_5k * 100.0f);
} else if(VALVE_ID_timer < TMR_FREQ_5k*2) {
Vout.ref = 1000.0f*(ID_index_array[ID_index]);
} else if(VALVE_ID_timer == TMR_FREQ_5k*2) {
VALVE_POS_TMP = 0;
data_num = 0;
} else if(VALVE_ID_timer < TMR_FREQ_5k*3) {
data_num = data_num + 1;
VALVE_POS_TMP = VALVE_POS_TMP + value;
} else if(VALVE_ID_timer == TMR_FREQ_5k*3) {
Vout.ref = 0.0f;
} else {
VALVE_POS_AVG[ID_index] = VALVE_POS_TMP / data_num;
VALVE_ID_timer = 0;
ID_index= ID_index +1;
}
if(ID_index>=25) {
int i;
VALVE_POS_AVG_OLD = VALVE_POS_AVG[0];
for(i=0; i<25; i++) {
VALVE_POS_VS_PWM[i] = (int16_t) (VALVE_POS_AVG[i]);
if(VALVE_POS_AVG[i] > VALVE_POS_AVG_OLD) {
VALVE_MAX_POS = VALVE_POS_AVG[i];
VALVE_POS_AVG_OLD = VALVE_MAX_POS;
} else if(VALVE_POS_AVG[i] < VALVE_POS_AVG_OLD) {
VALVE_MIN_POS = VALVE_POS_AVG[i];
VALVE_POS_AVG_OLD = VALVE_MIN_POS;
}
}
// ROM_RESET_DATA();
spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
for(int i=0; i<25; i++) {
spi_eeprom_write(RID_VALVE_POS_VS_PWM_0 + i, (int16_t) VALVE_POS_VS_PWM[i]);
}
ID_index = 0;
CONTROL_UTILITY_MODE = MODE_NO_ACT;
}
break;
}
case MODE_DDV_DEADZONE_AND_CENTER: {
CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
VALVE_DZ_timer = VALVE_DZ_timer + 1;
if(first_check == 0) {
if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
} else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
pos_plus_end = pos.sen;
} else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
} else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
pos_minus_end = pos.sen;
} else if(VALVE_DZ_timer < (int) (3.0f * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
} else if(VALVE_DZ_timer < (int) (4.0f * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
data_num = data_num + 1;
VALVE_POS_TMP = VALVE_POS_TMP + value;
} else if(VALVE_DZ_timer == (int) (4.0f * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
DDV_POS_AVG = VALVE_POS_TMP / data_num;
START_POS = pos.sen;
VALVE_POS_TMP = 0;
data_num = 0;
} else if(VALVE_DZ_timer < (int) (5.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = DDV_POS_AVG;
VALVE_POS_CONTROL(valve_pos.ref);
} else if(VALVE_DZ_timer < (int) (6.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = DDV_POS_AVG;
VALVE_POS_CONTROL(valve_pos.ref);
} else if(VALVE_DZ_timer == (int) (6.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = DDV_POS_AVG;
VALVE_POS_CONTROL(valve_pos.ref);
FINAL_POS = pos.sen;
if((FINAL_POS - START_POS)>200) {
DZ_case = 1;
} else if((FINAL_POS - START_POS)<-200) {
DZ_case = -1;
} else {
DZ_case = 0;
}
CAN_TX_PRES((int16_t) (DZ_case), (int16_t) (6));
first_check = 1;
DZ_DIRECTION = 1;
VALVE_DZ_timer = 0;
Ref_Valve_Pos_Old = DDV_POS_AVG;
DZ_NUM = 1;
DZ_index = 1;
}
} else {
if((DZ_case == -1 && DZ_NUM == 1) | (DZ_case == 1 && DZ_NUM == 1)) {
if(VALVE_DZ_timer < (int) (1.0 * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
//pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
//CONTROL_MODE = MODE_JOINT_CONTROL;
} else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
START_POS = pos.sen;
} else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = Ref_Valve_Pos_Old - DZ_case * DZ_DIRECTION * 64 / DZ_index;
if(valve_pos.ref <= VALVE_MIN_POS) {
valve_pos.ref = VALVE_MIN_POS;
} else if(valve_pos.ref >= VALVE_MAX_POS) {
valve_pos.ref = VALVE_MAX_POS;
}
VALVE_POS_CONTROL(valve_pos.ref);
} else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
Ref_Valve_Pos_Old = valve_pos.ref;
FINAL_POS = pos.sen;
if((FINAL_POS - START_POS)>100) {
DZ_DIRECTION = 1 * DZ_case;
} else if((FINAL_POS - START_POS)<-100) {
DZ_DIRECTION = -1 * DZ_case;
} else {
DZ_DIRECTION = 1 * DZ_case;
}
VALVE_DZ_timer = 0;
DZ_index= DZ_index *2;
if(DZ_index >= 128) {
FIRST_DZ = valve_pos.ref;
DZ_NUM = 2;
Ref_Valve_Pos_Old = FIRST_DZ;
DZ_index = 1;
DZ_DIRECTION = 1;
}
}
} else if((DZ_case == -1 && DZ_NUM == 2) | (DZ_case == 1 && DZ_NUM == 2)) {
if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
//pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
//CONTROL_MODE = MODE_JOINT_CONTROL;
} else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
START_POS = pos.sen;
} else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = Ref_Valve_Pos_Old - DZ_case * DZ_DIRECTION * 64 / DZ_index;
if(valve_pos.ref <= VALVE_MIN_POS) {
valve_pos.ref = VALVE_MIN_POS;
} else if(valve_pos.ref >= VALVE_MAX_POS) {
valve_pos.ref = VALVE_MAX_POS;
}
VALVE_POS_CONTROL(valve_pos.ref);
} else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
Vout.ref = 0.0f;
} else if(VALVE_DZ_timer > (int) (2.0f * (float) TMR_FREQ_5k)) {
Ref_Valve_Pos_Old = valve_pos.ref;
FINAL_POS = pos.sen;
if((FINAL_POS - START_POS)>100) {
DZ_DIRECTION = 1 * DZ_case;
} else if((FINAL_POS - START_POS)<-100) {
DZ_DIRECTION = -1 * DZ_case;
} else {
DZ_DIRECTION = -1 * DZ_case;
}
VALVE_DZ_timer = 0;
DZ_index= DZ_index * 2;
if(DZ_index >= 128) {
SECOND_DZ = valve_pos.ref;
VALVE_CENTER = (int) (0.5f * (float) (FIRST_DZ) + 0.5f * (float) (SECOND_DZ));
first_check = 0;
VALVE_DEADZONE_MINUS = (float) FIRST_DZ;
VALVE_DEADZONE_PLUS = (float) SECOND_DZ;
// ROM_RESET_DATA();
spi_eeprom_write(RID_VALVE_CNETER, (int16_t) VALVE_CENTER);
spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
CONTROL_UTILITY_MODE = MODE_NO_ACT;
DZ_index = 1;
}
}
} else if(DZ_case == 0 && DZ_NUM ==1) {
if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
//pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
//CONTROL_MODE = MODE_JOINT_CONTROL;
} else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
START_POS = pos.sen;
} else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = Ref_Valve_Pos_Old - DZ_DIRECTION * 64 / DZ_index;
if(valve_pos.ref <= VALVE_MIN_POS) {
valve_pos.ref = VALVE_MIN_POS;
} else if(valve_pos.ref >= VALVE_MAX_POS) {
valve_pos.ref = VALVE_MAX_POS;
}
VALVE_POS_CONTROL(valve_pos.ref);
} else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
Ref_Valve_Pos_Old = valve_pos.ref;
FINAL_POS = pos.sen;
if((FINAL_POS - START_POS)>100) {
DZ_DIRECTION = 1;
} else if((FINAL_POS - START_POS)<-100) {
DZ_DIRECTION = -1;
} else {
DZ_DIRECTION = 1;
}
VALVE_DZ_timer = 0;
DZ_index= DZ_index *2;
if(DZ_index >= 128) {
FIRST_DZ = valve_pos.ref;
DZ_NUM = 2;
Ref_Valve_Pos_Old = FIRST_DZ;
DZ_index = 1;
DZ_DIRECTION = 1;
}
}
} else {
if(VALVE_DZ_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
//pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
//CONTROL_MODE = MODE_JOINT_CONTROL;
} else if(VALVE_DZ_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
START_POS = pos.sen;
} else if(VALVE_DZ_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = Ref_Valve_Pos_Old + DZ_DIRECTION * 64 / DZ_index;
if(valve_pos.ref <= VALVE_MIN_POS) {
valve_pos.ref = VALVE_MIN_POS;
} else if(valve_pos.ref > VALVE_MAX_POS) {
valve_pos.ref = VALVE_MAX_POS - 1;
}
VALVE_POS_CONTROL(valve_pos.ref);
} else if(VALVE_DZ_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
Vout.ref = 0.0f;
} else if(VALVE_DZ_timer > (int) (2.0f * (float) TMR_FREQ_5k)) {
Ref_Valve_Pos_Old = valve_pos.ref;
FINAL_POS = pos.sen;
if((FINAL_POS - START_POS)>100) {
DZ_DIRECTION = 1;
} else if((FINAL_POS - START_POS)<-100) {
DZ_DIRECTION = -1;
} else {
DZ_DIRECTION = 1;
}
VALVE_DZ_timer = 0;
DZ_index= DZ_index *2;
if(DZ_index >= 128) {
SECOND_DZ = valve_pos.ref;
VALVE_CENTER = (int) (0.5f * (float) (FIRST_DZ) + 0.5f * (float) (SECOND_DZ));
first_check = 0;
VALVE_DEADZONE_MINUS = (float) FIRST_DZ;
VALVE_DEADZONE_PLUS = (float) SECOND_DZ;
// ROM_RESET_DATA();
spi_eeprom_write(RID_VALVE_CNETER, (int16_t) VALVE_CENTER);
spi_eeprom_write(RID_VALVE_MAX_POS, (int16_t) VALVE_MAX_POS);
spi_eeprom_write(RID_VALVE_MIN_POS, (int16_t) VALVE_MIN_POS);
CONTROL_UTILITY_MODE = MODE_NO_ACT;
DZ_index = 1;
}
}
}
}
break;
}
case MODE_DDV_POS_VS_FLOWRATE: {
CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
VALVE_FR_timer = VALVE_FR_timer + 1;
if(first_check == 0) {
if(VALVE_FR_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
//CAN_TX_PRES((int16_t) (VALVE_FR_timer), (int16_t) (6));
} else if(VALVE_FR_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
Vout.ref = VALVE_VOLTAGE_LIMIT * 1000.0f;
pos_plus_end = pos.sen;
// CAN_TX_PRES((int16_t) (V_out), (int16_t) (7));
} else if(VALVE_FR_timer < (int) (2.0f * (float) TMR_FREQ_5k)) {
Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
} else if(VALVE_FR_timer == (int) (2.0f * (float) TMR_FREQ_5k)) {
// CAN_TX_PRES((int16_t) (V_out), (int16_t) (8));
Vout.ref = -VALVE_VOLTAGE_LIMIT * 1000.0f;
pos_minus_end = pos.sen;
first_check = 1;
VALVE_FR_timer = 0;
valve_pos.ref = (float) VALVE_CENTER;
ID_index = 0;
max_check = 0;
min_check = 0;
}
} else {
if(VALVE_FR_timer < (int) (1.0f * (float) TMR_FREQ_5k)) {
//V_out = (float) P_GAIN_JOINT_POSITION * (0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen)/(float) ENC_PULSE_PER_POSITION;
pos.ref = 0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end;
CONTROL_MODE = MODE_JOINT_CONTROL;
} else if(VALVE_FR_timer == (int) (1.0f * (float) TMR_FREQ_5k)) {
data_num = 0;
valve_pos.ref = 10.0f*((float) ID_index_array[ID_index]) + (float) VALVE_CENTER;
VALVE_POS_CONTROL(valve_pos.ref);
START_POS = pos.sen;
} else if(VALVE_FR_timer < (int) (5.0f * (float) TMR_FREQ_5k)) {
valve_pos.ref = 10.0f*((float) ID_index_array[ID_index]) + (float) VALVE_CENTER;
VALVE_POS_CONTROL(valve_pos.ref);
data_num = data_num + 1;
if(abs(0.5f * (float) pos_plus_end + 0.5f * (float) pos_minus_end - (float) pos.sen) > 20000.0f) {
FINAL_POS = pos.sen;
one_period_end = 1;
}
} else if(VALVE_FR_timer == (int) (5.0f * (float) TMR_FREQ_5k)) {
FINAL_POS = pos.sen;
one_period_end = 1;
V_out = 0.0f;
}
if(one_period_end == 1) {
if(valve_pos.ref > VALVE_MAX_POS) {
max_check = 1;
} else if(valve_pos.ref < VALVE_MIN_POS) {
min_check = 1;
}
JOINT_VEL[ID_index] = (FINAL_POS - START_POS) / data_num * TMR_FREQ_5k; // pulse/sec
VALVE_FR_timer = 0;
one_period_end = 0;
ID_index= ID_index +1;
V_out = 0.0f;
}
if(max_check == 1 && min_check == 1) {
VALVE_POS_NUM = ID_index;
// ROM_RESET_DATA();
for(int i=0; i<100; i++) {
spi_eeprom_write(RID_VALVE_POS_VS_FLOWRATE_0 + i, (int16_t) (JOINT_VEL[i] & 0xFFFF));
spi_eeprom_write(RID_VALVE_POS_VS_FLOWRATE_0_1 + i, (int16_t) ((JOINT_VEL[i] >> 16) & 0xFFFF));
}
ID_index = 0;
first_check = 0;
VALVE_FR_timer = 0;
CONTROL_UTILITY_MODE = MODE_NO_ACT;
// CAN_TX_PRES((int16_t) (VALVE_FR_timer), (int16_t) (6));
}
}
break;
}
case MODE_SYSTEM_ID: {
freq_sysid_Iref = (double) cnt_sysid * DT_TMR3 * 3.0f;
valve_pos.ref = 2500.0f * sin(2.0f * 3.14159f * freq_sysid_Iref * (double) cnt_sysid * DT_TMR3);
CONTROL_MODE = MODE_VALVE_OPEN_LOOP;
cnt_sysid++;
if (freq_sysid_Iref >= 300) {
cnt_sysid = 0;
CONTROL_UTILITY_MODE = MODE_NO_ACT;
}
break;
}
case MODE_FREQ_TEST: {
float valve_pos_ref = 2500.0f * sin(2.0f * 3.141592f * freq_test_valve_ref * (float) cnt_freq_test * DT_TMR3);
if(valve_pos_ref >= 0) {
valve_pos.ref = (double)VALVE_CENTER + (double)valve_pos_ref * ((double)VALVE_MAX_POS-(double)VALVE_CENTER)/10000.0f;
} else {
valve_pos.ref = (double)VALVE_CENTER - (double)valve_pos_ref * ((double)VALVE_MIN_POS-(double)VALVE_CENTER)/10000.0f;
}
ref_array[cnt_freq_test] = valve_pos_ref;
if(value>=(float) VALVE_CENTER) {
pos_array[cnt_freq_test] = 10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
} else {
pos_array[cnt_freq_test] = -10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
}
CONTROL_MODE = MODE_VALVE_POSITION_CONTROL;
cnt_freq_test++;
if (freq_test_valve_ref * (float) cnt_freq_test * DT_TMR3 > 2) {
buffer_data_size = cnt_freq_test;
cnt_freq_test = 0;
cnt_send_buffer = 0;
freq_test_valve_ref = freq_test_valve_ref * 1.05f;
if (freq_test_valve_ref >= 400) {
CONTROL_UTILITY_MODE = MODE_NO_ACT;
CONTROL_MODE = MODE_NO_ACT;
CAN_TX_PWM((int16_t) (1)); //1300
}
CONTROL_MODE = MODE_NO_ACT;
CONTROL_UTILITY_MODE = MODE_SEND_OVER;
}
break;
}
case MODE_SEND_BUFFER: {
// if (TMR2_COUNT_CAN_TX % (int) ((int) TMR_FREQ_5k/CAN_FREQ) == 0) {
// CAN_TX_PRES((int16_t) (pos_array[cnt_send_buffer]), (int16_t) (ref_array[cnt_send_buffer])); // 1400
// if(cnt_send_buffer>=buffer_data_size) {
// CONTROL_UTILITY_MODE = MODE_FREQ_TEST;
// }
// cnt_send_buffer++;
// }
break;
}
case MODE_SEND_OVER: {
CAN_TX_TORQUE((int16_t) (buffer_data_size)); //1300
CONTROL_UTILITY_MODE = MODE_NO_ACT;
CONTROL_MODE = MODE_NO_ACT;
break;
}
case MODE_STEP_TEST: {
float valve_pos_ref = 0.0f;
if (cnt_step_test < (int) (1.0f * (float) TMR_FREQ_5k)) {
valve_pos_ref = 0.0f;
} else {
valve_pos_ref = 10000.0f;
}
if(valve_pos_ref >= 0) {
valve_pos.ref = (double)VALVE_CENTER + (double)valve_pos_ref * ((double)VALVE_MAX_POS-(double)VALVE_CENTER)/10000.0f;
} else {
valve_pos.ref = (double)VALVE_CENTER - (double)valve_pos_ref * ((double)VALVE_MIN_POS-(double)VALVE_CENTER)/10000.0f;
}
ref_array[cnt_step_test] = valve_pos_ref;
if(value>=(float) VALVE_CENTER) {
pos_array[cnt_step_test] = 10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
} else {
pos_array[cnt_step_test] = -10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
}
CONTROL_MODE = MODE_VALVE_POSITION_CONTROL;
cnt_step_test++;
if (cnt_step_test > (int) (2.0f * (float) TMR_FREQ_5k)) {
buffer_data_size = cnt_step_test;
cnt_step_test = 0;
cnt_send_buffer = 0;
CONTROL_UTILITY_MODE = MODE_SEND_OVER;
CONTROL_MODE = MODE_NO_ACT;
}
// if (cnt_step_test > (int) (2.0f * (float) TMR_FREQ_5k))
// {
// CONTROL_UTILITY_MODE = MODE_NO_ACT;
// CONTROL_MODE = MODE_NO_ACT;
// CAN_TX_PWM((int16_t) (1)); //1300
// }
break;
}
default:
break;
}
// CONTROL MODE ------------------------------------------------------------
switch (CONTROL_MODE) {
case MODE_NO_ACT: {
V_out = 0.0f;
break;
}
case MODE_VALVE_POSITION_CONTROL: {
if (OPERATING_MODE == 5) { //SW Valve
VALVE_POS_CONTROL(valve_pos.ref);
V_out = Vout.ref;
} else if (CURRENT_CONTROL_MODE == 0) { //PWM
V_out = valve_pos.ref;
} else {
I_REF = valve_pos.ref * 0.001f;
}
break;
}
case MODE_JOINT_CONTROL: {
double torq_ref = 0.0f;
pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
vel.err = (0.0f - vel.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm/s]
pos.err_sum += pos.err/(float) TMR_FREQ_5k; //[mm]
//K & D Low Pass Filter
float alpha_K_D = 1.0f/(1.0f + 5000.0f/(2.0f*3.14f*30.0f)); // f_cutoff : 30Hz
K_LPF = K_LPF*(1.0f-alpha_K_D)+K_SPRING*(alpha_K_D);
D_LPF = D_LPF*(1.0f-alpha_K_D)+D_DAMPER*(alpha_K_D);
// torq_ref = torq.ref + K_LPF * pos.err - D_LPF * vel.sen / ENC_PULSE_PER_POSITION; //[N]
torq_ref = torq.ref;
// torque feedback
torq.err = torq_ref - torq.sen; //[N]
torq.err_sum += torq.err/(float) TMR_FREQ_5k; //[N]
if (((OPERATING_MODE&0b110)>>1) == 0 || ((OPERATING_MODE&0b110)>>1) == 1) {
double I_REF_POS = 0.0f;
double I_REF_FORCE_FB = 0.0f; // I_REF by Force Feedback
double I_REF_VC = 0.0f; // I_REF for velocity compensation
double temp_vel_pos = 0.0f;
double temp_vel_torq = 0.0f;
double wn_Pos = 2.0f * PI * 5.0f; // f_cut : 5Hz Position Control
if ((OPERATING_MODE & 0x01) == 0) { // Rotary Mode
temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION) * PI / 180.0f; // rad/s
// L when P-gain = 100, f_cut = 10Hz L feedforward velocity
} else if ((OPERATING_MODE & 0x01) == 1) {
temp_vel_pos = (0.01f * (double) P_GAIN_JOINT_POSITION * wn_Pos * pos.err + 0.01f * (double) I_GAIN_JOINT_POSITION * wn_Pos * pos.err_sum + 0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / ENC_PULSE_PER_POSITION); // mm/s
// L when P-gain = 100, f_cut = 10Hz L feedforward velocity
}
if (temp_vel_pos > 0.0f) I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_A * 0.00006f / (K_v * sqrt(2.0f * alpha3 / (alpha3 + 1.0f))));
else I_REF_POS = temp_vel_pos * ((double) PISTON_AREA_B * 0.00006f / (K_v * sqrt(2.0f / (alpha3 + 1.0f))));
// velocity compensation for torque control
if ((OPERATING_MODE & 0x01) == 0) { // Rotary Mode
I_REF_FORCE_FB = 0.001f * ((double) P_GAIN_JOINT_TORQUE * torq.err + (double) I_GAIN_JOINT_TORQUE * torq.err_sum);
// temp_vel_torq = (0.01 * (double) VELOCITY_COMP_GAIN * (double) CUR_VELOCITY / (double) ENC_PULSE_PER_POSITION) * PI / 180.0; // rad/s
temp_vel_torq = (0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / (double) ENC_PULSE_PER_POSITION) * PI / 180.0f; // rad/s
// L feedforward velocity
} else if ((OPERATING_MODE & 0x01) == 1) {
I_REF_FORCE_FB = 0.001f * 0.01f*((double) P_GAIN_JOINT_TORQUE * torq.err + (double) I_GAIN_JOINT_TORQUE * torq.err_sum); // Linear Actuators are more sensitive.
// temp_vel_torq = (0.01 * (double) VELOCITY_COMP_GAIN * (double) CUR_VELOCITY / (double) ENC_PULSE_PER_POSITION); // mm/s
temp_vel_torq = (0.01f * (double) VELOCITY_COMP_GAIN * vel.ref / (double) ENC_PULSE_PER_POSITION); // mm/s
// L feedforward velocity
}
if (temp_vel_torq > 0.0f) I_REF_VC = temp_vel_torq * ((double) PISTON_AREA_A * 0.00006f / (K_v * sqrt(2.0f * alpha3 / (alpha3 + 1.0f))));
else I_REF_VC = temp_vel_torq * ((double) PISTON_AREA_B * 0.00006f / (K_v * sqrt(2.0f / (alpha3 + 1.0f))));
// L velocity(rad/s or mm/s) >> I_ref(mA)
// Ref_Joint_FT_dot = (Ref_Joint_FT_Nm - Ref_Joint_FT_Nm_old) / TMR_DT_5k;
// Ref_Joint_FT_Nm_old = Ref_Joint_FT_Nm;
I_REF = (1.0f - alpha_trans) * I_REF_POS + alpha_trans * (I_REF_VC + I_REF_FORCE_FB);
// Anti-windup for FT
if (I_GAIN_JOINT_TORQUE != 0) {
double I_MAX = 10.0f; // Maximum Current : 10mV
double Ka = 2.0f / ((double) I_GAIN_JOINT_TORQUE * 0.001f);
if (I_REF > I_MAX) {
double I_rem = I_REF - I_MAX;
I_rem = Ka*I_rem;
I_REF = I_MAX;
torq.err_sum = torq.err_sum - I_rem /(float) TMR_FREQ_5k;
} else if (I_REF < -I_MAX) {
double I_rem = I_REF - (-I_MAX);
I_rem = Ka*I_rem;
I_REF = -I_MAX;
torq.err_sum = torq.err_sum - I_rem /(float) TMR_FREQ_5k;
}
}
} else {
float VALVE_POS_RAW_FORCE_FB = 0.0f;
float VALVE_POS_RAW_FORCE_FF = 0.0f;
float VALVE_POS_RAW = 0.0f;
VALVE_POS_RAW_FORCE_FB = alpha_trans*(((float) P_GAIN_JOINT_TORQUE * torq.err + (float) I_GAIN_JOINT_TORQUE * torq.err_sum + (float) D_GAIN_JOINT_TORQUE * (torq.ref_diff - torq_dot.sen)) * 0.01f + DDV_JOINT_POS_FF(vel.sen))+ (1.0f-alpha_trans) * (P_GAIN_JOINT_POSITION * 0.01f * pos.err + DDV_JOINT_POS_FF(vel.ref));
VALVE_POS_RAW_FORCE_FF = P_GAIN_JOINT_TORQUE_FF * torq_ref * 0.001f + D_GAIN_JOINT_TORQUE_FF * (torq_ref - torq_ref_past) * 0.0001f;
VALVE_POS_RAW = VALVE_POS_RAW_FORCE_FB + VALVE_POS_RAW_FORCE_FF;
if (VALVE_POS_RAW >= 0) {
valve_pos.ref = VALVE_POS_RAW + VALVE_DEADZONE_PLUS;
} else {
valve_pos.ref = VALVE_POS_RAW + VALVE_DEADZONE_MINUS;
}
if(I_GAIN_JOINT_TORQUE != 0) {
double Ka = 2.0f / (double) I_GAIN_JOINT_TORQUE * 100.0f;
if(valve_pos.ref>VALVE_MAX_POS) {
double valve_pos_rem = valve_pos.ref - VALVE_MAX_POS;
valve_pos_rem = valve_pos_rem * Ka;
valve_pos.ref = VALVE_MAX_POS;
torq.err_sum = torq.err_sum - valve_pos_rem/(float) TMR_FREQ_5k;
} else if(valve_pos.ref < VALVE_MIN_POS) {
double valve_pos_rem = valve_pos.ref - VALVE_MIN_POS;
valve_pos_rem = valve_pos_rem * Ka;
valve_pos.ref = VALVE_MIN_POS;
torq.err_sum = torq.err_sum - valve_pos_rem/(float) TMR_FREQ_5k;
}
}
VALVE_POS_CONTROL(valve_pos.ref);
// Vout.ref = (float) P_GAIN_JOINT_POSITION * 0.01f * ((float) pos.err);
V_out = (float) Vout.ref;
}
torq_ref_past = torq_ref;
break;
}
case MODE_VALVE_OPEN_LOOP: {
V_out = (float) Vout.ref;
break;
}
case MODE_JOINT_ADAPTIVE_BACKSTEPPING: {
float Va = (1256.6f + Amm * pos.sen/(float)(ENC_PULSE_PER_POSITION)) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * x, unit : m^3
float Vb = (1256.6f + Amm * (79.0f - pos.sen/(float)(ENC_PULSE_PER_POSITION))) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * (79.0mm-x), unit : m^3
// float Va = (1256.6f + Amm * 39.5f) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * x, unit : m^3
// float Vb = (1256.6f + Amm * 39.5f) * 0.000000001f; // 4mm pipe * 100mm + (25mm Cylinder 18mm Rod) * (79.0mm-x), unit : m^3
V_adapt = 1.0f / (1.0f/Va + 1.0f/Vb); //initial 0.0000053f
float f3 = -Amm*Amm*beta*0.000001f*0.000001f/V_adapt * vel.sen/(float)(ENC_PULSE_PER_POSITION)*0.001f; // unit : N/s //xdot=10mm/s일때 -137076
float g3_prime = 0.0f;
if (torq.sen > Amm*(Ps-Pt)*0.000001f) {
g3_prime = 1.0f;
} else if (torq.sen < -Amm*(Ps-Pt)*0.000001f) {
g3_prime = -1.0f;
} else {
if ((value-VALVE_CENTER) > 0) {
g3_prime = sqrt(Ps-Pt-torq.sen/Amm*1000000.0f);
// g3_prime = sqrt(Ps-Pt);
} else {
g3_prime = sqrt(Ps-Pt+torq.sen/Amm*1000000.0f);
// g3_prime = sqrt(Ps-Pt);
}
}
float tau = 0.01f;
float K_valve = 0.0004f;
float x_v = 0.0f; //x_v : -1~1
if(value>=VALVE_CENTER) {
x_v = 1.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
} else {
x_v = -1.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
}
float f4 = -x_v/tau;
float g4 = K_valve/tau;
float torq_ref_dot = torq.ref_diff * 500.0f;
pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
vel.err = (0.0f - vel.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm/s]
pos.err_sum += pos.err/(float) TMR_FREQ_5k; //[mm]
torq.err = torq.ref - torq.sen; //[N]
torq.err_sum += torq.err/(float) TMR_FREQ_5k; //[N]
float k3 = 20000.0f; //2000
float k4 = 10.0f;
float rho3 = 3.2f;
float rho4 = 25000000.0f;
float x_4_des = (-f3 + torq_ref_dot - k3*(-torq.err))/(gamma_hat*g3_prime);
if (x_4_des > 1) x_4_des = 1;
else if (x_4_des < -1) x_4_des = -1;
if (x_4_des > 0) {
valve_pos.ref = x_4_des * (float)(VALVE_MAX_POS - VALVE_CENTER) + (float) VALVE_CENTER;
} else {
valve_pos.ref = x_4_des * (float)(VALVE_CENTER - VALVE_MIN_POS) + (float) VALVE_CENTER;
}
float x_4_des_dot = (x_4_des - x_4_des_old)*(float) TMR_FREQ_5k;
x_4_des_old = x_4_des;
V_out = (-f4 + x_4_des_dot - k4*(x_v-x_4_des)- rho3/rho4*gamma_hat*g3_prime*(-torq.err))/g4;
float rho_gamma = 50000.0f;//5000
float gamma_hat_dot = rho3*(-torq.err)/rho_gamma*((-f3+torq_ref_dot-k3*(-torq.err))/gamma_hat + g3_prime*(x_v-x_4_des));
gamma_hat = gamma_hat + gamma_hat_dot / (float) TMR_FREQ_5k;
break;
}
case MODE_RL: {
//t.reset();
//t.start();
// if(LED == 0) LED = 1;
// else LED = 0;
if (Update_Done_Flag == 1) {
//Gather Data on each loop
// pos.err = (pos.ref - pos.sen)/(float)(ENC_PULSE_PER_POSITION); //[mm]
// train_set_x[RL_timer] = pos.sen/(float)(ENC_PULSE_PER_POSITION)/35.0f - 1.0f; //-1.0~1.0
// train_set_error[RL_timer] = pos.err/70.0f; //-1.0~1.0
pos.err = pos.sen/(float)(ENC_PULSE_PER_POSITION) - virt_pos; //[mm]
train_set_x[RL_timer] = virt_pos/70.0f; //-1.0~1.0
train_set_error[RL_timer] = pos.err/70.0f; //-1.0~1.0
//train_set_count[RL_timer] = (float) RL_timer / (batch_size *num_batch); //-1.0~1.0
//float temp_array[3] = {train_set_x[RL_timer], train_set_error[RL_timer], train_set_count[RL_timer]};
float temp_array[2] = {train_set_x[RL_timer], train_set_error[RL_timer]};
Actor_Network(temp_array);
for (int i=0; i<num_hidden_unit1; i++) {
hx_a_sum_array[RL_timer][i] = hx_a_sum[i];
}
for (int i=0; i<num_hidden_unit2; i++) {
hxh_a_sum_array[RL_timer][i] = hxh_a_sum[i];
}
hxhh_a_sum_array[RL_timer][0] = hxhh_a_sum[0];
hxhh_a_sum_array[RL_timer][1] = hxhh_a_sum[1];
mean_array[RL_timer] = mean;
deviation_array[RL_timer] = deviation;
action_array[RL_timer] = rand_normal(mean_array[RL_timer], deviation_array[RL_timer]);
virt_pos = virt_pos + (action_array[RL_timer] - 5.0f) * 1000.0f * 0.0002f;
if (virt_pos > 70 ) {
virt_pos = 70.0f;
}else if(virt_pos < -70) {
virt_pos = -70.0f;
}
RL_timer++;
if (RL_timer >= batch_size) {
RL_timer = 0;
batch++;
for(int i=0; i<batch_size; i++) {
state_array[i][0] = train_set_x[i];
state_array[i][1] = train_set_error[i];
//state_array[i][2] = train_set_count[i];
}
Update_Case = 1;
Update_Done_Flag = 0;
logging1 = virt_pos;
if(batch >= num_batch) {
batch = 0;
RL_timer = 0;
Update_Case = 2;
Update_Done_Flag = 0;
virt_pos = 10.0f;
}
}
}
else {
pos.err = pos.sen/(float)(ENC_PULSE_PER_POSITION) - virt_pos; //[mm]
float temp_array[3] = {0.0f};
temp_array[0] = virt_pos/70.0f; //-1.0~1.0
temp_array[1] = pos.err/70.0f; //-1.0~1.0
//temp_array[2] = (float) RL_timer / (batch_size *num_batch); //-1.0~1.0
Actor_Network(temp_array);
action = rand_normal(mean, deviation);
//logging1 = action;
//logging2 = mean;
//logging4 = deviation;
virt_pos = virt_pos + (action-5.0f) * 1000.0f * 0.0002f;
if (virt_pos > 70) {
virt_pos = 70.0f;
}else if(virt_pos < -70) {
virt_pos = -70.0f;
}
logging3 = virt_pos;
}
//t.stop();
//logging1 = t.read()*1000.0f; //msec
break;
}
default:
break;
}
if (((OPERATING_MODE&0b110)>>1) == 0 || ((OPERATING_MODE&0b110)>>1) == 1) { //Moog Valve or KNR Valve
////////////////////////////////////////////////////////////////////////////
//////////////////////////// CURRENT CONTROL //////////////////////////////
////////////////////////////////////////////////////////////////////////////
if (CURRENT_CONTROL_MODE) {
double alpha_update_Iref = 1.0f / (1.0f + 5000.0f / (2.0f * 3.14f * 300.0f)); // f_cutoff : 500Hz
I_REF_fil = (1.0f - alpha_update_Iref) * I_REF_fil + alpha_update_Iref*I_REF;
I_ERR = I_REF_fil - cur.sen;
I_ERR_INT = I_ERR_INT + (I_ERR) * 0.0002f;
// Moog Valve Current Control Gain
double R_model = 500.0f; // ohm
double L_model = 1.2f;
double w0 = 2.0f * 3.14f * 150.0f;
double KP_I = 0.1f * L_model*w0;
double KI_I = 0.1f * R_model*w0;
// KNR Valve Current Control Gain
if (((OPERATING_MODE & 0b110)>>1) == 1) { // KNR Valve
R_model = 163.0f; // ohm
L_model = 1.0f;
w0 = 2.0f * 3.14f * 80.0f;
KP_I = 1.0f * L_model*w0;
KI_I = 0.08f * R_model*w0;
}
double FF_gain = 1.0f;
VALVE_PWM_RAW = KP_I * 2.0f * I_ERR + KI_I * 2.0f* I_ERR_INT;
// VALVE_PWM_RAW = VALVE_PWM_RAW + FF_gain * (R_model*I_REF); // Unit : mV
I_REF_fil_diff = I_REF_fil - I_REF_fil_old;
I_REF_fil_old = I_REF_fil;
// VALVE_PWM_RAW = VALVE_PWM_RAW + FF_gain * (R_model * I_REF_fil + L_model * I_REF_fil_diff * 5000.0f); // Unit : mV
VALVE_PWM_RAW = VALVE_PWM_RAW + FF_gain * (R_model * I_REF_fil); // Unit : mV
double V_MAX = 12000.0f; // Maximum Voltage : 12V = 12000mV
double Ka = 3.0f / KP_I;
if (VALVE_PWM_RAW > V_MAX) {
V_rem = VALVE_PWM_RAW - V_MAX;
V_rem = Ka*V_rem;
VALVE_PWM_RAW = V_MAX;
I_ERR_INT = I_ERR_INT - V_rem * 0.0002f;
} else if (VALVE_PWM_RAW < -V_MAX) {
V_rem = VALVE_PWM_RAW - (-V_MAX);
V_rem = Ka*V_rem;
VALVE_PWM_RAW = -V_MAX;
I_ERR_INT = I_ERR_INT - V_rem * 0.0002f;
}
Cur_Valve_Open_pulse = cur.sen / mA_PER_pulse;
} else {
VALVE_PWM_RAW = I_REF * mV_PER_mA;
Cur_Valve_Open_pulse = I_REF / mA_PER_pulse;
}
////////////////////////////////////////////////////////////////////////////
///////////////// Dead Zone Cancellation & Linearization //////////////////
////////////////////////////////////////////////////////////////////////////
// Dead Zone Cancellation (Mechanical Valve dead-zone)
if (FLAG_VALVE_DEADZONE) {
if (VALVE_PWM_RAW > 0) VALVE_PWM_RAW = VALVE_PWM_RAW + VALVE_DEADZONE_PLUS * mV_PER_pulse; // unit: mV
else if (VALVE_PWM_RAW < 0) VALVE_PWM_RAW = VALVE_PWM_RAW + VALVE_DEADZONE_MINUS * mV_PER_pulse; // unit: mV
VALVE_PWM_VALVE_DZ = VALVE_PWM_RAW + (double)VALVE_CENTER * mV_PER_pulse; // unit: mV
} else {
VALVE_PWM_VALVE_DZ = VALVE_PWM_RAW;
}
// Output Voltage Linearization
double CUR_PWM_nonlin = VALVE_PWM_VALVE_DZ; // Unit : mV
double CUR_PWM_lin = PWM_duty_byLT(CUR_PWM_nonlin); // -8000~8000
// Dead Zone Cancellation (Electrical dead-zone)
if (CUR_PWM_lin > 0) V_out = (float) (CUR_PWM_lin + 169.0f);
else if (CUR_PWM_lin < 0) V_out = (float) (CUR_PWM_lin - 174.0f);
else V_out = (float) (CUR_PWM_lin);
} else { //////////////////////////sw valve
// Output Voltage Linearization
// double CUR_PWM_nonlin = V_out; // Unit : mV
// double CUR_PWM_lin = PWM_duty_byLT(CUR_PWM_nonlin); // -8000~8000
// Dead Zone Cancellation (Electrical dead-zone)
// if (CUR_PWM_lin > 0) V_out = (float) (CUR_PWM_lin + 169.0f);
// else if (CUR_PWM_lin < 0) V_out = (float) (CUR_PWM_lin - 174.0f);
// else V_out = (float) (CUR_PWM_lin);
if (V_out > 0 ) V_out = (V_out + 180.0f)/0.8588f;
else if (V_out < 0) V_out = (V_out - 200.0f)/0.8651f;
else V_out = 0.0f;
}
// if(V_out > 0.0f) V_out = (float) (V_out + 169.0f);
// else if(V_out < 0.0f) V_out = (float) (V_out - 174.0f);
// else V_out = V_out;
/*******************************************************
*** PWM
********************************************************/
if(DIR_VALVE<0) {
V_out = -V_out;
}
if (V_out >= VALVE_VOLTAGE_LIMIT*1000.0f) {
V_out = VALVE_VOLTAGE_LIMIT*1000.0f;
} else if(V_out<=-VALVE_VOLTAGE_LIMIT*1000.0f) {
V_out = -VALVE_VOLTAGE_LIMIT*1000.0f;
}
PWM_out= V_out/(SUPPLY_VOLTAGE*1000.0f); // Full duty : 12000.0mV
// Saturation of output voltage to 12.0V
if(PWM_out > 1.0f) PWM_out=1.0f;
else if (PWM_out < -1.0f) PWM_out=-1.0f;
if (PWM_out>0.0f) {
dtc_v=0.0f;
dtc_w=PWM_out;
} else {
dtc_v=-PWM_out;
dtc_w=0.0f;
}
//pwm
TIM4->CCR2 = (PWM_ARR)*(1.0f-dtc_v);
TIM4->CCR1 = (PWM_ARR)*(1.0f-dtc_w);
if (TMR2_COUNT_CAN_TX % (int) ((int) TMR_FREQ_5k/CAN_FREQ) == 0) {
// Position, Velocity, and Torque (ID:1200)
if (flag_data_request[0] == HIGH) {
if ((OPERATING_MODE & 0b01) == 0) { // Rotary Actuator
if (SENSING_MODE == 0) {
CAN_TX_POSITION_FT((int16_t) (pos.sen), (int16_t) (vel.sen/10.0f), (int16_t) (torq.sen*10.0f));
} else if (SENSING_MODE == 1) {
CAN_TX_POSITION_PRESSURE((int16_t) (pos.sen), (int16_t) (vel.sen/10.0f), (int16_t) ((pres_A.sen)*5.0f), (int16_t) ((pres_B.sen)*5.0f));
}
} else if ((OPERATING_MODE & 0b01) == 1) { // Linear Actuator
if (SENSING_MODE == 0) {
CAN_TX_POSITION_FT((int16_t) (pos.sen/10.0f), (int16_t) (vel.sen/256.0f), (int16_t) (torq.sen * 10.0f * (float)(TORQUE_SENSOR_PULSE_PER_TORQUE)));
} else if (SENSING_MODE == 1) {
CAN_TX_POSITION_PRESSURE((int16_t) (pos.sen/10.0f), (int16_t) (vel.sen/256.0f), (int16_t) ((pres_A.sen)*5.0f), (int16_t) ((pres_B.sen)*5.0f));
}
}
}
if (flag_data_request[1] == HIGH) {
CAN_TX_TORQUE((int16_t) (return_G[0]*100.0f)); //1300
}
if (flag_data_request[2] == HIGH) {
double t_value = 0.0f;
if(value>=(float) VALVE_CENTER) {
t_value = 10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
} else {
t_value = -10000.0f*((double)value - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
}
double t_value_ref = 0.0f;
if(valve_pos.ref>=(float) VALVE_CENTER) {
t_value_ref = 10000.0f*((double)valve_pos.ref - (double)VALVE_CENTER)/((double)VALVE_MAX_POS - (double)VALVE_CENTER);
} else {
t_value_ref = -10000.0f*((double)valve_pos.ref - (double)VALVE_CENTER)/((double)VALVE_MIN_POS - (double)VALVE_CENTER);
}
CAN_TX_PRES((int16_t) (t_value), (int16_t) (t_value_ref)); // 1400
}
//If it doesn't rest, below can can not work.
for (can_rest = 0; can_rest < 10000; can_rest++) {
;
}
if (flag_data_request[3] == HIGH) {
//PWM
CAN_TX_PWM((int16_t) (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) action_array[20], (int16_t) virt_pos, (int16_t) Update_Case*1000, (int16_t) (logging4*1000.0f)); //1600
}
// Others : Reference position, Reference FT, PWM, Current (ID:1300)
// if (flag_data_request[1] == HIGH) {
// CAN_TX_SOMETHING((int) (FORCE_VREF), (int16_t) (1), (int16_t) (2), (int16_t) (3));
// }
//if (flag_delay_test == 1){
//CAN_TX_PRES((int16_t) (0),(int16_t) torq_ref);
//}
TMR2_COUNT_CAN_TX = 0;
}
TMR2_COUNT_CAN_TX++;
}
TIM3->SR = 0x0; // reset the status register
}