meas_tasks.c 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383
  1. /*
  2. * meas_tasks.c
  3. *
  4. * Created on: Sep 5, 2024
  5. * Author: jakubski
  6. */
  7. #include <math.h>
  8. #include <stdio.h>
  9. #include "adc_buffers.h"
  10. #include "meas_tasks.h"
  11. #include "measurements.h"
  12. #include "node-red-config.h"
  13. #include "peripherial.h"
  14. #include "cmsis_os.h"
  15. #include "main.h"
  16. #ifdef PV_BOARD
  17. #define VOLTAGES_COUNT 1
  18. #define CURRENTS_COUNT 1
  19. #else
  20. #define VOLTAGES_COUNT 3
  21. #define CURRENTS_COUNT 3
  22. #endif
  23. #define CIRC_BUFF_LEN 10
  24. osThreadId_t adc1MeasTaskHandle = NULL;
  25. osThreadId_t adc2MeasTaskHandle = NULL;
  26. osThreadId_t adc3MeasTaskHandle = NULL;
  27. osThreadId_t limiterSwitchTaskHandle = NULL;
  28. osThreadId_t encoderXTaskHandle = NULL;
  29. osThreadId_t encoderYTaskHandle = NULL;
  30. osMessageQueueId_t adc1MeasDataQueue = NULL;
  31. osMessageQueueId_t adc2MeasDataQueue = NULL;
  32. osMessageQueueId_t adc3MeasDataQueue = NULL;
  33. osMutexId_t vRefmVMutex;
  34. osMutexId_t resMeasurementsMutex;
  35. osMutexId_t sensorsInfoMutex;
  36. osMutexId_t ILxRefMutex;
  37. volatile uint32_t vRefmV = 3000;
  38. RESMeasurements resMeasurements __attribute__ ((aligned (32))) = { 0 };
  39. SesnorsInfo sensorsInfo __attribute__ ((aligned (32))) = { 0 };
  40. uint16_t ILxRef[CURRENTS_COUNT] __attribute__ ((aligned (32))) = { 0 };
  41. EncoderTaskArg encoderXTaskArg __attribute__ ((aligned (32))) = { 0 };
  42. EncoderTaskArg encoderYTaskArg __attribute__ ((aligned (32))) = { 0 };
  43. extern TIM_HandleTypeDef htim3;
  44. extern TIM_OC_InitTypeDef motorXYTimerConfigOC;
  45. extern osTimerId_t motorXTimerHandle;
  46. extern osTimerId_t motorYTimerHandle;
  47. void MeasTasksInit (void) {
  48. vRefmVMutex = osMutexNew (NULL);
  49. resMeasurementsMutex = osMutexNew (NULL);
  50. sensorsInfoMutex = osMutexNew (NULL);
  51. ILxRefMutex = osMutexNew (NULL);
  52. adc1MeasDataQueue = osMessageQueueNew (8, sizeof (ADC1_Data), NULL);
  53. adc2MeasDataQueue = osMessageQueueNew (8, sizeof (ADC2_Data), NULL);
  54. adc3MeasDataQueue = osMessageQueueNew (8, sizeof (ADC3_Data), NULL);
  55. osThreadAttr_t osThreadAttradc1MeasTask = { 0 };
  56. osThreadAttr_t osThreadAttradc2MeasTask = { 0 };
  57. osThreadAttr_t osThreadAttradc3MeasTask = { 0 };
  58. osThreadAttradc1MeasTask.stack_size = configMINIMAL_STACK_SIZE * 2;
  59. osThreadAttradc1MeasTask.priority = (osPriority_t)osPriorityRealtime;
  60. osThreadAttradc2MeasTask.stack_size = configMINIMAL_STACK_SIZE * 2;
  61. osThreadAttradc2MeasTask.priority = (osPriority_t)osPriorityRealtime;
  62. osThreadAttradc3MeasTask.stack_size = configMINIMAL_STACK_SIZE * 2;
  63. osThreadAttradc3MeasTask.priority = (osPriority_t)osPriorityNormal;
  64. adc1MeasTaskHandle = osThreadNew (ADC1MeasTask, NULL, &osThreadAttradc1MeasTask);
  65. adc2MeasTaskHandle = osThreadNew (ADC2MeasTask, NULL, &osThreadAttradc2MeasTask);
  66. adc3MeasTaskHandle = osThreadNew (ADC3MeasTask, NULL, &osThreadAttradc3MeasTask);
  67. osThreadAttr_t osThreadAttradc1LimiterSwitchTask = { 0 };
  68. osThreadAttradc1LimiterSwitchTask.stack_size = configMINIMAL_STACK_SIZE * 2;
  69. osThreadAttradc1LimiterSwitchTask.priority = (osPriority_t)osPriorityNormal;
  70. limiterSwitchTaskHandle = osThreadNew (LimiterSwitchTask, NULL, &osThreadAttradc1LimiterSwitchTask);
  71. encoderXTaskArg.dbgLed = DBG_LED2;
  72. encoderXTaskArg.pvEncoder = &(sensorsInfo.pvEncoderX);
  73. encoderXTaskArg.currentPosition = &(sensorsInfo.currentXPosition);
  74. osMessageQueueAttr_t encoderMsgQueueAttr = { 0 };
  75. encoderXTaskArg.dataQueue = osMessageQueueNew (16, sizeof (uint32_t), &encoderMsgQueueAttr);
  76. encoderXTaskArg.initPinStates = ((HAL_GPIO_ReadPin(GPIOD, GPIO_PIN_15) << 1) | HAL_GPIO_ReadPin(GPIOD, GPIO_PIN_14)) & 0x3;
  77. encoderYTaskArg.dbgLed = DBG_LED3;
  78. encoderYTaskArg.pvEncoder = &(sensorsInfo.pvEncoderY);
  79. encoderYTaskArg.currentPosition = &(sensorsInfo.currentYPosition);
  80. encoderYTaskArg.dataQueue = osMessageQueueNew (16, sizeof (uint32_t), &encoderMsgQueueAttr);
  81. encoderYTaskArg.initPinStates = ((HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_11) << 1) | HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_10)) & 0x3;
  82. osThreadAttr_t osThreadAttrEncoderTask = { 0 };
  83. osThreadAttrEncoderTask.stack_size = configMINIMAL_STACK_SIZE * 2;
  84. osThreadAttrEncoderTask.priority = (osPriority_t)osPriorityRealtime;
  85. encoderXTaskHandle = osThreadNew (EncoderTask, &encoderXTaskArg, &osThreadAttrEncoderTask);
  86. encoderYTaskHandle = osThreadNew (EncoderTask, &encoderYTaskArg, &osThreadAttrEncoderTask);
  87. }
  88. void ADC1MeasTask (void* arg) {
  89. float circBuffer[VOLTAGES_COUNT][CIRC_BUFF_LEN] = { 0 };
  90. float rms[VOLTAGES_COUNT] = { 0 };
  91. ;
  92. ADC1_Data adcData = { 0 };
  93. uint32_t circBuffPos = 0;
  94. float gainCorrection = 1.0;
  95. while (pdTRUE) {
  96. osMessageQueueGet (adc1MeasDataQueue, &adcData, 0, osWaitForever);
  97. #ifdef GAIN_AUTO_CORRECTION
  98. if (osMutexAcquire (vRefmVMutex, osWaitForever) == osOK) {
  99. gainCorrection = (float)vRefmV;
  100. osMutexRelease (vRefmVMutex);
  101. }
  102. gainCorrection = gainCorrection / EXT_VREF_mV;
  103. #endif
  104. for (uint8_t i = 0; i < VOLTAGES_COUNT; i++) {
  105. float val = adcData.adcDataBuffer[i] * deltaADC * U_CHANNEL_CONST * gainCorrection * U_MeasCorrectionData[i].gain + U_MeasCorrectionData[i].offset;
  106. circBuffer[i][circBuffPos] = val;
  107. rms[i] = 0.0;
  108. for (uint8_t c = 0; c < CIRC_BUFF_LEN; c++) {
  109. rms[i] += circBuffer[i][c];
  110. }
  111. rms[i] = rms[i] / CIRC_BUFF_LEN;
  112. if (osMutexAcquire (resMeasurementsMutex, osWaitForever) == osOK) {
  113. if (fabs (resMeasurements.voltagePeak[i]) < fabs (val)) {
  114. resMeasurements.voltagePeak[i] = val;
  115. }
  116. resMeasurements.voltageRMS[i] = rms[i];
  117. resMeasurements.power[i] = resMeasurements.voltageRMS[i] * resMeasurements.currentRMS[i];
  118. osMutexRelease (resMeasurementsMutex);
  119. }
  120. }
  121. ++circBuffPos;
  122. circBuffPos = circBuffPos % CIRC_BUFF_LEN;
  123. if (osMutexAcquire (ILxRefMutex, osWaitForever) == osOK) {
  124. uint8_t refIdx = 0;
  125. for (uint8_t i = (uint8_t)IL1Ref; i <= (uint8_t)IL3Ref; i++) {
  126. ILxRef[refIdx++] = adcData.adcDataBuffer[i];
  127. }
  128. osMutexRelease (ILxRefMutex);
  129. }
  130. float fanFBVoltage = adcData.adcDataBuffer[FanFB] * deltaADC * -4.35 + 12;
  131. if (osMutexAcquire (sensorsInfoMutex, osWaitForever) == osOK) {
  132. sensorsInfo.fanVoltage = fanFBVoltage;
  133. osMutexRelease (sensorsInfoMutex);
  134. }
  135. }
  136. }
  137. void ADC2MeasTask (void* arg) {
  138. float circBuffer[CURRENTS_COUNT][CIRC_BUFF_LEN] = { 0 };
  139. float rms[CURRENTS_COUNT] = { 0 };
  140. ADC2_Data adcData = { 0 };
  141. uint32_t circBuffPos = 0;
  142. float gainCorrection = 1.0;
  143. while (pdTRUE) {
  144. osMessageQueueGet (adc2MeasDataQueue, &adcData, 0, osWaitForever);
  145. if (osMutexAcquire (vRefmVMutex, osWaitForever) == osOK) {
  146. gainCorrection = (float)vRefmV;
  147. osMutexRelease (vRefmVMutex);
  148. }
  149. gainCorrection = gainCorrection / EXT_VREF_mV;
  150. float ref[CURRENTS_COUNT] = { 0 };
  151. if (osMutexAcquire (ILxRefMutex, osWaitForever) == osOK) {
  152. for (uint8_t i = 0; i < CURRENTS_COUNT; i++) {
  153. ref[i] = (float)ILxRef[i];
  154. }
  155. osMutexRelease (ILxRefMutex);
  156. }
  157. for (uint8_t i = 0; i < CURRENTS_COUNT; i++) {
  158. float adcVal = (float)adcData.adcDataBuffer[i];
  159. float val = (adcVal - ref[i]) * deltaADC * I_CHANNEL_CONST * gainCorrection * I_MeasCorrectionData[i].gain + I_MeasCorrectionData[i].offset;
  160. circBuffer[i][circBuffPos] = val;
  161. rms[i] = 0.0;
  162. for (uint8_t c = 0; c < CIRC_BUFF_LEN; c++) {
  163. rms[i] += circBuffer[i][c];
  164. }
  165. rms[i] = rms[i] / CIRC_BUFF_LEN;
  166. if (osMutexAcquire (resMeasurementsMutex, osWaitForever) == osOK) {
  167. if (resMeasurements.currentPeak[i] < val) {
  168. resMeasurements.currentPeak[i] = val;
  169. }
  170. resMeasurements.currentRMS[i] = rms[i];
  171. osMutexRelease (resMeasurementsMutex);
  172. }
  173. }
  174. ++circBuffPos;
  175. circBuffPos = circBuffPos % CIRC_BUFF_LEN;
  176. }
  177. }
  178. void ADC3MeasTask (void* arg) {
  179. float motorXSensCircBuffer[CIRC_BUFF_LEN] = { 0 };
  180. float motorYSensCircBuffer[CIRC_BUFF_LEN] = { 0 };
  181. float pvT1CircBuffer[CIRC_BUFF_LEN] = { 0 };
  182. float pvT2CircBuffer[CIRC_BUFF_LEN] = { 0 };
  183. uint32_t circBuffPos = 0;
  184. ADC3_Data adcData = { 0 };
  185. while (pdTRUE) {
  186. osMessageQueueGet (adc3MeasDataQueue, &adcData, 0, osWaitForever);
  187. uint32_t vRef = __LL_ADC_CALC_VREFANALOG_VOLTAGE (adcData.adcDataBuffer[VrefInt], LL_ADC_RESOLUTION_16B);
  188. if (osMutexAcquire (vRefmVMutex, osWaitForever) == osOK) {
  189. vRefmV = vRef;
  190. osMutexRelease (vRefmVMutex);
  191. }
  192. float motorXCurrentSense = adcData.adcDataBuffer[motorXSense] * deltaADC * 10 / 8.33333;
  193. float motorYCurrentSense = adcData.adcDataBuffer[motorYSense] * deltaADC * 10 / 8.33333;
  194. motorXSensCircBuffer[circBuffPos] = motorXCurrentSense;
  195. motorYSensCircBuffer[circBuffPos] = motorYCurrentSense;
  196. pvT1CircBuffer[circBuffPos] = adcData.adcDataBuffer[pvTemp1] * deltaADC * 45.33333333 - 63;
  197. pvT2CircBuffer[circBuffPos] = adcData.adcDataBuffer[pvTemp2] * deltaADC * 45.33333333 - 63;
  198. float motorXAveCurrent = 0;
  199. float motorYAveCurrent = 0;
  200. float pvT1AveTemp = 0;
  201. float pvT2AveTemp = 0;
  202. for (uint8_t i = 0; i < CIRC_BUFF_LEN; i++) {
  203. motorXAveCurrent += motorXSensCircBuffer[i];
  204. motorYAveCurrent += motorYSensCircBuffer[i];
  205. #ifdef PV_BOARD
  206. pvT1AveTemp += pvT1CircBuffer[i];
  207. pvT2AveTemp += pvT2CircBuffer[i];
  208. #endif
  209. }
  210. motorXAveCurrent /= CIRC_BUFF_LEN;
  211. motorYAveCurrent /= CIRC_BUFF_LEN;
  212. pvT1AveTemp /= CIRC_BUFF_LEN;
  213. pvT2AveTemp /= CIRC_BUFF_LEN;
  214. if (osMutexAcquire (sensorsInfoMutex, osWaitForever) == osOK) {
  215. if (sensorsInfo.motorXStatus == 1) {
  216. sensorsInfo.motorXAveCurrent = motorXAveCurrent;
  217. if (sensorsInfo.motorXPeakCurrent < motorXCurrentSense) {
  218. sensorsInfo.motorXPeakCurrent = motorXCurrentSense;
  219. }
  220. }
  221. if (sensorsInfo.motorYStatus == 1) {
  222. sensorsInfo.motorYAveCurrent = motorYAveCurrent;
  223. if (sensorsInfo.motorYPeakCurrent < motorYCurrentSense) {
  224. sensorsInfo.motorYPeakCurrent = motorYCurrentSense;
  225. }
  226. }
  227. sensorsInfo.pvTemperature[0] = pvT1AveTemp;
  228. sensorsInfo.pvTemperature[1] = pvT2AveTemp;
  229. osMutexRelease (sensorsInfoMutex);
  230. }
  231. ++circBuffPos;
  232. circBuffPos = circBuffPos % CIRC_BUFF_LEN;
  233. }
  234. }
  235. void LimiterSwitchTask (void* arg) {
  236. uint8_t limitXSwitchDownPrevState = 0;
  237. uint8_t limitXSwitchCenterPrevState = 0;
  238. uint8_t limitXSwitchUpPrevState = 0;
  239. uint8_t limitYSwitchDownPrevState = 0;
  240. uint8_t limitYSwitchCenterPrevState = 0;
  241. uint8_t limitYSwitchUpPrevState = 0;
  242. uint8_t pinStates = 0;
  243. uint8_t limiterXTriggered = 0;
  244. uint8_t limiterYTriggered = 0;
  245. if (osMutexAcquire (sensorsInfoMutex, osWaitForever) == osOK) {
  246. sensorsInfo.positionXWeak = 1;
  247. sensorsInfo.positionYWeak = 1;
  248. osMutexRelease (sensorsInfoMutex);
  249. }
  250. while (pdTRUE) {
  251. osDelay (pdMS_TO_TICKS (100));
  252. if (osMutexAcquire (sensorsInfoMutex, osWaitForever) == osOK) {
  253. sensorsInfo.limitXSwitchDown = HAL_GPIO_ReadPin (GPIOD, GPIO_PIN_13);
  254. pinStates = (limitXSwitchDownPrevState << 1) | sensorsInfo.limitXSwitchDown;
  255. if ((pinStates & 0x3) == 0x1) {
  256. limiterXTriggered = 1;
  257. sensorsInfo.currentXPosition = 0;
  258. sensorsInfo.positionXWeak = 0;
  259. }
  260. limitXSwitchDownPrevState = sensorsInfo.limitXSwitchDown;
  261. sensorsInfo.limitXSwitchUp = HAL_GPIO_ReadPin (GPIOD, GPIO_PIN_12);
  262. pinStates = (limitXSwitchUpPrevState << 1) | sensorsInfo.limitXSwitchUp;
  263. if ((pinStates & 0x3) == 0x1) {
  264. limiterXTriggered = 1;
  265. sensorsInfo.currentXPosition = 100;
  266. sensorsInfo.positionXWeak = 0;
  267. }
  268. limitXSwitchUpPrevState = sensorsInfo.limitXSwitchUp;
  269. sensorsInfo.limitXSwitchCenter = HAL_GPIO_ReadPin (GPIOD, GPIO_PIN_10);
  270. pinStates = (limitXSwitchCenterPrevState << 1) | sensorsInfo.limitXSwitchCenter;
  271. if ((pinStates & 0x3) == 0x1) {
  272. sensorsInfo.currentXPosition = AXE_X_MIDDLE_VALUE;
  273. sensorsInfo.positionXWeak = 0;
  274. }
  275. limitXSwitchCenterPrevState = sensorsInfo.limitXSwitchCenter;
  276. sensorsInfo.limitYSwitchDown = HAL_GPIO_ReadPin (GPIOD, GPIO_PIN_9);
  277. pinStates = (limitYSwitchDownPrevState << 1) | sensorsInfo.limitYSwitchDown;
  278. if ((pinStates & 0x3) == 0x1) {
  279. limiterYTriggered = 1;
  280. sensorsInfo.currentYPosition = 0;
  281. sensorsInfo.positionYWeak = 0;
  282. }
  283. limitYSwitchDownPrevState = sensorsInfo.limitYSwitchDown;
  284. sensorsInfo.limitYSwitchUp = HAL_GPIO_ReadPin (GPIOD, GPIO_PIN_11);
  285. pinStates = (limitYSwitchUpPrevState << 1) | sensorsInfo.limitYSwitchUp;
  286. if ((pinStates & 0x3) == 0x1) {
  287. limiterYTriggered = 1;
  288. sensorsInfo.currentYPosition = 100;
  289. sensorsInfo.positionYWeak = 0;
  290. }
  291. limitYSwitchUpPrevState = sensorsInfo.limitYSwitchUp;
  292. sensorsInfo.limitYSwitchCenter = HAL_GPIO_ReadPin (GPIOD, GPIO_PIN_8);
  293. pinStates = (limitYSwitchCenterPrevState << 1) | sensorsInfo.limitYSwitchCenter;
  294. if ((pinStates & 0x3) == 0x1) {
  295. sensorsInfo.currentYPosition = AXE_Y_MIDDLE_VALUE;
  296. sensorsInfo.positionYWeak = 0;
  297. }
  298. limitYSwitchCenterPrevState = sensorsInfo.limitYSwitchCenter;
  299. if (((sensorsInfo.limitXSwitchDown == 1) || (sensorsInfo.limitXSwitchUp == 1)) && (limiterXTriggered == 1)) {
  300. sensorsInfo.motorXStatus = MotorControl (&htim3, &motorXYTimerConfigOC, TIM_CHANNEL_1, TIM_CHANNEL_2, motorXTimerHandle, 0, 0, sensorsInfo.limitXSwitchUp, sensorsInfo.limitXSwitchDown);
  301. }
  302. if (((sensorsInfo.limitYSwitchDown == 1) || (sensorsInfo.limitYSwitchUp == 1)) && (limiterYTriggered == 1)) {
  303. sensorsInfo.motorYStatus = MotorControl (&htim3, &motorXYTimerConfigOC, TIM_CHANNEL_3, TIM_CHANNEL_4, motorYTimerHandle, 0, 0, sensorsInfo.limitYSwitchUp, sensorsInfo.limitYSwitchDown);
  304. }
  305. limiterXTriggered = 0;
  306. limiterYTriggered = 0;
  307. osMutexRelease (sensorsInfoMutex);
  308. }
  309. }
  310. }
  311. void EncoderTask (void* arg) {
  312. // 01 11 10 00
  313. const uint32_t encoderStates[4] = { 0x00, 0x01, 0x03, 0x02 };
  314. uint8_t step = 0;
  315. EncoderTaskArg* encoderTaskArg = (EncoderTaskArg*)arg;
  316. uint32_t pinStates = encoderTaskArg->initPinStates;
  317. for (uint8_t i = 0; i < 4; i++) {
  318. if (pinStates == encoderStates[i]) {
  319. step = i;
  320. break;
  321. }
  322. }
  323. while (pdTRUE) {
  324. float encoderValue = *encoderTaskArg->pvEncoder;
  325. osMessageQueueGet (encoderTaskArg->dataQueue, &pinStates, 0, osWaitForever);
  326. if (osMutexAcquire (sensorsInfoMutex, osWaitForever) == osOK) {
  327. if (encoderStates[(step + 1) % 4] == pinStates) {
  328. step++;
  329. encoderValue += 360.0 / ENCODER_X_IMP_PER_TURN;
  330. // printf ("Forward\n");
  331. } else if (encoderStates[(step - 1) % 4] == pinStates) {
  332. encoderValue -= 360.0 / ENCODER_X_IMP_PER_TURN;
  333. if (encoderValue < 0) {
  334. encoderValue = 360.0 + encoderValue;
  335. }
  336. // printf ("Reverse\n");
  337. step--;
  338. } else {
  339. printf ("Forbidden\n");
  340. }
  341. step = step % 4;
  342. *encoderTaskArg->pvEncoder = fmodf (encoderValue, 360.0);
  343. *encoderTaskArg->currentPosition = 100 * (*encoderTaskArg->pvEncoder) / MAX_X_AXE_ANGLE;
  344. osMutexRelease (sensorsInfoMutex);
  345. }
  346. DbgLEDToggle (encoderTaskArg->dbgLed);
  347. }
  348. }