diff --git a/Inc/targets.h b/Inc/targets.h
index 7cbe6d9c..99fc3be0 100644
--- a/Inc/targets.h
+++ b/Inc/targets.h
@@ -1,9 +1,11 @@
#ifndef USE_MAKE
-//#define FD6288_F051
-#define IFLIGHT_F051
+#define FD6288_F051
+//#define IFLIGHT_F051
//#define MP6531_F051
+//#define DAKEFPV_35A_F051
+
//#define TMOTOR55_F051 // like iflight but with leds
//#define TMOTOR45_F051
//#define HGLRC_F051
@@ -59,6 +61,14 @@
#define USE_SERIAL_TELEMETRY
#endif
+#ifdef DAKEFPV_35A_F051
+#define FILE_NAME "DAKEFPV_35A_F051"
+#define FIRMWARE_NAME "DakeFPV 35A"
+#define DEAD_TIME 18
+#define HARDWARE_GROUP_F0_B
+#define USE_SERIAL_TELEMETRY
+#endif
+
#ifdef RAZOR32_F051
#define FILE_NAME "RAZOR32_F051"
#define FIRMWARE_NAME "Razor32 "
diff --git a/Mcu/f031/Src/IO.c b/Mcu/f031/Src/IO.c
index 25eb66ac..a8a90f4e 100644
--- a/Mcu/f031/Src/IO.c
+++ b/Mcu/f031/Src/IO.c
@@ -195,7 +195,7 @@ void checkDshot(){
output_timer_prescaler=0;
dshot = 1;
buffer_divider = 44;
- buffer_padding = 9;
+ // buffer_padding = 9;
buffersize = 32;
inputSet = 1;
}
@@ -205,7 +205,7 @@ void checkDshot(){
output_timer_prescaler=1;
IC_TIMER_REGISTER->CNT = 0xffff;
buffer_divider = 44;
- buffer_padding = 7;
+ // buffer_padding = 7;
buffersize = 32;
inputSet = 1;
}
diff --git a/Mcu/l431/Inc/ADC.h b/Mcu/l431/Inc/ADC.h
new file mode 100644
index 00000000..228140c3
--- /dev/null
+++ b/Mcu/l431/Inc/ADC.h
@@ -0,0 +1,29 @@
+/*
+ * ADC.h
+ *
+ * Created on: May 20, 2020
+ * Author: Alka
+ */
+
+#include "main.h"
+#include "targets.h"
+
+
+#ifndef ADC_H_
+#define ADC_H_
+
+
+
+void ADC_DMA_Callback();
+void enableADC_DMA();
+void activateADC();
+void ADC_Init(void);
+
+void Configure_DMA();
+
+void Configure_ADC();
+
+void Activate_ADC();
+
+
+#endif /* ADC_H_ */
diff --git a/Mcu/l431/Inc/IO.h b/Mcu/l431/Inc/IO.h
new file mode 100644
index 00000000..1e7a3d84
--- /dev/null
+++ b/Mcu/l431/Inc/IO.h
@@ -0,0 +1,28 @@
+/*
+ * IO.h
+ *
+ * Created on: Sep. 26, 2020
+ * Author: Alka
+ */
+
+#ifndef IO_H_
+#define IO_H_
+
+#endif /* IO_H_ */
+
+
+#include "main.h"
+
+void changeToOutput();
+void changeToInput();
+void receiveDshotDma();
+void sendDshotDma();
+void detectInput();
+
+extern char inputSet;
+extern char dshot;
+extern char servoPwm;
+extern char send_telemetry;
+extern uint8_t degrees_celsius;
+
+extern uint16_t ADC_raw_volts;
diff --git a/Mcu/l431/Inc/WS2812.h b/Mcu/l431/Inc/WS2812.h
new file mode 100644
index 00000000..e34311ac
--- /dev/null
+++ b/Mcu/l431/Inc/WS2812.h
@@ -0,0 +1,23 @@
+/*
+ * WS2812.h
+ *
+ * Created on: Sep 9, 2020
+ * Author: Alka
+ */
+
+#ifndef INC_WS2812_H_
+#define INC_WS2812_H_
+
+#include "main.h"
+
+
+
+
+void send_LED_DMA();
+void WS2812_Init(void);
+void send_LED_RGB(uint8_t red, uint8_t green, uint8_t blue);
+
+extern char dma_busy;
+
+
+#endif /* INC_WS2812_H_ */
\ No newline at end of file
diff --git a/Mcu/l431/Inc/comparator.h b/Mcu/l431/Inc/comparator.h
new file mode 100644
index 00000000..a70c0bdb
--- /dev/null
+++ b/Mcu/l431/Inc/comparator.h
@@ -0,0 +1,22 @@
+/*
+ * comparator.h
+ *
+ * Created on: Sep. 26, 2020
+ * Author: Alka
+ */
+
+#ifndef COMPARATOR_H_
+#define COMPARATOR_H_
+
+
+
+#endif /* COMPARATOR_H_ */
+
+#include "main.h"
+
+void maskPhaseInterrupts();
+void changeCompInput();
+void enableCompInterrupts();
+
+extern char rising;
+extern char step;
diff --git a/Mcu/l431/Inc/eeprom.h b/Mcu/l431/Inc/eeprom.h
new file mode 100644
index 00000000..4c1f0c7b
--- /dev/null
+++ b/Mcu/l431/Inc/eeprom.h
@@ -0,0 +1,20 @@
+/*
+ * bootloader.h
+ *
+ * Created on: Mar. 25, 2020
+ * Author: Alka
+ */
+#include "main.h"
+#ifndef INC_EEPROM_H_
+#define INC_EEPROM_H_
+
+
+
+#endif /* INC_BOOTLOADER_H_ */
+
+
+//void save_to_flash(uint8_t *data);
+//void read_flash(uint8_t* data, uint32_t address);
+//void save_to_flash_bin(uint8_t *data, int length, uint32_t add);
+void read_flash_bin(uint8_t* data , uint32_t add ,int out_buff_len);
+void save_flash_nolib(uint8_t *data, int length, uint32_t add);
diff --git a/Mcu/l431/Inc/main.h b/Mcu/l431/Inc/main.h
new file mode 100644
index 00000000..765aafd6
--- /dev/null
+++ b/Mcu/l431/Inc/main.h
@@ -0,0 +1,88 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.h
+ * @brief : Header for main.c file.
+ * This file contains the common defines of the application.
+ ******************************************************************************
+ * @attention
+ *
+ *
© Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32g0xx_ll_adc.h"
+#include "stm32g0xx_ll_comp.h"
+#include "stm32g0xx_ll_exti.h"
+#include "stm32g0xx_ll_dma.h"
+#include "stm32g0xx_ll_iwdg.h"
+#include "stm32g0xx_ll_rcc.h"
+#include "stm32g0xx_ll_bus.h"
+#include "stm32g0xx_ll_system.h"
+#include "stm32g0xx_ll_cortex.h"
+#include "stm32g0xx_ll_utils.h"
+#include "stm32g0xx_ll_pwr.h"
+#include "stm32g0xx_ll_tim.h"
+#include "stm32g0xx_ll_gpio.h"
+#include "stm32g0xx_ll_usart.h"
+
+#if defined(USE_FULL_ASSERT)
+#include "stm32_assert.h"
+#endif /* USE_FULL_ASSERT */
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void Error_Handler(void);
+
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+/* Private defines -----------------------------------------------------------*/
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MAIN_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/Mcu/l431/Inc/peripherals.h b/Mcu/l431/Inc/peripherals.h
new file mode 100644
index 00000000..b8e1d74e
--- /dev/null
+++ b/Mcu/l431/Inc/peripherals.h
@@ -0,0 +1,33 @@
+/*
+ * peripherals.h
+ *
+ * Created on: Sep. 26, 2020
+ * Author: Alka
+ */
+
+#ifndef PERIPHERALS_H_
+#define PERIPHERALS_H_
+
+
+
+#endif /* PERIPHERALS_H_ */
+
+#include "main.h"
+
+void initAfterJump(void);
+void initCorePeripherals(void);
+void SystemClock_Config(void);
+void MX_GPIO_Init(void);
+void MX_DMA_Init(void);
+void MX_ADC1_Init(void);
+void MX_COMP2_Init(void);
+void MX_COMP1_Init(void);
+void MX_TIM1_Init(void);
+void MX_TIM2_Init(void);
+void MX_TIM3_Init(void);
+void MX_TIM14_Init(void);
+void MX_TIM17_Init(void);
+void MX_TIM16_Init(void);
+void MX_IWDG_Init(void);
+void MX_TIM6_Init(void);
+
diff --git a/Mcu/l431/Inc/serial_telemetry.h b/Mcu/l431/Inc/serial_telemetry.h
new file mode 100644
index 00000000..dba4e33f
--- /dev/null
+++ b/Mcu/l431/Inc/serial_telemetry.h
@@ -0,0 +1,24 @@
+/*
+ * serial_telemetry.h
+ *
+ * Created on: May 13, 2020
+ * Author: Alka
+ */
+
+
+#include "main.h"
+
+#ifndef SERIAL_TELEMETRY_H_
+#define SERIAL_TELEMETRY_H_
+
+void makeTelemPackage(uint8_t temp,
+ uint16_t voltage,
+ uint16_t current,
+ uint16_t consumption,
+ uint16_t e_rpm);
+
+
+void telem_UART_Init(void);
+void send_telem_DMA();
+
+#endif /* SERIAL_TELEMETRY_H_ */
diff --git a/Mcu/l431/Inc/stm32_assert.h b/Mcu/l431/Inc/stm32_assert.h
new file mode 100644
index 00000000..e16456da
--- /dev/null
+++ b/Mcu/l431/Inc/stm32_assert.h
@@ -0,0 +1,53 @@
+/**
+ ******************************************************************************
+ * @file stm32_assert.h
+ * @brief STM32 assert file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2018 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32_ASSERT_H
+#define __STM32_ASSERT_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Includes ------------------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr: If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(uint8_t* file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32_ASSERT_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/Mcu/l431/Inc/stm32g0xx_it.h b/Mcu/l431/Inc/stm32g0xx_it.h
new file mode 100644
index 00000000..8ea5da0e
--- /dev/null
+++ b/Mcu/l431/Inc/stm32g0xx_it.h
@@ -0,0 +1,73 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32g0xx_it.h
+ * @brief This file contains the headers of the interrupt handlers.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32G0xx_IT_H
+#define __STM32G0xx_IT_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void NMI_Handler(void);
+void HardFault_Handler(void);
+void SVC_Handler(void);
+void PendSV_Handler(void);
+void SysTick_Handler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_3_IRQHandler(void);
+void ADC1_COMP_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM14_IRQHandler(void);
+void TIM16_IRQHandler(void);
+void USART1_IRQHandler(void);
+/* USER CODE BEGIN EFP */
+void DMA1_Ch4_7_DMAMUX1_OVR_IRQHandler(void);
+void TIM6_DAC_LPTIM1_IRQHandler(void);
+/* USER CODE END EFP */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32G0xx_IT_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/Mcu/l431/Src/ADC.c b/Mcu/l431/Src/ADC.c
new file mode 100644
index 00000000..c24dc081
--- /dev/null
+++ b/Mcu/l431/Src/ADC.c
@@ -0,0 +1,212 @@
+/*
+ * ADC.c
+ *
+ * Created on: May 20, 2020
+ * Author: Alka
+ */
+#include "ADC.h"
+
+
+#ifdef USE_ADC_INPUT
+uint16_t ADCDataDMA[4];
+#else
+uint16_t ADCDataDMA[3];
+#endif
+
+
+extern uint16_t ADC_raw_temp;
+extern uint16_t ADC_raw_volts;
+extern uint16_t ADC_raw_current;
+extern uint16_t ADC_raw_input;
+
+#define ADC_DELAY_CALIB_ENABLE_CPU_CYCLES (LL_ADC_DELAY_CALIB_ENABLE_ADC_CYCLES * 64)
+
+
+
+void ADC_DMA_Callback(){ // read dma buffer and set extern variables
+
+#ifdef USE_ADC_INPUT
+ ADC_raw_temp = ADCDataDMA[3];
+ ADC_raw_volts = ADCDataDMA[1]/2;
+ ADC_raw_current =ADCDataDMA[2];
+ ADC_raw_input = ADCDataDMA[0];
+
+
+#else
+ADC_raw_temp = ADCDataDMA[2];
+ADC_raw_volts = ADCDataDMA[1];
+ADC_raw_current = ADCDataDMA[0];
+#endif
+}
+
+
+
+void enableADC_DMA(){ // enables channel
+
+ NVIC_SetPriority(DMA1_Channel2_3_IRQn, 3);
+ NVIC_EnableIRQ(DMA1_Channel2_3_IRQn);
+
+ LL_DMA_ConfigAddresses(DMA1,
+ LL_DMA_CHANNEL_2,
+ LL_ADC_DMA_GetRegAddr(ADC1, LL_ADC_DMA_REG_REGULAR_DATA),
+ (uint32_t)&ADCDataDMA,
+ LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
+
+ /* Set DMA transfer size */
+#ifdef USE_ADC_INPUT
+ LL_DMA_SetDataLength(DMA1,
+ LL_DMA_CHANNEL_2,
+ 4);
+#else
+ LL_DMA_SetDataLength(DMA1,
+ LL_DMA_CHANNEL_2,
+ 3);
+
+#endif
+ /* Enable DMA transfer interruption: transfer complete */
+ LL_DMA_EnableIT_TC(DMA1,
+ LL_DMA_CHANNEL_2);
+
+ /* Enable DMA transfer interruption: transfer error */
+ LL_DMA_EnableIT_TE(DMA1,
+ LL_DMA_CHANNEL_2);
+
+ /*## Activation of DMA #####################################################*/
+ /* Enable the DMA transfer */
+ LL_DMA_EnableChannel(DMA1,
+ LL_DMA_CHANNEL_2);
+}
+
+void activateADC(void)
+{
+ __IO uint32_t wait_loop_index = 0U;
+ __IO uint32_t backup_setting_adc_dma_transfer = 0U;
+
+ if (LL_ADC_IsEnabled(ADC1) == 0)
+ {
+ /* Enable ADC internal voltage regulator */
+ LL_ADC_EnableInternalRegulator(ADC1);
+ wait_loop_index = ((LL_ADC_DELAY_INTERNAL_REGUL_STAB_US * (SystemCoreClock / (100000 * 2))) / 10);
+ while(wait_loop_index != 0)
+ {
+ wait_loop_index--;
+ }
+ backup_setting_adc_dma_transfer = LL_ADC_REG_GetDMATransfer(ADC1);
+ LL_ADC_REG_SetDMATransfer(ADC1, LL_ADC_REG_DMA_TRANSFER_NONE);
+
+ /* Run ADC self calibration */
+ LL_ADC_StartCalibration(ADC1);
+
+ /* Poll for ADC effectively calibrated */
+
+ while (LL_ADC_IsCalibrationOnGoing(ADC1) != 0)
+ {
+ }
+ /* Restore ADC DMA transfer request after calibration */
+ LL_ADC_REG_SetDMATransfer(ADC1, backup_setting_adc_dma_transfer);
+
+ /* Delay between ADC end of calibration and ADC enable. */
+ /* Note: Variable divided by 2 to compensate partially */
+ /* CPU processing cycles (depends on compilation optimization). */
+ wait_loop_index = (ADC_DELAY_CALIB_ENABLE_CPU_CYCLES >> 1);
+ while(wait_loop_index != 0)
+ {
+ wait_loop_index--;
+ }
+ /* Enable ADC */
+ LL_ADC_Enable(ADC1);
+ while (LL_ADC_IsActiveFlag_ADRDY(ADC1) == 0)
+ {
+ }
+ ADC->CCR |= ADC_CCR_TSEN;
+ }
+
+}
+void ADC_Init(void)
+{
+
+ LL_ADC_REG_InitTypeDef ADC_REG_InitStruct = {0};
+ LL_ADC_InitTypeDef ADC_InitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_ADC);
+
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
+ /**ADC1 GPIO Configuration
+ PA4 ------> ADC1_IN4
+ PA6 ------> ADC1_IN6
+ */
+ GPIO_InitStruct.Pin = VOLTAGE_ADC_PIN;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+
+ GPIO_InitStruct.Pin = CURRENT_ADC_PIN;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+
+ /* ADC1 DMA Init */
+
+ /* ADC1 Init */
+ LL_DMA_SetPeriphRequest(DMA1, LL_DMA_CHANNEL_2, LL_DMAMUX_REQ_ADC1);
+
+ LL_DMA_SetDataTransferDirection(DMA1, LL_DMA_CHANNEL_2, LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
+
+ LL_DMA_SetChannelPriorityLevel(DMA1, LL_DMA_CHANNEL_2, LL_DMA_PRIORITY_HIGH);
+
+ LL_DMA_SetMode(DMA1, LL_DMA_CHANNEL_2, LL_DMA_MODE_CIRCULAR);
+
+ LL_DMA_SetPeriphIncMode(DMA1, LL_DMA_CHANNEL_2, LL_DMA_PERIPH_NOINCREMENT);
+
+ LL_DMA_SetMemoryIncMode(DMA1, LL_DMA_CHANNEL_2, LL_DMA_MEMORY_INCREMENT);
+
+ LL_DMA_SetPeriphSize(DMA1, LL_DMA_CHANNEL_2, LL_DMA_PDATAALIGN_WORD);
+
+ LL_DMA_SetMemorySize(DMA1, LL_DMA_CHANNEL_2, LL_DMA_MDATAALIGN_HALFWORD);
+
+ /* USER CODE BEGIN ADC1_Init 1 */
+
+ /* USER CODE END ADC1_Init 1 */
+ /** Configure Regular Channel
+ */
+ LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(ADC1), LL_ADC_CHANNEL_TEMPSENSOR);
+ /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
+ */
+ ADC_REG_InitStruct.TriggerSource = LL_ADC_REG_TRIG_SOFTWARE;
+ ADC_REG_InitStruct.SequencerLength = LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS;
+ ADC_REG_InitStruct.SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE;
+ ADC_REG_InitStruct.ContinuousMode = LL_ADC_REG_CONV_SINGLE;
+ ADC_REG_InitStruct.DMATransfer = LL_ADC_REG_DMA_TRANSFER_LIMITED;
+ ADC_REG_InitStruct.Overrun = LL_ADC_REG_OVR_DATA_PRESERVED;
+ LL_ADC_REG_Init(ADC1, &ADC_REG_InitStruct);
+ //LL_ADC_REG_SetTriggerEdge(ADC1, LL_ADC_REG_TRIG_EXT_FALLING);
+ LL_ADC_SetOverSamplingScope(ADC1, LL_ADC_OVS_DISABLE);
+ LL_ADC_SetTriggerFrequencyMode(ADC1, LL_ADC_CLOCK_FREQ_MODE_LOW);
+ LL_ADC_REG_SetSequencerConfigurable(ADC1, LL_ADC_REG_SEQ_CONFIGURABLE);
+ LL_ADC_SetClock(ADC1, LL_ADC_CLOCK_ASYNC_DIV4);
+ LL_ADC_SetSamplingTimeCommonChannels(ADC1, LL_ADC_SAMPLINGTIME_COMMON_1, LL_ADC_SAMPLINGTIME_19CYCLES_5);
+ LL_ADC_SetSamplingTimeCommonChannels(ADC1, LL_ADC_SAMPLINGTIME_COMMON_2, LL_ADC_SAMPLINGTIME_160CYCLES_5);
+ LL_ADC_DisableIT_EOC(ADC1);
+ LL_ADC_DisableIT_EOS(ADC1);
+
+ ADC_InitStruct.Resolution = LL_ADC_RESOLUTION_12B;
+ ADC_InitStruct.DataAlignment = LL_ADC_DATA_ALIGN_RIGHT;
+ ADC_InitStruct.LowPowerMode = LL_ADC_LP_MODE_NONE;
+ LL_ADC_Init(ADC1, &ADC_InitStruct);
+
+ LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, CURRENT_ADC_CHANNEL);
+ LL_ADC_SetChannelSamplingTime(ADC1, CURRENT_ADC_CHANNEL, LL_ADC_SAMPLINGTIME_COMMON_1);
+
+ LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_2, VOLTAGE_ADC_CHANNEL);
+ LL_ADC_SetChannelSamplingTime(ADC1, VOLTAGE_ADC_CHANNEL, LL_ADC_SAMPLINGTIME_COMMON_1);
+
+ LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_3, LL_ADC_CHANNEL_TEMPSENSOR);
+ LL_ADC_SetChannelSamplingTime(ADC1, LL_ADC_CHANNEL_TEMPSENSOR, LL_ADC_SAMPLINGTIME_COMMON_2);
+
+}
+
diff --git a/Mcu/l431/Src/IO.c b/Mcu/l431/Src/IO.c
new file mode 100644
index 00000000..cfe08f35
--- /dev/null
+++ b/Mcu/l431/Src/IO.c
@@ -0,0 +1,180 @@
+/*
+ * IO.c
+ *
+ * Created on: Sep. 26, 2020
+ * Author: Alka
+ */
+
+#include "targets.h"
+#include "IO.h"
+#include "dshot.h"
+#include "serial_telemetry.h"
+#include "functions.h"
+#include "common.h"
+
+//int max_servo_deviation = 250;
+//int servorawinput;
+char ic_timer_prescaler = 1;
+char output_timer_prescaler;
+int buffersize = 32;
+int smallestnumber = 20000;
+uint32_t dma_buffer[64] = {0};
+char out_put = 0;
+char buffer_divider = 44;
+int dshot_runout_timer = 62500;
+uint16_t average_signal_pulse = 0;
+
+
+
+void changeToInput(){
+ LL_DMA_SetDataTransferDirection(DMA1, INPUT_DMA_CHANNEL, LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
+#ifdef USE_TIMER_3_CHANNEL_1
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM3); // de-init timer 2
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM3);
+ IC_TIMER_REGISTER->CCMR1 = 0x1;
+ IC_TIMER_REGISTER->CCER = 0xa;
+#endif
+#ifdef USE_TIMER_16_CHANNEL_1
+ LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM16); // de-init timer 2
+ LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM16);
+ IC_TIMER_REGISTER->CCMR1 = 0x1;
+ IC_TIMER_REGISTER->CCER = 0xa;
+#endif
+
+ IC_TIMER_REGISTER->PSC = ic_timer_prescaler;
+ IC_TIMER_REGISTER->ARR = 0xFFFF;
+ LL_TIM_GenerateEvent_UPDATE(IC_TIMER_REGISTER);
+ out_put = 0;
+}
+
+
+
+void receiveDshotDma(){
+ changeToInput();
+ IC_TIMER_REGISTER->CNT = 0;
+ LL_DMA_ConfigAddresses(DMA1, INPUT_DMA_CHANNEL, (uint32_t)&IC_TIMER_REGISTER->CCR1, (uint32_t)&dma_buffer, LL_DMA_GetDataTransferDirection(DMA1, INPUT_DMA_CHANNEL));
+ LL_DMA_SetDataLength(DMA1, INPUT_DMA_CHANNEL, buffersize);
+ LL_DMA_EnableIT_TC(DMA1, INPUT_DMA_CHANNEL);
+ LL_DMA_EnableIT_TE(DMA1, INPUT_DMA_CHANNEL);
+ LL_DMA_EnableChannel(DMA1, INPUT_DMA_CHANNEL);
+
+ LL_TIM_EnableDMAReq_CC1(IC_TIMER_REGISTER);
+ LL_TIM_EnableDMAReq_CC1(IC_TIMER_REGISTER);
+
+ LL_TIM_CC_EnableChannel(IC_TIMER_REGISTER, IC_TIMER_CHANNEL);
+ LL_TIM_EnableCounter(IC_TIMER_REGISTER);
+ // TIM16->PSC = 1;
+
+}
+void changeToOutput(){
+ LL_DMA_SetDataTransferDirection(DMA1, INPUT_DMA_CHANNEL, LL_DMA_DIRECTION_MEMORY_TO_PERIPH);
+
+#ifdef USE_TIMER_3_CHANNEL_1
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM3); // de-init timer 2
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM3);
+ IC_TIMER_REGISTER->CCMR1 = 0x60;
+ IC_TIMER_REGISTER->CCER = 0x3;
+#endif
+#ifdef USE_TIMER_16_CHANNEL_1
+ LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM16); // de-init timer 2
+ LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM16);
+ IC_TIMER_REGISTER->CCMR1 = 0x60;
+ IC_TIMER_REGISTER->CCER = 0x3;
+#endif
+
+
+ IC_TIMER_REGISTER->PSC = output_timer_prescaler;
+ IC_TIMER_REGISTER->ARR = 92;
+ out_put = 1;
+ LL_TIM_GenerateEvent_UPDATE(IC_TIMER_REGISTER);
+}
+
+void sendDshotDma(){
+ changeToOutput();
+ LL_DMA_ConfigAddresses(DMA1, INPUT_DMA_CHANNEL, (uint32_t)&gcr, (uint32_t)&IC_TIMER_REGISTER->CCR1, LL_DMA_GetDataTransferDirection(DMA1, INPUT_DMA_CHANNEL));
+
+ LL_DMA_SetDataLength(DMA1, INPUT_DMA_CHANNEL, 30);
+ LL_DMA_EnableIT_TC(DMA1, INPUT_DMA_CHANNEL);
+ LL_DMA_EnableIT_TE(DMA1, INPUT_DMA_CHANNEL);
+ LL_DMA_EnableChannel(DMA1, INPUT_DMA_CHANNEL);
+
+
+ LL_TIM_EnableDMAReq_CC1(IC_TIMER_REGISTER);
+
+ LL_TIM_CC_EnableChannel(IC_TIMER_REGISTER, IC_TIMER_CHANNEL);
+ LL_TIM_EnableAllOutputs(IC_TIMER_REGISTER);
+ LL_TIM_EnableCounter(IC_TIMER_REGISTER);
+
+}
+
+
+void checkDshot(){
+ if ((smallestnumber > 3)&&(smallestnumber < 32)){
+ ic_timer_prescaler= 0;
+ output_timer_prescaler=0;
+ dshot = 1;
+ buffer_divider = 65;
+ dshot_runout_timer = 65000;
+ armed_count_threshold = 10000;
+ buffersize = 32;
+ inputSet = 1;
+ }
+ if ((smallestnumber > 32 )&&(smallestnumber < 110)){
+ dshot = 1;
+ ic_timer_prescaler=1;
+ output_timer_prescaler=1;
+ IC_TIMER_REGISTER->CNT = 0xffff;
+ buffer_divider = 65;
+ dshot_runout_timer = 65000;
+ armed_count_threshold = 10000;
+ buffersize = 32;
+ inputSet = 1;
+ }
+}
+
+void checkServo(){
+ if (smallestnumber > 1500){
+ servoPwm = 1;
+ ic_timer_prescaler=63;
+ armed_count_threshold = 100;
+ buffersize = 2;
+ inputSet = 1;
+ }
+}
+
+
+void detectInput(){
+ smallestnumber = 20000;
+ average_signal_pulse = 0;
+ int lastnumber = dma_buffer[0];
+
+
+ for ( int j = 1 ; j < 31; j++){
+ if(dma_buffer[j] - lastnumber > 0 ){
+ if((dma_buffer[j] - lastnumber) < smallestnumber){
+
+ smallestnumber = dma_buffer[j] - lastnumber;
+
+ }
+
+ average_signal_pulse += (dma_buffer[j] - lastnumber);
+ }
+ lastnumber = dma_buffer[j];
+ }
+ average_signal_pulse = average_signal_pulse/32 ;
+
+if(dshot == 1){
+ checkDshot();
+}
+if(servoPwm == 1){
+ checkServo();
+}
+
+if(!dshot && !servoPwm){
+ checkDshot();
+ checkServo();
+}
+
+}
+
+
diff --git a/Mcu/l431/Src/WS2812.c b/Mcu/l431/Src/WS2812.c
new file mode 100644
index 00000000..c4e3b73e
--- /dev/null
+++ b/Mcu/l431/Src/WS2812.c
@@ -0,0 +1,128 @@
+/*
+ * WS2812.c
+ *
+ * Created on: Sep 9, 2020
+ * Author: Alka
+ */
+
+#include "WS2812.h"
+
+char dma_busy;
+uint16_t led_Buffer[24] = {20,20,20,20,20,20,20,20,
+ 60,60,60,60,60,60,60,60,
+ 20,20,20,20,20,20,20,20};
+
+void send_LED_DMA(){
+ dma_busy = 1;
+ TIM16->CNT = 0;
+ LL_DMA_ConfigAddresses(DMA1, LL_DMA_CHANNEL_6, (uint32_t)&led_Buffer, (uint32_t)&TIM16->CCR1, LL_DMA_GetDataTransferDirection(DMA1, LL_DMA_CHANNEL_6));
+ LL_DMA_SetDataLength(DMA1, LL_DMA_CHANNEL_6, 24);
+ LL_DMA_EnableIT_TC(DMA1, LL_DMA_CHANNEL_6);
+ LL_DMA_EnableIT_TE(DMA1, LL_DMA_CHANNEL_6);
+ LL_DMA_EnableChannel(DMA1, LL_DMA_CHANNEL_6);
+ LL_TIM_EnableDMAReq_CC1(TIM16);
+ LL_TIM_CC_EnableChannel(TIM16, LL_TIM_CHANNEL_CH1);
+ LL_TIM_EnableAllOutputs(TIM16);
+ LL_TIM_EnableCounter(TIM16);
+}
+
+void send_LED_RGB(uint8_t red, uint8_t green, uint8_t blue){
+if(!dma_busy){
+uint32_t twenty_four_bit_color_number = green << 16 | red << 8 | blue ;
+
+
+for(int i = 0; i < 24 ; i ++){
+ led_Buffer[i] = (((twenty_four_bit_color_number >> (23 - i))&1) * 40) + 20;
+}
+
+send_LED_DMA();
+}
+}
+
+
+
+
+void WS2812_Init(void)
+{
+
+ /* USER CODE BEGIN TIM16_Init 0 */
+ NVIC_SetPriority(DMA1_Ch4_7_DMAMUX1_OVR_IRQn, 3);
+ NVIC_EnableIRQ(DMA1_Ch4_7_DMAMUX1_OVR_IRQn);
+ /* USER CODE END TIM16_Init 0 */
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+ LL_TIM_OC_InitTypeDef TIM_OC_InitStruct = {0};
+ LL_TIM_BDTR_InitTypeDef TIM_BDTRInitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM16);
+
+ /* TIM16 DMA Init */
+
+ /* TIM16_CH1 Init */
+ LL_DMA_SetPeriphRequest(DMA1, LL_DMA_CHANNEL_6, LL_DMAMUX_REQ_TIM16_CH1);
+
+ LL_DMA_SetDataTransferDirection(DMA1, LL_DMA_CHANNEL_6, LL_DMA_DIRECTION_MEMORY_TO_PERIPH);
+
+ LL_DMA_SetChannelPriorityLevel(DMA1, LL_DMA_CHANNEL_6, LL_DMA_PRIORITY_HIGH);
+
+ LL_DMA_SetMode(DMA1, LL_DMA_CHANNEL_6, LL_DMA_MODE_NORMAL);
+
+ LL_DMA_SetPeriphIncMode(DMA1, LL_DMA_CHANNEL_6, LL_DMA_PERIPH_NOINCREMENT);
+
+ LL_DMA_SetMemoryIncMode(DMA1, LL_DMA_CHANNEL_6, LL_DMA_MEMORY_INCREMENT);
+
+ LL_DMA_SetPeriphSize(DMA1, LL_DMA_CHANNEL_6, LL_DMA_PDATAALIGN_HALFWORD);
+
+ LL_DMA_SetMemorySize(DMA1, LL_DMA_CHANNEL_6, LL_DMA_MDATAALIGN_HALFWORD);
+
+ /* USER CODE BEGIN TIM16_Init 1 */
+
+ /* USER CODE END TIM16_Init 1 */
+ TIM_InitStruct.Prescaler = 0;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_DOWN;
+ TIM_InitStruct.Autoreload = 79;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ TIM_InitStruct.RepetitionCounter = 0;
+ LL_TIM_Init(TIM16, &TIM_InitStruct);
+ LL_TIM_EnableARRPreload(TIM16);
+ LL_TIM_OC_EnablePreload(TIM16, LL_TIM_CHANNEL_CH1);
+ TIM_OC_InitStruct.OCMode = LL_TIM_OCMODE_PWM1;
+ TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.CompareValue = 0;
+ TIM_OC_InitStruct.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
+ TIM_OC_InitStruct.OCNPolarity = LL_TIM_OCPOLARITY_HIGH;
+ TIM_OC_InitStruct.OCIdleState = LL_TIM_OCIDLESTATE_LOW;
+ TIM_OC_InitStruct.OCNIdleState = LL_TIM_OCIDLESTATE_LOW;
+ LL_TIM_OC_Init(TIM16, LL_TIM_CHANNEL_CH1, &TIM_OC_InitStruct);
+ LL_TIM_OC_DisableFast(TIM16, LL_TIM_CHANNEL_CH1);
+ TIM_BDTRInitStruct.OSSRState = LL_TIM_OSSR_DISABLE;
+ TIM_BDTRInitStruct.OSSIState = LL_TIM_OSSI_DISABLE;
+ TIM_BDTRInitStruct.LockLevel = LL_TIM_LOCKLEVEL_OFF;
+ TIM_BDTRInitStruct.DeadTime = 0;
+ TIM_BDTRInitStruct.BreakState = LL_TIM_BREAK_DISABLE;
+ TIM_BDTRInitStruct.BreakPolarity = LL_TIM_BREAK_POLARITY_HIGH;
+ TIM_BDTRInitStruct.BreakFilter = LL_TIM_BREAK_FILTER_FDIV1;
+ TIM_BDTRInitStruct.AutomaticOutput = LL_TIM_AUTOMATICOUTPUT_DISABLE;
+ LL_TIM_BDTR_Init(TIM16, &TIM_BDTRInitStruct);
+ /* USER CODE BEGIN TIM16_Init 2 */
+// NVIC_SetPriority(TIM16_IRQn, 0);
+// NVIC_EnableIRQ(TIM16_IRQn);
+ /* USER CODE END TIM16_Init 2 */
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+ /**TIM16 GPIO Configuration
+ PB8 ------> TIM16_CH1
+ */
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_8;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ TIM16->CCER |= 1 << 0;
+}
diff --git a/Mcu/l431/Src/comparator.c b/Mcu/l431/Src/comparator.c
new file mode 100644
index 00000000..72b045bf
--- /dev/null
+++ b/Mcu/l431/Src/comparator.c
@@ -0,0 +1,161 @@
+///*
+// * comparator.c
+// *
+// * Created on: Sep. 26, 2020
+// * Author: Alka
+// */
+//
+//#include "comparator.h"
+//#include "targets.h"
+//
+//
+//void maskPhaseInterrupts(){
+// EXTI->IMR1 &= ~(1 << 18);
+// EXTI->RPR1 = EXTI_LINE;
+// EXTI->FPR1 = EXTI_LINE;
+//// LL_EXTI_ClearRisingFlag_0_31(EXTI_LINE);
+//// LL_EXTI_ClearFallingFlag_0_31(EXTI_LINE);
+//}
+//
+//void enableCompInterrupts(){
+// EXTI->IMR1 |= (1 << 18);
+//}
+//
+//void changeCompInput() {
+//// TIM3->CNT = 0;
+//// HAL_COMP_Stop_IT(&hcomp1); // done in comparator interrupt routine
+//
+//// LL_COMP_InitTypeDef COMP_InitStruct = {0};
+//
+//
+//
+// if (step == 1 || step == 4) { // c floating
+//
+// // LL_COMP_ConfigInputs(COMP2, PHASE_C_COMP , LL_COMP_INPUT_PLUS_IO3);
+//
+// COMP2->CSR = 0x100281;
+//
+// }
+//
+// if (step == 2 || step == 5) { // a floating
+//
+// // LL_COMP_ConfigInputs(COMP2, PHASE_A_COMP, LL_COMP_INPUT_PLUS_IO3);
+// COMP2->CSR = 0x100271;
+//
+//
+// }
+//
+// if (step == 3 || step == 6) { // b floating
+//
+// // LL_COMP_ConfigInputs(COMP2, PHASE_B_COMP, LL_COMP_INPUT_PLUS_IO3);
+// COMP2->CSR = 0x100261;
+// }
+// //COMP_InitStruct.InputPlus = LL_COMP_INPUT_PLUS_IO3;
+// //LL_COMP_Init(COMP2, &COMP_InitStruct);
+//
+// if (rising){
+//
+// // LL_EXTI_DisableRisingTrig_0_31(LL_EXTI_LINE_18);
+// // LL_EXTI_EnableFallingTrig_0_31(LL_EXTI_LINE_18);
+// EXTI->RTSR1 &= ~(LL_EXTI_LINE_18);
+// EXTI->FTSR1 |= LL_EXTI_LINE_18;
+//
+// // hcomp1.Init.TriggerMode = COMP_TRIGGERMODE_IT_FALLING; // polarity of comp output reversed
+// }else{ // falling bemf
+//
+// EXTI->RTSR1 |= LL_EXTI_LINE_18;
+// EXTI->FTSR1 &= ~(LL_EXTI_LINE_18);
+// // LL_EXTI_EnableRisingTrig_0_31(LL_EXTI_LINE_18);
+// // LL_EXTI_DisableFallingTrig_0_31(LL_EXTI_LINE_18);
+// // hcomp1.Init.TriggerMode = COMP_TRIGGERMODE_IT_RISING;
+// }
+//
+//// LL_COMP_Enable(COMP2);
+//}
+
+/*
+ * comparator.c
+ *
+ * Created on: Sep. 26, 2020
+ * Author: Alka
+ */
+
+#include "comparator.h"
+#include "targets.h"
+#include "common.h"
+
+COMP_TypeDef* active_COMP = COMP2;
+uint32_t current_EXTI_LINE = LL_EXTI_LINE_18;
+
+void maskPhaseInterrupts(){
+ EXTI->IMR1 &= ~(1 << 18);
+ LL_EXTI_ClearRisingFlag_0_31(LL_EXTI_LINE_18);
+ LL_EXTI_ClearFallingFlag_0_31(LL_EXTI_LINE_18);
+#ifdef N_VARIANT
+ EXTI->IMR1 &= ~(1 << 17);
+ LL_EXTI_ClearRisingFlag_0_31(LL_EXTI_LINE_17);
+ LL_EXTI_ClearFallingFlag_0_31(LL_EXTI_LINE_17);
+#endif
+
+}
+
+void enableCompInterrupts(){
+ EXTI->IMR1 |= current_EXTI_LINE;
+}
+
+void changeCompInput() {
+// TIM3->CNT = 0;
+// HAL_COMP_Stop_IT(&hcomp1); // done in comparator interrupt routine
+
+// LL_COMP_InitTypeDef COMP_InitStruct = {0};
+
+
+
+ if (step == 1 || step == 4) { // c floating
+#ifdef N_VARIANT
+ current_EXTI_LINE = PHASE_C_EXTI_LINE;
+ active_COMP = PHASE_C_COMP_NUMBER;
+#endif
+ LL_COMP_ConfigInputs(active_COMP, PHASE_C_COMP , LL_COMP_INPUT_PLUS_IO3);
+
+
+ }
+
+ if (step == 2 || step == 5) { // a floating
+#ifdef N_VARIANT
+ current_EXTI_LINE = PHASE_A_EXTI_LINE;
+ active_COMP = PHASE_A_COMP_NUMBER;
+#endif
+ LL_COMP_ConfigInputs(active_COMP, PHASE_A_COMP, LL_COMP_INPUT_PLUS_IO3);
+ }
+
+ if (step == 3 || step == 6) { // b floating
+#ifdef N_VARIANT
+ current_EXTI_LINE = PHASE_B_EXTI_LINE;
+ active_COMP = PHASE_B_COMP_NUMBER;
+#endif
+ LL_COMP_ConfigInputs(active_COMP, PHASE_B_COMP, LL_COMP_INPUT_PLUS_IO3);
+ }
+ //COMP_InitStruct.InputPlus = LL_COMP_INPUT_PLUS_IO3;
+ //LL_COMP_Init(COMP2, &COMP_InitStruct);
+
+ if (rising){
+
+ LL_EXTI_DisableRisingTrig_0_31(LL_EXTI_LINE_18);
+ LL_EXTI_DisableRisingTrig_0_31(LL_EXTI_LINE_17);
+ LL_EXTI_EnableFallingTrig_0_31(current_EXTI_LINE);
+
+ // hcomp1.Init.TriggerMode = COMP_TRIGGERMODE_IT_FALLING; // polarity of comp output reversed
+ }else{ // falling bemf
+
+
+ LL_EXTI_EnableRisingTrig_0_31(current_EXTI_LINE);
+ LL_EXTI_DisableFallingTrig_0_31(LL_EXTI_LINE_17);
+ LL_EXTI_DisableFallingTrig_0_31(LL_EXTI_LINE_18);
+ // hcomp1.Init.TriggerMode = COMP_TRIGGERMODE_IT_RISING;
+ }
+
+// LL_COMP_Enable(COMP2);
+}
+
+
diff --git a/Mcu/l431/Src/eeprom.c b/Mcu/l431/Src/eeprom.c
new file mode 100644
index 00000000..3aaac19e
--- /dev/null
+++ b/Mcu/l431/Src/eeprom.c
@@ -0,0 +1,88 @@
+/*
+ * bootloader.c
+ *
+ * Created on: Mar. 25, 2020
+ * Author: Alka
+ *
+ */
+
+#include "eeprom.h"
+#include
+
+
+#define page_size 0x800 // 2 kb for g071
+uint32_t FLASH_FKEY1 =0x45670123;
+uint32_t FLASH_FKEY2 =0xCDEF89AB;
+
+
+
+void save_flash_nolib(uint8_t *data, int length, uint32_t add){
+ uint32_t data_to_FLASH[length / 4];
+ memset(data_to_FLASH, 0, length / 4);
+ for(int i = 0; i < length / 4 ; i ++ ){
+ data_to_FLASH[i] = data[i*4+3] << 24 |data[i*4+2] << 16|data[i*4+1] << 8| data[i*4]; // make 16 bit
+ }
+ volatile uint32_t data_length = length / 4;
+
+ // unlock flash
+
+ while ((FLASH->SR & FLASH_SR_BSY1) != 0) {
+ /* add time-out*/
+ }
+ if ((FLASH->CR & FLASH_CR_LOCK) != 0) {
+ FLASH->KEYR = FLASH_FKEY1;
+ FLASH->KEYR = FLASH_FKEY2;
+ }
+
+ // erase page if address even divisable by 1024
+ if((add % 2048) == 0){
+
+
+ FLASH->CR |= FLASH_CR_PER;
+ FLASH->CR |= (add/2048) << 3;
+ FLASH->CR |= FLASH_CR_STRT;
+ while ((FLASH->SR & FLASH_SR_BSY1) != 0){
+ /* add time-out */
+ }
+ if ((FLASH->SR & FLASH_SR_EOP) != 0){
+ FLASH->SR = FLASH_SR_EOP;
+ }
+ else{
+ /* error */
+ }
+ FLASH->CR &= ~FLASH_CR_PER;
+
+ }
+
+ volatile uint32_t write_cnt=0, index=0;
+ while(index < data_length)
+ {
+
+ FLASH->CR |= FLASH_CR_PG; /* (1) */
+ *(__IO uint32_t*)(add+write_cnt) = data_to_FLASH[index];
+ *(__IO uint32_t*)(add+write_cnt+4) = data_to_FLASH[index+1];
+ while ((FLASH->SR & FLASH_SR_BSY1) != 0){ /* add time-out */
+ }
+ if ((FLASH->SR & FLASH_SR_EOP) != 0){
+ FLASH->SR = FLASH_SR_EOP;
+ }
+ else{
+ /* error */
+ }
+ FLASH->CR &= ~FLASH_CR_PG;
+ write_cnt += 8;
+ index +=2;
+ }
+ SET_BIT(FLASH->CR, FLASH_CR_LOCK);
+}
+
+
+
+
+void read_flash_bin(uint8_t* data , uint32_t add , int out_buff_len){
+ //volatile uint32_t read_data;
+ for (int i = 0; i < out_buff_len ; i ++){
+ data[i] = *(uint8_t*)(add + i);
+ }
+}
+
diff --git a/Mcu/l431/Src/peripherals.c b/Mcu/l431/Src/peripherals.c
new file mode 100644
index 00000000..c363bb35
--- /dev/null
+++ b/Mcu/l431/Src/peripherals.c
@@ -0,0 +1,735 @@
+/*
+ * peripherals.c
+ *
+ * Created on: Sep. 26, 2020
+ * Author: Alka
+ */
+
+
+// PERIPHERAL SETUP
+
+#include "peripherals.h"
+#include "targets.h"
+#include "serial_telemetry.h"
+
+#ifdef USE_LED_STRIP
+#include "WS2812.h"
+#endif
+
+//extern uint16_t DEAD_TIME;
+
+
+void initCorePeripherals(void){
+
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SYSCFG);
+ LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_PWR);
+ LL_SYSCFG_EnablePinRemap(LL_SYSCFG_PIN_RMP_PA11);
+ LL_SYSCFG_EnablePinRemap(LL_SYSCFG_PIN_RMP_PA12);
+ FLASH->ACR |= FLASH_ACR_PRFTEN; //// prefetch buffer enable
+ SystemClock_Config();
+ MX_GPIO_Init();
+ MX_DMA_Init();
+ MX_COMP2_Init();
+ MX_TIM1_Init();
+ MX_TIM2_Init();
+#ifdef USE_TIMER_3_CHANNEL_1
+ MX_TIM3_Init();
+#endif
+#ifdef USE_TIMER_16_CHANNEL_1
+ MX_TIM16_Init();
+#endif
+#ifdef N_VARIANT
+ MX_COMP1_Init();
+#endif
+ MX_TIM14_Init();
+ MX_TIM17_Init();
+ MX_TIM6_Init();
+ telem_UART_Init();
+#ifdef USE_LED_STRIP
+WS2812_Init();
+#endif
+
+}
+
+void initAfterJump(){
+
+ SCB->VTOR = 0x08001000;
+ __enable_irq();
+}
+
+void SystemClock_Config(void)
+{
+ LL_FLASH_SetLatency(LL_FLASH_LATENCY_2);
+ if(LL_FLASH_GetLatency() != LL_FLASH_LATENCY_2)
+ {
+ // Error_Handler();
+ };
+
+ /* HSI configuration and activation */
+ LL_RCC_HSI_Enable();
+ while(LL_RCC_HSI_IsReady() != 1)
+ {
+ };
+
+ /* LSI configuration and activation */
+ LL_RCC_LSI_Enable();
+ while(LL_RCC_LSI_IsReady() != 1)
+ {
+ };
+
+ /* Main PLL configuration and activation */
+ LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, LL_RCC_PLLM_DIV_1, 8, LL_RCC_PLLR_DIV_2);
+ LL_RCC_PLL_Enable();
+ LL_RCC_PLL_EnableDomain_SYS();
+ while(LL_RCC_PLL_IsReady() != 1)
+ {
+ };
+
+ /* Set AHB prescaler*/
+ LL_RCC_SetAHBPrescaler(LL_RCC_SYSCLK_DIV_1);
+
+ /* Sysclk activation on the main PLL */
+ LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL);
+ while(LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL)
+ {
+ };
+
+ /* Set APB1 prescaler*/
+ LL_RCC_SetAPB1Prescaler(LL_RCC_APB1_DIV_1);
+ LL_Init1msTick(64000000);
+ LL_SetSystemCoreClock(64000000);
+ /* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */
+ LL_SetSystemCoreClock(64000000);
+ LL_RCC_SetTIMClockSource(LL_RCC_TIM1_CLKSOURCE_PCLK1);
+ LL_RCC_SetADCClockSource(LL_RCC_ADC_CLKSOURCE_SYSCLK);
+}
+
+void MX_COMP1_Init(void)
+{
+
+ /* USER CODE BEGIN COMP2_Init 0 */
+
+ /* USER CODE END COMP2_Init 0 */
+
+ LL_COMP_InitTypeDef COMP_InitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+ /**COMP2 GPIO Configuration
+ PA2 ------> COMP2_INM
+ PA3 ------> COMP2_INP
+ */
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_0;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_1;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+
+ /* USER CODE BEGIN COMP2_Init 1 */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SYSCFG);
+ /* USER CODE END COMP2_Init 1 */
+ COMP_InitStruct.InputPlus = LL_COMP_INPUT_PLUS_IO3;
+ COMP_InitStruct.InputMinus = LL_COMP_INPUT_MINUS_IO3;
+ COMP_InitStruct.InputHysteresis = LL_COMP_HYSTERESIS_NONE;
+ COMP_InitStruct.OutputPolarity = LL_COMP_OUTPUTPOL_NONINVERTED;
+ COMP_InitStruct.OutputBlankingSource = LL_COMP_BLANKINGSRC_TIM1_OC5;
+ LL_COMP_Init(COMP1, &COMP_InitStruct);
+ LL_COMP_SetPowerMode(COMP1, LL_COMP_POWERMODE_HIGHSPEED);
+ LL_COMP_SetCommonWindowMode(__LL_COMP_COMMON_INSTANCE(COMP1), LL_COMP_WINDOWMODE_DISABLE);
+ LL_COMP_SetCommonWindowOutput(__LL_COMP_COMMON_INSTANCE(COMP1), LL_COMP_WINDOWOUTPUT_EACH_COMP);
+
+ /* Wait loop initialization and execution */
+ /* Note: Variable divided by 2 to compensate partially CPU processing cycles */
+ __IO uint32_t wait_loop_index = 0;
+ wait_loop_index = (LL_COMP_DELAY_VOLTAGE_SCALER_STAB_US * (SystemCoreClock / (1000000 * 2)));
+ while(wait_loop_index != 0)
+ {
+ wait_loop_index--;
+ }
+ LL_EXTI_DisableEvent_0_31(LL_EXTI_LINE_17);
+ LL_EXTI_DisableIT_0_31(LL_EXTI_LINE_17);
+ /* USER CODE BEGIN COMP2_Init 2 */
+ NVIC_SetPriority(ADC1_COMP_IRQn, 0);
+ NVIC_EnableIRQ(ADC1_COMP_IRQn);
+ //__NVIC_EnableIRQ;
+ /* USER CODE END COMP2_Init 2 */
+
+}
+
+
+
+
+void MX_COMP2_Init(void)
+{
+
+ /* USER CODE BEGIN COMP2_Init 0 */
+
+ /* USER CODE END COMP2_Init 0 */
+
+ LL_COMP_InitTypeDef COMP_InitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+ /**COMP2 GPIO Configuration
+ PA2 ------> COMP2_INM
+ PA3 ------> COMP2_INP
+ */
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_2;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_3;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+#ifndef N_VARIANT
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_3;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+#endif
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_7;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+
+ /* USER CODE BEGIN COMP2_Init 1 */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SYSCFG);
+ /* USER CODE END COMP2_Init 1 */
+ COMP_InitStruct.InputPlus = LL_COMP_INPUT_PLUS_IO3;
+ COMP_InitStruct.InputMinus = LL_COMP_INPUT_MINUS_IO3;
+ COMP_InitStruct.InputHysteresis = LL_COMP_HYSTERESIS_NONE;
+ COMP_InitStruct.OutputPolarity = LL_COMP_OUTPUTPOL_NONINVERTED;
+ COMP_InitStruct.OutputBlankingSource = LL_COMP_BLANKINGSRC_TIM1_OC5;
+ LL_COMP_Init(COMP2, &COMP_InitStruct);
+ LL_COMP_SetPowerMode(COMP2, LL_COMP_POWERMODE_HIGHSPEED);
+ LL_COMP_SetCommonWindowMode(__LL_COMP_COMMON_INSTANCE(COMP2), LL_COMP_WINDOWMODE_DISABLE);
+ LL_COMP_SetCommonWindowOutput(__LL_COMP_COMMON_INSTANCE(COMP2), LL_COMP_WINDOWOUTPUT_EACH_COMP);
+
+ /* Wait loop initialization and execution */
+ /* Note: Variable divided by 2 to compensate partially CPU processing cycles */
+ __IO uint32_t wait_loop_index = 0;
+ wait_loop_index = (LL_COMP_DELAY_VOLTAGE_SCALER_STAB_US * (SystemCoreClock / (1000000 * 2)));
+ while(wait_loop_index != 0)
+ {
+ wait_loop_index--;
+ }
+ LL_EXTI_DisableEvent_0_31(LL_EXTI_LINE_18);
+ LL_EXTI_DisableIT_0_31(LL_EXTI_LINE_18);
+ /* USER CODE BEGIN COMP2_Init 2 */
+ NVIC_SetPriority(ADC1_COMP_IRQn, 0);
+ NVIC_EnableIRQ(ADC1_COMP_IRQn);
+ //__NVIC_EnableIRQ;
+ /* USER CODE END COMP2_Init 2 */
+
+}
+
+/**
+ * @brief IWDG Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_IWDG_Init(void)
+{
+
+ /* USER CODE BEGIN IWDG_Init 0 */
+
+ /* USER CODE END IWDG_Init 0 */
+
+ /* USER CODE BEGIN IWDG_Init 1 */
+
+ /* USER CODE END IWDG_Init 1 */
+ LL_IWDG_Enable(IWDG);
+ LL_IWDG_EnableWriteAccess(IWDG);
+ LL_IWDG_SetPrescaler(IWDG, LL_IWDG_PRESCALER_4);
+ LL_IWDG_SetReloadCounter(IWDG, 4095);
+ while (LL_IWDG_IsReady(IWDG) != 1)
+ {
+ }
+
+ LL_IWDG_SetWindow(IWDG, 4095);
+ LL_IWDG_ReloadCounter(IWDG);
+ /* USER CODE BEGIN IWDG_Init 2 */
+
+ /* USER CODE END IWDG_Init 2 */
+
+}
+
+/**
+ * @brief TIM1 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_TIM1_Init(void)
+{
+
+ /* USER CODE BEGIN TIM1_Init 0 */
+
+ /* USER CODE END TIM1_Init 0 */
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+ LL_TIM_OC_InitTypeDef TIM_OC_InitStruct = {0};
+ LL_TIM_BDTR_InitTypeDef TIM_BDTRInitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM1);
+
+ /* USER CODE BEGIN TIM1_Init 1 */
+
+ /* USER CODE END TIM1_Init 1 */
+ TIM_InitStruct.Prescaler = 0;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 3000;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ TIM_InitStruct.RepetitionCounter = 0;
+ LL_TIM_Init(TIM1, &TIM_InitStruct);
+ LL_TIM_EnableARRPreload(TIM1);
+ LL_TIM_OC_EnablePreload(TIM1, LL_TIM_CHANNEL_CH1);
+#ifdef USE_SWAPPED_OUPUT
+ TIM_OC_InitStruct.OCMode = LL_TIM_OCMODE_PWM2;
+#else
+ TIM_OC_InitStruct.OCMode = LL_TIM_OCMODE_PWM1;
+#endif
+ TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.CompareValue = 0;
+ TIM_OC_InitStruct.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
+ TIM_OC_InitStruct.OCNPolarity = LL_TIM_OCPOLARITY_HIGH;
+ TIM_OC_InitStruct.OCIdleState = LL_TIM_OCIDLESTATE_LOW;
+ TIM_OC_InitStruct.OCNIdleState = LL_TIM_OCIDLESTATE_LOW;
+ LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH1, &TIM_OC_InitStruct);
+ LL_TIM_OC_DisableFast(TIM1, LL_TIM_CHANNEL_CH1);
+ LL_TIM_OC_EnablePreload(TIM1, LL_TIM_CHANNEL_CH2);
+ TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
+ LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH2, &TIM_OC_InitStruct);
+ LL_TIM_OC_DisableFast(TIM1, LL_TIM_CHANNEL_CH2);
+ LL_TIM_OC_EnablePreload(TIM1, LL_TIM_CHANNEL_CH3);
+ TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
+ LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH3, &TIM_OC_InitStruct);
+ LL_TIM_OC_DisableFast(TIM1, LL_TIM_CHANNEL_CH3);
+
+ LL_TIM_OC_EnablePreload(TIM1, LL_TIM_CHANNEL_CH4);
+ TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
+ LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH4, &TIM_OC_InitStruct);
+ LL_TIM_OC_DisableFast(TIM1, LL_TIM_CHANNEL_CH4);
+
+ LL_TIM_OC_EnablePreload(TIM1, LL_TIM_CHANNEL_CH5);
+ TIM_OC_InitStruct.OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct.OCNState = LL_TIM_OCSTATE_DISABLE;
+ LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH5, &TIM_OC_InitStruct);
+ LL_TIM_OC_DisableFast(TIM1, LL_TIM_CHANNEL_CH5);
+
+ LL_TIM_SetTriggerOutput(TIM1, LL_TIM_TRGO_RESET);
+ LL_TIM_SetTriggerOutput2(TIM1, LL_TIM_TRGO2_RESET);
+ LL_TIM_DisableMasterSlaveMode(TIM1);
+ TIM_BDTRInitStruct.OSSRState = LL_TIM_OSSR_DISABLE;
+ TIM_BDTRInitStruct.OSSIState = LL_TIM_OSSI_DISABLE;
+ TIM_BDTRInitStruct.LockLevel = LL_TIM_LOCKLEVEL_OFF;
+ TIM_BDTRInitStruct.DeadTime = DEAD_TIME;
+ TIM_BDTRInitStruct.BreakState = LL_TIM_BREAK_DISABLE;
+ TIM_BDTRInitStruct.BreakPolarity = LL_TIM_BREAK_POLARITY_HIGH;
+ TIM_BDTRInitStruct.BreakFilter = LL_TIM_BREAK_FILTER_FDIV1;
+ TIM_BDTRInitStruct.BreakAFMode = LL_TIM_BREAK_AFMODE_INPUT;
+ TIM_BDTRInitStruct.Break2State = LL_TIM_BREAK2_DISABLE;
+ TIM_BDTRInitStruct.Break2Polarity = LL_TIM_BREAK2_POLARITY_HIGH;
+ TIM_BDTRInitStruct.Break2Filter = LL_TIM_BREAK2_FILTER_FDIV1;
+ TIM_BDTRInitStruct.Break2AFMode = LL_TIM_BREAK_AFMODE_INPUT;
+ TIM_BDTRInitStruct.AutomaticOutput = LL_TIM_AUTOMATICOUTPUT_DISABLE;
+ LL_TIM_BDTR_Init(TIM1, &TIM_BDTRInitStruct);
+ /* USER CODE BEGIN TIM1_Init 2 */
+
+ /* USER CODE END TIM1_Init 2 */
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+ /**TIM1 GPIO Configuration
+ PA7 ------> TIM1_CH1N
+ PB0 ------> TIM1_CH2N
+ PB1 ------> TIM1_CH3N
+ PA8 ------> TIM1_CH1
+ PA9 [PA11] ------> TIM1_CH2
+ PA10 [PA12] ------> TIM1_CH3
+ */
+#ifdef PWM_ENABLE_BRIDGE
+ #define PHASE_C_GPIO_LOW PHASE_C_GPIO_ENABLE
+ #define PHASE_B_GPIO_LOW PHASE_B_GPIO_ENABLE
+ #define PHASE_A_GPIO_LOW PHASE_A_GPIO_ENABLE
+ #define PHASE_C_GPIO_PORT_LOW PHASE_C_GPIO_PORT_ENABLE
+ #define PHASE_B_GPIO_PORT_LOW PHASE_B_GPIO_PORT_ENABLE
+ #define PHASE_A_GPIO_PORT_LOW PHASE_A_GPIO_PORT_ENABLE
+
+ #define PHASE_C_GPIO_HIGH PHASE_C_GPIO_PWM
+ #define PHASE_B_GPIO_HIGH PHASE_B_GPIO_PWM
+ #define PHASE_A_GPIO_HIGH PHASE_A_GPIO_PWM
+ #define PHASE_C_GPIO_PORT_HIGH PHASE_C_GPIO_PORT_PWM
+ #define PHASE_B_GPIO_PORT_HIGH PHASE_B_GPIO_PORT_PWM
+ #define PHASE_A_GPIO_PORT_HIGH PHASE_A_GPIO_PORT_PWM
+#endif
+#ifndef OPEN_DRAIN_PWM
+ #define PWM_OUTPUT_TYPE LL_GPIO_OUTPUT_PUSHPULL
+#else
+ #define PWM_OUTPUT_TYPE LL_GPIO_OUTPUT_OPENDRAIN
+#endif
+
+ GPIO_InitStruct.Pin = PHASE_C_GPIO_LOW;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(PHASE_C_GPIO_PORT_LOW, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = PHASE_B_GPIO_LOW;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(PHASE_B_GPIO_PORT_LOW, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = PHASE_A_GPIO_LOW;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(PHASE_A_GPIO_PORT_LOW, &GPIO_InitStruct);
+
+ // high side gate / PWM outputs
+ GPIO_InitStruct.Pin = PHASE_C_GPIO_HIGH;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = PWM_OUTPUT_TYPE;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(PHASE_C_GPIO_PORT_HIGH, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = PHASE_B_GPIO_HIGH;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = PWM_OUTPUT_TYPE;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(PHASE_B_GPIO_PORT_HIGH, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = PHASE_A_GPIO_HIGH;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = PWM_OUTPUT_TYPE;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_2;
+ LL_GPIO_Init(PHASE_A_GPIO_PORT_HIGH, &GPIO_InitStruct);
+
+}
+
+/**
+ * @brief TIM2 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_TIM2_Init(void)
+{
+
+ /* USER CODE BEGIN TIM2_Init 0 */
+
+ /* USER CODE END TIM2_Init 0 */
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2);
+
+ /* USER CODE BEGIN TIM2_Init 1 */
+
+ /* USER CODE END TIM2_Init 1 */
+ TIM_InitStruct.Prescaler = 31;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 65535;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ LL_TIM_Init(TIM2, &TIM_InitStruct);
+ LL_TIM_DisableARRPreload(TIM2);
+ LL_TIM_SetClockSource(TIM2, LL_TIM_CLOCKSOURCE_INTERNAL);
+ LL_TIM_SetTriggerOutput(TIM2, LL_TIM_TRGO_RESET);
+ LL_TIM_DisableMasterSlaveMode(TIM2);
+ /* USER CODE BEGIN TIM2_Init 2 */
+
+ /* USER CODE END TIM2_Init 2 */
+
+}
+
+/**
+ * @brief TIM3 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_TIM3_Init(void)
+{
+
+ /* USER CODE BEGIN TIM3_Init 0 */
+
+ /* USER CODE END TIM3_Init 0 */
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM3);
+
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+ /**TIM3 GPIO Configuration
+ PB4 ------> TIM3_CH1
+ */
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_4;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_1;
+ LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* TIM3 DMA Init */
+
+ /* TIM3_CH1 Init */
+ LL_DMA_SetPeriphRequest(DMA1, LL_DMA_CHANNEL_1, LL_DMAMUX_REQ_TIM3_CH1);
+
+ LL_DMA_SetDataTransferDirection(DMA1, LL_DMA_CHANNEL_1, LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
+
+ LL_DMA_SetChannelPriorityLevel(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PRIORITY_LOW);
+
+ LL_DMA_SetMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MODE_NORMAL);
+
+ LL_DMA_SetPeriphIncMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PERIPH_NOINCREMENT);
+
+ LL_DMA_SetMemoryIncMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MEMORY_INCREMENT);
+
+ LL_DMA_SetPeriphSize(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PDATAALIGN_HALFWORD);
+
+ LL_DMA_SetMemorySize(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MDATAALIGN_WORD);
+
+ /* TIM3 interrupt Init */
+ NVIC_SetPriority(TIM3_IRQn, 0);
+ NVIC_EnableIRQ(TIM3_IRQn);
+
+ /* USER CODE BEGIN TIM3_Init 1 */
+
+ /* USER CODE END TIM3_Init 1 */
+ TIM_InitStruct.Prescaler = 0;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 65535;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ LL_TIM_Init(TIM3, &TIM_InitStruct);
+ LL_TIM_DisableARRPreload(TIM3);
+ LL_TIM_SetTriggerOutput(TIM3, LL_TIM_TRGO_RESET);
+ LL_TIM_DisableMasterSlaveMode(TIM3);
+ LL_TIM_IC_SetActiveInput(TIM3, LL_TIM_CHANNEL_CH1, LL_TIM_ACTIVEINPUT_DIRECTTI);
+ LL_TIM_IC_SetPrescaler(TIM3, LL_TIM_CHANNEL_CH1, LL_TIM_ICPSC_DIV1);
+ LL_TIM_IC_SetFilter(TIM3, LL_TIM_CHANNEL_CH1, LL_TIM_IC_FILTER_FDIV1);
+ LL_TIM_IC_SetPolarity(TIM3, LL_TIM_CHANNEL_CH1, LL_TIM_IC_POLARITY_BOTHEDGE);
+ /* USER CODE BEGIN TIM3_Init 2 */
+
+ /* USER CODE END TIM3_Init 2 */
+
+}
+
+void MX_TIM16_Init(void)
+{
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM16);
+
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
+ /**TIM3 GPIO Configuration
+ PB4 ------> TIM3_CH1
+ */
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_6;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_5;
+ LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+
+ LL_DMA_SetPeriphRequest(DMA1, LL_DMA_CHANNEL_1, LL_DMAMUX_REQ_TIM16_CH1);
+
+ LL_DMA_SetDataTransferDirection(DMA1, LL_DMA_CHANNEL_1, LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
+
+ LL_DMA_SetChannelPriorityLevel(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PRIORITY_LOW);
+
+ LL_DMA_SetMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MODE_NORMAL);
+
+ LL_DMA_SetPeriphIncMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PERIPH_NOINCREMENT);
+
+ LL_DMA_SetMemoryIncMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MEMORY_INCREMENT);
+
+ LL_DMA_SetPeriphSize(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PDATAALIGN_HALFWORD);
+
+ LL_DMA_SetMemorySize(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MDATAALIGN_WORD);
+
+ /* TIM3 interrupt Init */
+ NVIC_SetPriority(TIM16_IRQn, 0);
+ NVIC_EnableIRQ(TIM16_IRQn);
+
+ /* USER CODE BEGIN TIM3_Init 1 */
+
+ /* USER CODE END TIM3_Init 1 */
+ TIM_InitStruct.Prescaler = 0;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 65535;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ LL_TIM_Init(TIM16, &TIM_InitStruct);
+ LL_TIM_DisableARRPreload(TIM16);
+ LL_TIM_SetTriggerOutput(TIM16, LL_TIM_TRGO_RESET);
+ LL_TIM_DisableMasterSlaveMode(TIM16);
+ LL_TIM_IC_SetActiveInput(TIM16, LL_TIM_CHANNEL_CH1, LL_TIM_ACTIVEINPUT_DIRECTTI);
+ LL_TIM_IC_SetPrescaler(TIM16, LL_TIM_CHANNEL_CH1, LL_TIM_ICPSC_DIV1);
+ LL_TIM_IC_SetFilter(TIM16, LL_TIM_CHANNEL_CH1, LL_TIM_IC_FILTER_FDIV1);
+ LL_TIM_IC_SetPolarity(TIM16, LL_TIM_CHANNEL_CH1, LL_TIM_IC_POLARITY_BOTHEDGE);
+ /* USER CODE BEGIN TIM3_Init 2 */
+
+ /* USER CODE END TIM3_Init 2 */
+
+}
+
+/**
+ * @brief TIM14 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_TIM14_Init(void)
+{
+
+ /* USER CODE BEGIN TIM14_Init 0 */
+
+ /* USER CODE END TIM14_Init 0 */
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM14);
+
+ /* TIM14 interrupt Init */
+ NVIC_SetPriority(TIM14_IRQn, 0);
+ NVIC_EnableIRQ(TIM14_IRQn);
+
+ /* USER CODE BEGIN TIM14_Init 1 */
+
+ /* USER CODE END TIM14_Init 1 */
+ TIM_InitStruct.Prescaler = 31;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 65535;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ LL_TIM_Init(TIM14, &TIM_InitStruct);
+ LL_TIM_DisableARRPreload(TIM14);
+ /* USER CODE BEGIN TIM14_Init 2 */
+
+ /* USER CODE END TIM14_Init 2 */
+
+}
+
+
+/**
+ * @brief TIM17 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_TIM17_Init(void)
+{
+
+ /* USER CODE BEGIN TIM17_Init 0 */
+
+ /* USER CODE END TIM17_Init 0 */
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM17);
+
+ /* USER CODE BEGIN TIM17_Init 1 */
+
+ /* USER CODE END TIM17_Init 1 */
+ TIM_InitStruct.Prescaler = 63;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 65535;
+ TIM_InitStruct.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ TIM_InitStruct.RepetitionCounter = 0;
+ LL_TIM_Init(TIM17, &TIM_InitStruct);
+ LL_TIM_EnableARRPreload(TIM17);
+ /* USER CODE BEGIN TIM17_Init 2 */
+
+ /* USER CODE END TIM17_Init 2 */
+
+}
+
+/**
+ * Enable DMA controller clock
+ */
+void MX_DMA_Init(void)
+{
+
+ /* Init with LL driver */
+ /* DMA controller clock enable */
+ LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_DMA1);
+
+ /* DMA interrupt init */
+ /* DMA1_Channel1_IRQn interrupt configuration */
+ NVIC_SetPriority(DMA1_Channel1_IRQn, 1);
+ NVIC_EnableIRQ(DMA1_Channel1_IRQn);
+ /* DMA1_Channel2_3_IRQn interrupt configuration */
+ NVIC_SetPriority(DMA1_Channel2_3_IRQn, 1);
+ NVIC_EnableIRQ(DMA1_Channel2_3_IRQn);
+
+}
+
+void MX_TIM6_Init(void)
+{
+
+ LL_TIM_InitTypeDef TIM_InitStruct = {0};
+
+
+ LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM6);
+
+ /* TIM6 interrupt Init */
+ NVIC_SetPriority(TIM6_DAC_LPTIM1_IRQn, 2);
+ NVIC_EnableIRQ(TIM6_DAC_LPTIM1_IRQn);
+
+ TIM_InitStruct.Prescaler = 63;
+ TIM_InitStruct.CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct.Autoreload = 100;
+ LL_TIM_Init(TIM6, &TIM_InitStruct);
+ LL_TIM_DisableARRPreload(TIM6);
+ LL_TIM_SetTriggerOutput(TIM6, LL_TIM_TRGO_RESET);
+ LL_TIM_DisableMasterSlaveMode(TIM6);
+
+
+}
+void MX_GPIO_Init(void)
+{
+
+ /* GPIO Ports Clock Enable */
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+
+}
+
+
diff --git a/Mcu/l431/Src/serial_telemetry.c b/Mcu/l431/Src/serial_telemetry.c
new file mode 100644
index 00000000..9989467f
--- /dev/null
+++ b/Mcu/l431/Src/serial_telemetry.c
@@ -0,0 +1,140 @@
+/*
+ * serial_telemetry.c
+ *
+ * Created on: May 13, 2020
+ * Author: Alka
+ */
+
+
+#include "serial_telemetry.h"
+
+
+uint8_t aTxBuffer[10];
+uint8_t nbDataToTransmit = sizeof(aTxBuffer);
+
+
+
+void telem_UART_Init()
+{
+
+
+ LL_USART_InitTypeDef USART_InitStruct = {0};
+
+ LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* Peripheral clock enable */
+ LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_USART1);
+
+ LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
+
+ GPIO_InitStruct.Pin = LL_GPIO_PIN_6;
+ GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
+ GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_OPENDRAIN;
+ GPIO_InitStruct.Pull = LL_GPIO_PULL_UP;
+ GPIO_InitStruct.Alternate = LL_GPIO_AF_0;
+ LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ NVIC_SetPriority(USART1_IRQn, 3);
+ NVIC_EnableIRQ(USART1_IRQn);
+
+
+ LL_DMA_SetPeriphRequest(DMA1, LL_DMA_CHANNEL_3, LL_DMAMUX_REQ_USART1_TX);
+
+ LL_DMA_SetDataTransferDirection(DMA1, LL_DMA_CHANNEL_3, LL_DMA_DIRECTION_MEMORY_TO_PERIPH);
+
+ LL_DMA_SetChannelPriorityLevel(DMA1, LL_DMA_CHANNEL_3, LL_DMA_PRIORITY_LOW);
+
+ LL_DMA_SetMode(DMA1, LL_DMA_CHANNEL_3, LL_DMA_MODE_NORMAL);
+
+ LL_DMA_SetPeriphIncMode(DMA1, LL_DMA_CHANNEL_3, LL_DMA_PERIPH_NOINCREMENT);
+
+ LL_DMA_SetMemoryIncMode(DMA1, LL_DMA_CHANNEL_3, LL_DMA_MEMORY_INCREMENT);
+
+ LL_DMA_SetPeriphSize(DMA1, LL_DMA_CHANNEL_3, LL_DMA_PDATAALIGN_BYTE);
+
+ LL_DMA_SetMemorySize(DMA1, LL_DMA_CHANNEL_3, LL_DMA_MDATAALIGN_BYTE);
+
+
+ USART_InitStruct.PrescalerValue = LL_USART_PRESCALER_DIV1;
+ USART_InitStruct.BaudRate = 115200;
+ USART_InitStruct.DataWidth = LL_USART_DATAWIDTH_8B;
+ USART_InitStruct.StopBits = LL_USART_STOPBITS_1;
+ USART_InitStruct.Parity = LL_USART_PARITY_NONE;
+ USART_InitStruct.TransferDirection = LL_USART_DIRECTION_TX_RX;
+ USART_InitStruct.OverSampling = LL_USART_OVERSAMPLING_16;
+ LL_USART_Init(USART1, &USART_InitStruct);
+ LL_USART_SetTXFIFOThreshold(USART1, LL_USART_FIFOTHRESHOLD_1_8);
+ LL_USART_SetRXFIFOThreshold(USART1, LL_USART_FIFOTHRESHOLD_1_8);
+ LL_USART_DisableFIFO(USART1);
+ LL_USART_ConfigHalfDuplexMode(USART1);
+
+
+ LL_USART_Enable(USART1);
+ while((!(LL_USART_IsActiveFlag_TEACK(USART1))) || (!(LL_USART_IsActiveFlag_REACK(USART1))))
+ {
+ }
+
+ LL_DMA_ConfigAddresses(DMA1, LL_DMA_CHANNEL_3,
+ (uint32_t)aTxBuffer,
+ LL_USART_DMA_GetRegAddr(USART1, LL_USART_DMA_REG_DATA_TRANSMIT),
+ LL_DMA_GetDataTransferDirection(DMA1, LL_DMA_CHANNEL_3));
+ LL_DMA_SetDataLength(DMA1, LL_DMA_CHANNEL_3, nbDataToTransmit);
+
+ /* (5) Enable DMA transfer complete/error interrupts */
+ LL_DMA_EnableIT_TC(DMA1, LL_DMA_CHANNEL_3);
+ LL_DMA_EnableIT_TE(DMA1, LL_DMA_CHANNEL_3);
+
+
+
+
+
+
+}
+
+void send_telem_DMA(){ // set data length and enable channel to start transfer
+ LL_USART_SetTransferDirection(USART1, LL_USART_DIRECTION_TX);
+ // GPIOB->OTYPER &= 0 << 6;
+ LL_DMA_SetDataLength(DMA1, LL_DMA_CHANNEL_3, nbDataToTransmit);
+ LL_USART_EnableDMAReq_TX(USART1);
+
+ LL_DMA_EnableChannel(DMA1, LL_DMA_CHANNEL_3);
+ LL_USART_SetTransferDirection(USART1, LL_USART_DIRECTION_RX);
+}
+
+
+
+uint8_t update_crc8(uint8_t crc, uint8_t crc_seed){
+uint8_t crc_u, i;
+crc_u = crc;
+crc_u ^= crc_seed;
+for ( i=0; i<8; i++) crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
+return (crc_u);
+}
+
+uint8_t get_crc8(uint8_t *Buf, uint8_t BufLen){
+uint8_t crc = 0, i;
+for( i=0; i> 8) & 0xFF; // voltage hB
+ aTxBuffer[2] = voltage & 0xFF; // voltage lowB
+
+ aTxBuffer[3] = (current >> 8) & 0xFF; // current
+ aTxBuffer[4] = current & 0xFF; // divide by 10 for Amps
+
+ aTxBuffer[5] = (consumption >> 8) & 0xFF; // consumption
+ aTxBuffer[6] = consumption & 0xFF; // in mah
+
+ aTxBuffer[7] = (e_rpm >> 8) & 0xFF; //
+ aTxBuffer[8] = e_rpm & 0xFF; // eRpM *100
+
+ aTxBuffer[9] = get_crc8(aTxBuffer,9);
+}
+
diff --git a/Mcu/l431/Src/stm32g0xx_it.c b/Mcu/l431/Src/stm32g0xx_it.c
new file mode 100644
index 00000000..4bfad0be
--- /dev/null
+++ b/Mcu/l431/Src/stm32g0xx_it.c
@@ -0,0 +1,391 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32g0xx_it.c
+ * @brief Interrupt Service Routines.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "stm32g0xx_it.h"
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+#include "ADC.h"
+#include "targets.h"
+#include "WS2812.h"
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* External variables --------------------------------------------------------*/
+
+/* USER CODE BEGIN EV */
+extern void transfercomplete();
+extern void PeriodElapsedCallback();
+extern void interruptRoutine();
+extern void tenKhzRoutine();
+
+
+extern char send_telemetry;
+int update_interupt = 0;
+extern char servoPwm;
+/* USER CODE END EV */
+
+/******************************************************************************/
+/* Cortex-M0+ Processor Interruption and Exception Handlers */
+/******************************************************************************/
+/**
+ * @brief This function handles Non maskable interrupt.
+ */
+void NMI_Handler(void)
+{
+ /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
+
+ /* USER CODE END NonMaskableInt_IRQn 0 */
+ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
+
+ /* USER CODE END NonMaskableInt_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Hard fault interrupt.
+ */
+void HardFault_Handler(void)
+{
+ /* USER CODE BEGIN HardFault_IRQn 0 */
+
+ /* USER CODE END HardFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_HardFault_IRQn 0 */
+ /* USER CODE END W1_HardFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles System service call via SWI instruction.
+ */
+void SVC_Handler(void)
+{
+ /* USER CODE BEGIN SVC_IRQn 0 */
+
+ /* USER CODE END SVC_IRQn 0 */
+ /* USER CODE BEGIN SVC_IRQn 1 */
+
+ /* USER CODE END SVC_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Pendable request for system service.
+ */
+void PendSV_Handler(void)
+{
+ /* USER CODE BEGIN PendSV_IRQn 0 */
+
+ /* USER CODE END PendSV_IRQn 0 */
+ /* USER CODE BEGIN PendSV_IRQn 1 */
+
+ /* USER CODE END PendSV_IRQn 1 */
+}
+
+/**
+ * @brief This function handles System tick timer.
+ */
+void SysTick_Handler(void)
+{
+ /* USER CODE BEGIN SysTick_IRQn 0 */
+
+ /* USER CODE END SysTick_IRQn 0 */
+
+ /* USER CODE BEGIN SysTick_IRQn 1 */
+
+ /* USER CODE END SysTick_IRQn 1 */
+}
+
+/******************************************************************************/
+/* STM32G0xx Peripheral Interrupt Handlers */
+/* Add here the Interrupt Handlers for the used peripherals. */
+/* For the available peripheral interrupt handler names, */
+/* please refer to the startup file (startup_stm32g0xx.s). */
+/******************************************************************************/
+
+/**
+ * @brief This function handles DMA1 channel 1 interrupt.
+ */
+void DMA1_Channel1_IRQHandler(void)
+{
+ /* USER CODE BEGIN DMA1_Channel1_IRQn 0 */
+ if(LL_DMA_IsActiveFlag_HT1(DMA1)){
+ if(servoPwm){
+ LL_TIM_IC_SetPolarity(IC_TIMER_REGISTER, IC_TIMER_CHANNEL, LL_TIM_IC_POLARITY_FALLING);
+ LL_DMA_ClearFlag_HT1(DMA1);
+ }
+ }
+ if(LL_DMA_IsActiveFlag_TC1(DMA1) == 1)
+ {
+ LL_DMA_ClearFlag_GI1(DMA1);
+
+ LL_DMA_DisableChannel(DMA1, LL_DMA_CHANNEL_1);
+
+
+ transfercomplete();
+
+ }
+ else if(LL_DMA_IsActiveFlag_TE1(DMA1) == 1)
+ {
+ LL_DMA_ClearFlag_GI1(DMA1);
+ }
+
+ /* USER CODE END DMA1_Channel1_IRQn 0 */
+
+ /* USER CODE BEGIN DMA1_Channel1_IRQn 1 */
+
+ /* USER CODE END DMA1_Channel1_IRQn 1 */
+}
+
+/**
+ * @brief This function handles DMA1 channel 2 and channel 3 interrupts.
+ */
+void DMA1_Channel2_3_IRQHandler(void)
+{
+ if(LL_DMA_IsActiveFlag_TC2(DMA1) == 1)
+ {
+ /* Clear flag DMA global interrupt */
+ /* (global interrupt flag: half transfer and transfer complete flags) */
+ LL_DMA_ClearFlag_GI2(DMA1);
+ ADC_DMA_Callback();
+ /* Call interruption treatment function */
+ // AdcDmaTransferComplete_Callback();
+ }
+
+ /* Check whether DMA transfer error caused the DMA interruption */
+ if(LL_DMA_IsActiveFlag_TE2(DMA1) == 1)
+ {
+ /* Clear flag DMA transfer error */
+ LL_DMA_ClearFlag_TE2(DMA1);
+
+ /* Call interruption treatment function */
+ }
+
+ if(LL_DMA_IsActiveFlag_TC3(DMA1))
+ {
+ // telemetry_done = 1;
+ // update_interupt++;
+ send_telemetry = 0;
+ LL_DMA_ClearFlag_GI3(DMA1);
+ LL_DMA_DisableChannel(DMA1, LL_DMA_CHANNEL_3);
+ /* Call function Transmission complete Callback */
+
+ }
+ else if(LL_DMA_IsActiveFlag_TE3(DMA1))
+ {
+ LL_DMA_ClearFlag_GI3(DMA1);
+ LL_DMA_DisableChannel(DMA1, LL_DMA_CHANNEL_3);
+ /* Call Error function */
+ // USART_TransferError_Callback();
+ }
+
+}
+
+/**
+ * @brief This function handles ADC1, COMP1 and COMP2 interrupts (COMP interrupts through EXTI lines 17 and 18).
+ */
+void ADC1_COMP_IRQHandler(void)
+{
+ //count++;
+ /* USER CODE BEGIN ADC1_COMP_IRQn 0 */
+
+ if(LL_EXTI_IsActiveFallingFlag_0_31(LL_EXTI_LINE_18)){
+ LL_EXTI_ClearFallingFlag_0_31(LL_EXTI_LINE_18);
+ interruptRoutine();
+ return;
+ }
+
+ if(LL_EXTI_IsActiveRisingFlag_0_31(LL_EXTI_LINE_18)){
+ LL_EXTI_ClearRisingFlag_0_31(LL_EXTI_LINE_18);
+ interruptRoutine();
+ return;
+ }
+ if(LL_EXTI_IsActiveFallingFlag_0_31(LL_EXTI_LINE_17)){
+ LL_EXTI_ClearFallingFlag_0_31(LL_EXTI_LINE_17);
+ interruptRoutine();
+ return;
+ }
+ if(LL_EXTI_IsActiveRisingFlag_0_31(LL_EXTI_LINE_17)){
+ LL_EXTI_ClearRisingFlag_0_31(LL_EXTI_LINE_17);
+ interruptRoutine();
+ return;
+ }
+
+ /* USER CODE END ADC1_COMP_IRQn 0 */
+
+ /* USER CODE BEGIN ADC1_COMP_IRQn 1 */
+
+ /* USER CODE END ADC1_COMP_IRQn 1 */
+}
+
+/**
+ * @brief This function handles TIM3 global interrupt.
+ */
+void TIM3_IRQHandler(void)
+{
+
+
+ /* USER CODE BEGIN TIM3_IRQn 0 */
+ if(LL_TIM_IsActiveFlag_CC1(TIM3) == 1)
+ {
+
+ LL_TIM_ClearFlag_CC1(TIM3);
+ }
+
+ if(LL_TIM_IsActiveFlag_UPDATE(TIM3) == 1)
+ {
+ LL_TIM_ClearFlag_UPDATE(TIM3);
+ // update_interupt++;
+
+ }
+ /* USER CODE END TIM3_IRQn 0 */
+ /* USER CODE BEGIN TIM3_IRQn 1 */
+
+ /* USER CODE END TIM3_IRQn 1 */
+}
+
+void TIM16_IRQHandler(void)
+{
+
+
+ /* USER CODE BEGIN TIM3_IRQn 0 */
+ if(LL_TIM_IsActiveFlag_CC1(TIM16) == 1)
+ {
+
+ LL_TIM_ClearFlag_CC1(TIM16);
+ }
+
+ if(LL_TIM_IsActiveFlag_UPDATE(TIM16) == 1)
+ {
+ LL_TIM_ClearFlag_UPDATE(TIM16);
+ // update_interupt++;
+
+ }
+ /* USER CODE END TIM3_IRQn 0 */
+ /* USER CODE BEGIN TIM3_IRQn 1 */
+
+ /* USER CODE END TIM3_IRQn 1 */
+}
+
+
+void TIM6_DAC_LPTIM1_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM6_DAC_LPTIM1_IRQn 0 */
+ if(LL_TIM_IsActiveFlag_UPDATE(TIM6) == 1)
+ {
+ LL_TIM_ClearFlag_UPDATE(TIM6);
+ tenKhzRoutine();
+
+ }
+ /* USER CODE END TIM6_DAC_LPTIM1_IRQn 0 */
+
+ /* USER CODE BEGIN TIM6_DAC_LPTIM1_IRQn 1 */
+
+ /* USER CODE END TIM6_DAC_LPTIM1_IRQn 1 */
+}
+
+
+/**
+ * @brief This function handles TIM14 global interrupt.
+ */
+void TIM14_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM14_IRQn 0 */
+ if(LL_TIM_IsActiveFlag_UPDATE(TIM14) == 1)
+ {
+ PeriodElapsedCallback();
+ LL_TIM_ClearFlag_UPDATE(TIM14);
+ }
+ /* USER CODE END TIM14_IRQn 0 */
+ /* USER CODE BEGIN TIM14_IRQn 1 */
+
+ /* USER CODE END TIM14_IRQn 1 */
+}
+
+/* USER CODE BEGIN 1 */
+void DMA1_Ch4_7_DMAMUX1_OVR_IRQHandler(void)
+{
+
+
+ /* USER CODE BEGIN DMA1_Ch4_7_DMAMUX1_OVR_IRQn 0 */
+ if(LL_DMA_IsActiveFlag_HT6(DMA1)){
+
+ }
+ if(LL_DMA_IsActiveFlag_TC6(DMA1) == 1)
+ {
+ LL_DMA_ClearFlag_GI6(DMA1);
+
+ LL_DMA_DisableChannel(DMA1, LL_DMA_CHANNEL_6);
+ // update_interupt++;
+ // LL_TIM_CC_DisableChannel(TIM16, LL_DMA_CHANNEL_6);
+ LL_TIM_DisableAllOutputs(TIM16);
+ LL_TIM_DisableCounter(TIM16);
+ dma_busy = 0;
+
+
+ }
+ else if(LL_DMA_IsActiveFlag_TE6(DMA1) == 1)
+ {
+ LL_DMA_DisableChannel(DMA1, LL_DMA_CHANNEL_6);
+ // update_interupt++;
+ // LL_TIM_CC_DisableChannel(TIM16, LL_DMA_CHANNEL_6);
+ LL_TIM_DisableAllOutputs(TIM16);
+ LL_TIM_DisableCounter(TIM16);
+dma_busy = 0;
+ LL_DMA_ClearFlag_GI6(DMA1);
+ }
+ /* USER CODE END DMA1_Ch4_7_DMAMUX1_OVR_IRQn 0 */
+
+ /* USER CODE BEGIN DMA1_Ch4_7_DMAMUX1_OVR_IRQn 1 */
+
+ /* USER CODE END DMA1_Ch4_7_DMAMUX1_OVR_IRQn 1 */
+}
+/* USER CODE END 1 */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/Mcu/l431/Src/system_stm32g0xx.c b/Mcu/l431/Src/system_stm32g0xx.c
new file mode 100644
index 00000000..233ab30a
--- /dev/null
+++ b/Mcu/l431/Src/system_stm32g0xx.c
@@ -0,0 +1,290 @@
+/**
+ ******************************************************************************
+ * @file system_stm32g0xx.c
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-M0+ Device Peripheral Access Layer System Source File
+ *
+ * This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32g0xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * After each device reset the HSI (8 MHz then 16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32g0xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * This file configures the system clock as follows:
+ *=============================================================================
+ *-----------------------------------------------------------------------------
+ * System Clock source | HSI
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSI Division factor | 1
+ *-----------------------------------------------------------------------------
+ * PLL_M | 1
+ *-----------------------------------------------------------------------------
+ * PLL_N | 8
+ *-----------------------------------------------------------------------------
+ * PLL_P | 7
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 2
+ *-----------------------------------------------------------------------------
+ * PLL_R | 2
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for RNG | Disabled
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2018 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32g0xx_system
+ * @{
+ */
+
+/** @addtogroup STM32G0xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32g0xx.h"
+
+#if !defined (HSE_VALUE)
+#define HSE_VALUE (8000000UL) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE (16000000UL) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+#if !defined (LSI_VALUE)
+ #define LSI_VALUE (32000UL) /*!< Value of LSI in Hz*/
+#endif /* LSI_VALUE */
+
+#if !defined (LSE_VALUE)
+ #define LSE_VALUE (32768UL) /*!< Value of LSE in Hz*/
+#endif /* LSE_VALUE */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G0xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G0xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x0U /*!< Vector Table base offset field.
+ This value must be a multiple of 0x100. */
+/******************************************************************************/
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G0xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G0xx_System_Private_Variables
+ * @{
+ */
+ /* The SystemCoreClock variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+ uint32_t SystemCoreClock = 16000000UL;
+
+ const uint32_t AHBPrescTable[16UL] = {0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL, 6UL, 7UL, 8UL, 9UL};
+ const uint32_t APBPrescTable[8UL] = {0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G0xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G0xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**) / HSI division factor
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
+ *
+ * - If SYSCLK source is LSI, SystemCoreClock will contain the LSI_VALUE
+ *
+ * - If SYSCLK source is LSE, SystemCoreClock will contain the LSE_VALUE
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (**) HSI_VALUE is a constant defined in stm32g0xx_hal_conf.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (***) HSE_VALUE is a constant defined in stm32g0xx_hal_conf.h file (default value
+ * 8 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp;
+ uint32_t pllvco;
+ uint32_t pllr;
+ uint32_t pllsource;
+ uint32_t pllm;
+ uint32_t hsidiv;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ switch (RCC->CFGR & RCC_CFGR_SWS)
+ {
+ case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
+ SystemCoreClock = HSE_VALUE;
+ break;
+
+ case RCC_CFGR_SWS_LSI: /* LSI used as system clock */
+ SystemCoreClock = LSI_VALUE;
+ break;
+
+ case RCC_CFGR_SWS_LSE: /* LSE used as system clock */
+ SystemCoreClock = LSE_VALUE;
+ break;
+
+ case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
+ SYSCLK = PLL_VCO / PLLR
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
+ pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1UL;
+
+ if(pllsource == 0x03UL) /* HSE used as PLL clock source */
+ {
+ pllvco = (HSE_VALUE / pllm);
+ }
+ else /* HSI used as PLL clock source */
+ {
+ pllvco = (HSI_VALUE / pllm);
+ }
+ pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1UL);
+
+ SystemCoreClock = pllvco/pllr;
+ break;
+
+ case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
+ default: /* HSI used as system clock */
+ hsidiv = (1UL << ((READ_BIT(RCC->CR, RCC_CR_HSIDIV))>> RCC_CR_HSIDIV_Pos));
+ SystemCoreClock = (HSI_VALUE/hsidiv);
+ break;
+ }
+ /* Compute HCLK clock frequency --------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/Mcu/l431/Startup/startup_stm32l431kbux.s b/Mcu/l431/Startup/startup_stm32l431kbux.s
new file mode 100644
index 00000000..f652136e
--- /dev/null
+++ b/Mcu/l431/Startup/startup_stm32l431kbux.s
@@ -0,0 +1,461 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32l431xx.s
+ * @author MCD Application Team
+ * @brief STM32L431xx devices vector table for GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2017 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* Set stack pointer */
+
+/* Call the clock system initialization function.*/
+ bl SystemInit
+
+/* Copy the data segment initializers from flash to SRAM */
+ ldr r0, =_sdata
+ ldr r1, =_edata
+ ldr r2, =_sidata
+ movs r3, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r4, [r2, r3]
+ str r4, [r0, r3]
+ adds r3, r3, #4
+
+LoopCopyDataInit:
+ adds r4, r0, r3
+ cmp r4, r1
+ bcc CopyDataInit
+
+/* Zero fill the bss segment. */
+ ldr r2, =_sbss
+ ldr r4, =_ebss
+ movs r3, #0
+ b LoopFillZerobss
+
+FillZerobss:
+ str r3, [r2]
+ adds r2, r2, #4
+
+LoopFillZerobss:
+ cmp r2, r4
+ bcc FillZerobss
+
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_IRQHandler
+ .word CAN1_TX_IRQHandler
+ .word CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word 0
+ .word 0
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SDMMC1_IRQHandler
+ .word 0
+ .word SPI3_IRQHandler
+ .word 0
+ .word 0
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word 0
+ .word 0
+ .word 0
+ .word COMP_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word 0
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word LPUART1_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SAI1_IRQHandler
+ .word 0
+ .word SWPMI1_IRQHandler
+ .word TSC_IRQHandler
+ .word 0
+ .word 0
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+ .word CRS_IRQHandler
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_IRQHandler
+ .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak SDMMC1_IRQHandler
+ .thumb_set SDMMC1_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak SWPMI1_IRQHandler
+ .thumb_set SWPMI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+
diff --git a/Src/dshot.c b/Src/dshot.c
index bd6c5b8b..5a4c5539 100644
--- a/Src/dshot.c
+++ b/Src/dshot.c
@@ -71,6 +71,12 @@ dshot_frametime = dma_buffer[31]- dma_buffer[0];
dpulse[i] = ((dma_buffer[j + (i<<1) +1] - dma_buffer[j + (i<<1)])>>6) ;
}
#endif
+#if defined(MCU_L431)
+ if((dshot_frametime < 1800)&&(dshot_frametime > 1650)){
+ for (int i = 0; i < 16; i++){
+ dpulse[i] = ((dma_buffer[j + (i<<1) +1] - dma_buffer[j + (i<<1)])>>6) ;
+ }
+#endif
uint8_t calcCRC = ((dpulse[0]^dpulse[4]^dpulse[8])<<3
|(dpulse[1]^dpulse[5]^dpulse[9])<<2
@@ -267,6 +273,12 @@ for (int i = 15; i >= 9 ; i--){
}
gcr[7] = 0;
#endif
-
+#ifdef MCU_L431
+ gcr[1+7] = 94;
+ for( int i= 19; i >= 0; i--){ // each digit in gcrnumber
+ gcr[7+20-i+1] = ((((gcrnumber & 1 << i )) >> i) ^ (gcr[7+20-i]>>6)) *94; // exclusive ored with number before it multiplied by 64 to match output timer.
+ }
+ gcr[7] = 0;
+#endif
}
diff --git a/Src/main.c b/Src/main.c
index ec7cfda5..8435f03a 100644
--- a/Src/main.c
+++ b/Src/main.c
@@ -162,6 +162,8 @@
- Add firmware file name to each target hex file
-fix extended telemetry not activating dshot600
-fix low voltage cuttoff timeout
+*1.94 - Add selectable input types
+*1.95 - reduce timeout to 0.5 seconds when armed
*/
#include
@@ -185,7 +187,7 @@
#endif
#define VERSION_MAJOR 1
-#define VERSION_MINOR 94
+#define VERSION_MINOR 95
//firmware build options !! fixed speed and duty cycle modes are not to be used with sinusoidal startup !!
@@ -1302,8 +1304,8 @@ if(send_telemetry){
}
#else
signaltimeout++;
- if(signaltimeout > 2500 * (servoPwm+1)) { // quarter second timeout when armed half second for servo;
- if(input > 47){
+ if(signaltimeout > 5000) { // half second timeout when armed;
+ if(armed){
allOff();
armed = 0;
input = 0;