Browse Source

Writen. Need more tests.

Vladimir N. Shilov 5 months ago
parent
commit
7dc8d0e647
8 changed files with 351 additions and 407 deletions
  1. 1 9
      Makefile
  2. 16 0
      Skid.code-workspace
  3. 15 170
      inc/board.h
  4. 0 8
      inc/main.h
  5. 1 10
      inc/stm32g0xx_it.h
  6. 244 0
      src/board.c
  7. 67 29
      src/main.c
  8. 7 181
      src/stm32g0xx_it.c

+ 1 - 9
Makefile

@@ -41,15 +41,7 @@ BUILD_DIR = build
 C_SOURCES =  \
 src/main.c \
 src/board.c \
-src/sensor.c \
-src/utils.c \
-src/clock.c \
 src/stm32g0xx_it.c \
-src/i2c.c \
-src/ds3231.c \
-src/bme280.c \
-src/rtos.c \
-src/event-system.c \
 src/system_stm32g0xx.c
 
 # ASM sources
@@ -144,7 +136,7 @@ CFLAGS += -std=gnu11 -pedantic
 # LDFLAGS
 #######################################
 # link script
-LDSCRIPT = Drivers/STM32G030F6Tx_FLASH.ld
+LDSCRIPT = Drivers/STM32G030F6Px_FLASH.ld
 
 # libraries
 LIBS = -lc -lm -lnosys 

+ 16 - 0
Skid.code-workspace

@@ -0,0 +1,16 @@
+{
+	"folders": [
+		{
+			"path": "."
+		}
+	],
+	"settings": {
+		"cortex-debug.armToolchainPath": "C:/MCU/gcc-arm/bin",
+		"cortex-debug.gdbPath": "C:/MCU/gcc-arm/bin/arm-none-eabi-gdb.exe",
+		"cortex-debug.openocdPath": "C:/MCU/OpenOCD/bin/openocd.exe",
+		"cortex-debug.JLinkGDBServerPath": "C:/MCU/SEGGER/JLink/JLinkGDBServerCL.exe",
+		"cortex-debug.stutilPath": "C:/MCU/STMicroelectronics/stlink/bin/st-util.exe",
+		"cortex-debug.stlinkPath": "C:/MCU/STMicroelectronics/STLinkGDB.exe",
+		"cortex-debug.stm32cubeprogrammer": ""
+	}
+}

+ 15 - 170
inc/board.h

@@ -8,186 +8,31 @@
 #include "gpio.h"
 
 /* Type Defs */
-typedef enum {
-  Tube_All = 0xf,
-  Tube_C = 4,
-  Tube_A = 3,
-  Tube_B = 2,
-  Tube_D = 1,
-  Tube_E = 0
-} tube_pos_t;
-
-typedef enum {
-  sym_None      = 0,
-  sym_Pressure  = 0x1,
-  sym_Plus      = 0x2,
-  sym_Minus     = 0x4,
-  sym_Percent   = 0x8,
-  sym_Off       = 0xf << 16
-} in15_pin_t;
-
-typedef struct {
-    uint8_t r;
-    uint8_t g;
-    uint8_t b;
-} RGB_t;
-
-typedef struct {
-    uint8_t h;
-    uint8_t s;
-    uint8_t v;
-} HSV_t;
-
-typedef union {
-  uint32_t u32;  /* element specifier for accessing whole u32 */
-  uint8_t ar[4]; /* element specifier for accessing as array  */
-  struct {
-    uint8_t tE;  /* element specifier for accessing Tube_E(4) */
-    uint8_t tD;  /* element specifier for accessing Tube_D(3) */
-    uint8_t tB;  /* element specifier for accessing Tube_B(2) */
-    uint8_t tA;  /* element specifier for accessing Tube_A(1) */
-  } s8;         /* element spec. for acc. struct with tubes  */
-} tube4_t;
-
 /* Exported macros */
-#define LATCH_DOWN      GPIOC->BRR = 0x40
-#define LATCH_UP        GPIOC->BSRR = 0x40
-
-#define TUBE_PWR_ON     GPIOA->BRR = 0x10
-#define TUBE_PWR_OFF    GPIOA->BSRR = 0x10
-
-#define TUBE_A_ON       TIM1->CCER |= (TIM_CCER_CC1E)
-#define TUBE_B_ON       TIM3->CCER |= (TIM_CCER_CC4E)
-#define TUBE_C_ON       TIM3->CCER |= (TIM_CCER_CC3E)
-#define TUBE_D_ON       TIM3->CCER |= (TIM_CCER_CC2E)
-#define TUBE_E_ON       TIM3->CCER |= (TIM_CCER_CC1E)
-#define TUBE_BCDE_ON    TIM3->CCER |= (TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E)
-#define TUBE_ALL_ON     TUBE_A_ON; TUBE_BCDE_ON
-
-#define TUBE_A_OFF      TIM1->CCER &= ~(TIM_CCER_CC1E)
-#define TUBE_B_OFF      TIM3->CCER &= ~(TIM_CCER_CC4E)
-#define TUBE_C_OFF      TIM3->CCER &= ~(TIM_CCER_CC3E)
-#define TUBE_D_OFF      TIM3->CCER &= ~(TIM_CCER_CC2E)
-#define TUBE_E_OFF      TIM3->CCER &= ~(TIM_CCER_CC1E)
-#define TUBE_BCDE_OFF   TIM3->CCER &= ~(TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E)
-#define TUBE_ALL_OFF    TUBE_A_OFF; TUBE_BCDE_OFF
-
-#define IN15_P          GPIOA->BSRR = 0x1
-#define IN15_Plus       GPIOA->BSRR = 0x2
-#define IN15_Minus      GPIOA->BSRR = 0x4
-#define IN15_Percent    GPIOA->BSRR = 0x8
-#define IN15_OFF        GPIOA->BRR = 0xF
-
-#define COLOR_R(x)      TIM1->CCR2 = x
-#define COLOR_G(x)      TIM1->CCR3 = x
-#define COLOR_B(x)      TIM1->CCR4 = x
-#define LEDS_OFF        COLOR_R(0); COLOR_G(0); COLOR_B(0)
-
-#define TUBE_A_BRIGHT(x)  TIM1->CCR1 = x
-#define TUBE_B_BRIGHT(x)  TIM3->CCR4 = x
-#define TUBE_C_BRIGHT(x)  TIM3->CCR3 = x
-#define TUBE_D_BRIGHT(x)  TIM3->CCR2 = x
-#define TUBE_E_BRIGHT(x)  TIM3->CCR1 = x
-#define TUBES_BRIGHT(x)   TUBE_A_BRIGHT(x); TUBE_B_BRIGHT(x); TUBE_C_BRIGHT(x); TUBE_D_BRIGHT(x); TUBE_E_BRIGHT(x)
-
 /* Constants */
-/* PWM Timers for 250 Hz */
-#define TIM1_PSC            (375 - 1)
-#define TIM1_ARR            (256 - 1)
-#define TIM3_PSC            (375 - 1)
-#define TIM3_ARR            (256 - 1)
-#define PWM_TUBE_INIT_VAL   127
-#define PWM_LED_INIT_VAL    127
-#define PWM_LED_MAX_VAL     TIM3_ARR
+/* PWM Timers for 50 Hz */
+#define TIM1_PSC            (24 - 1)
+#define TIM1_ARR            (20000 - 1)
+#define SERVO_INIT_VAL      1000
+#define SERVO_OPEN_VAL      2000
 
-#define TIM14_PSC            (12000 - 1)
-#define TIM14_ARR            (1000 - 1)
-#define TIM14_PULSE_VAL      500
-
-#define TIM16_PSC            (24 - 1)
-#define TIM16_ARR            (1000 - 1)
-
-#define TIM17_PSC            (24 - 1)
-#define TIM17_ARR            (1000 - 1)
-
-#define TUBE_BLANK            0xa
+#define TIM3_PSC            (24000 - 1)
+#define TIM3_ARR            (100 - 1)
 
 /* Defines */
-#define BTN1_GPIO_Port GPIOB
-#define BTN1_Pin GPIO_PIN_2
-#define BTN2_GPIO_Port GPIOA
-#define BTN2_Pin GPIO_PIN_12
-#define BTN3_GPIO_Port GPIOB
-#define BTN3_Pin GPIO_PIN_4
-#define BTN4_GPIO_Port GPIOA
-#define BTN4_Pin GPIO_PIN_5
-#define IRQ_EXTI_IRQn EXTI4_15_IRQn
-#define IRQ_GPIO_Port GPIOC
-#define IRQ_Pin GPIO_PIN_14
-#define Latch_GPIO_Port GPIOC
-#define Latch_Pin GPIO_PIN_6
-#define LC0_GPIO_Port GPIOA
-#define LC0_Pin GPIO_PIN_0
-#define LC1_GPIO_Port GPIOA
-#define LC1_Pin GPIO_PIN_1
-#define LC2_GPIO_Port GPIOA
-#define LC2_Pin GPIO_PIN_2
-#define LC3_GPIO_Port GPIOA
-#define LC3_Pin GPIO_PIN_3
-#define PWM_1_GPIO_Port GPIOA
-#define PWM_1_Pin GPIO_PIN_8
-#define PWM_2_GPIO_Port GPIOB
-#define PWM_2_Pin GPIO_PIN_1
-#define PWM_3_GPIO_Port GPIOB
-#define PWM_3_Pin GPIO_PIN_0
-#define PWM_4_GPIO_Port GPIOA
-#define PWM_4_Pin GPIO_PIN_7
-#define PWM_5_GPIO_Port GPIOA
-#define PWM_5_Pin GPIO_PIN_6
-#define PWM_B_GPIO_Port GPIOA
-#define PWM_B_Pin GPIO_PIN_11
-#define PWM_G_GPIO_Port GPIOA
-#define PWM_G_Pin GPIO_PIN_10
-#define PWM_R_GPIO_Port GPIOA
-#define PWM_R_Pin GPIO_PIN_9
-#define SHDN_GPIO_Port GPIOA
-#define SHDN_Pin GPIO_PIN_4
-#define SWCLK_GPIO_Port GPIOA
-#define SWCLK_Pin GPIO_PIN_14
-#define SWDIO_GPIO_Port GPIOA
-#define SWDIO_Pin GPIO_PIN_13
-#define UART_EN_GPIO_Port GPIOC
-#define UART_EN_Pin GPIO_PIN_15
-#define UART_ST_GPIO_Port GPIOA
-#define UART_ST_Pin GPIO_PIN_15
-
-/* BTNs */
-#define BTN_NUM             4
-#define BTN1_PIN            GPIO_IDR_ID2
-#define BTN2_PIN            GPIO_IDR_ID12
-#define BTN3_PIN            GPIO_IDR_ID4
-#define BTN4_PIN            GPIO_IDR_ID5
-#define BTN1_STATE          (BTN1_GPIO_Port->IDR & BTN1_PIN)
-#define BTN2_STATE          (BTN2_GPIO_Port->IDR & BTN2_PIN)
-#define BTN3_STATE          (BTN3_GPIO_Port->IDR & BTN3_PIN)
-#define BTN4_STATE          (BTN4_GPIO_Port->IDR & BTN4_PIN)
-#define BTNS1_STATE         (GPIOB->IDR & (BTN1_PIN | BTN3_PIN))
-#define BTNS2_STATE         (GPIOA->IDR & (BTN2_PIN | BTN4_PIN))
-#define BTNS_STATE          (BTNS1_STATE | BTNS2_STATE)
+#define Photo_Pin     GPIO_PIN_7
+#define Photo_Port    GPIOB
+#define Servo_2_Pin   GPIO_PIN_8
+#define Servo_2_Port  GPIOA
+#define Servo_1_Pin   GPIO_PIN_11
+#define Servo_1_Port  GPIOA
 
 /* Variables */
 
 /* Exported funcions */
 void SystemClock_Config(void);
 void Board_Init(void);
-void Blink_Start(void);
-void Blink_Stop(void);
-void showDigits(tube4_t dig);
-void tube_Refresh(void);
-void lShiftDigits(const tube4_t old, const tube4_t dig);
-void slideDigits(tube4_t dig);
-void tube_PowerOn(tube_pos_t tube);
-void tube_PowerOff(tube_pos_t tube);
-void tube_BrightLevel(tube_pos_t tube, uint8_t bright);
+void delay_ms(uint32_t msek);
+void SysTick_Handler(void);
 
 #endif /* _BPARD_H */

+ 0 - 8
inc/main.h

@@ -30,14 +30,6 @@ extern "C" {
 
 /* Private includes ----------------------------------------------------------*/
 #include "board.h"
-#include "sensor.h"
-#include "i2c.h"
-#include "ds3231.h"
-#include "bme280.h"
-#include "rtos.h"
-#include "event-system.h"
-#include "list_event.h"
-#include "clock.h"
 
 /* Exported types ------------------------------------------------------------*/
 typedef enum {

+ 1 - 10
inc/stm32g0xx_it.h

@@ -33,16 +33,7 @@ void NMI_Handler(void);
 void HardFault_Handler(void);
 void SVC_Handler(void);
 void PendSV_Handler(void);
-void SysTick_Handler(void);
-void EXTI4_15_IRQHandler(void);
-void DMA1_Channel1_IRQHandler(void);
-void DMA1_Channel2_3_IRQHandler(void);
-void TIM14_IRQHandler(void);
-void TIM16_IRQHandler(void);
-void TIM17_IRQHandler(void);
-void I2C1_IRQHandler(void);
-void SPI1_IRQHandler(void);
-void USART1_IRQHandler(void);
+void ADC1_IRQHandler(void);
 
 #ifdef __cplusplus
 }

+ 244 - 0
src/board.c

@@ -0,0 +1,244 @@
+#include "board.h"
+
+/* private defines */
+/* private variables */
+static volatile uint32_t TDelay;
+
+/* private typedef */
+/* private functions */
+static void GPIO_Init(void);
+static void ADC_Init(void);
+static void TIM1_Init(void);
+static void TIM3_Init(void);
+static void IWDG_Init(void);
+
+/* Board perephireal Configuration  */
+void Board_Init(void)
+{
+  /* Main peripheral clock enable */
+  RCC->APBENR1 = (RCC_APBENR1_PWREN | RCC_APBENR1_TIM3EN);
+  RCC->APBENR2 = (RCC_APBENR2_SYSCFGEN | RCC_APBENR2_ADCEN | RCC_APBENR2_TIM1EN);
+  /* GPIO Ports Clock Enable */
+  RCC->IOPENR = (RCC_IOPENR_GPIOAEN | RCC_IOPENR_GPIOBEN);
+
+  /* Peripheral interrupt init*/
+  /* RCC_IRQn interrupt configuration */
+  NVIC_SetPriority(RCC_IRQn, 0);
+  NVIC_EnableIRQ(RCC_IRQn);
+
+  /* Configure the system clock */
+  SystemClock_Config();
+
+  /* Configure SysTick */
+  SysTick->LOAD  = (uint32_t)(SystemCoreClock/1000 - 1UL);          /* set reload register */
+  NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */
+  SysTick->VAL   = 0UL;                                             /* Load the SysTick Counter Value */
+  SysTick->CTRL  = SysTick_CTRL_CLKSOURCE_Msk |
+                   SysTick_CTRL_TICKINT_Msk   |
+                   SysTick_CTRL_ENABLE_Msk;                         /* Enable SysTick IRQ and SysTick Timer */
+
+  /* Processor uses sleep as its low power mode */
+  SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+  /* DisableSleepOnExit */
+  SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPONEXIT_Msk);
+
+  /* Initialize all configured peripherals */
+  GPIO_Init();
+
+  ADC_Init();
+
+  TIM1_Init();
+  TIM3_Init();
+
+  IWDG_Init();
+}
+
+
+/**
+  * @brief System Clock Configuration
+  * @retval None
+  */
+void SystemClock_Config(void)
+{
+  /* HSI configuration and activation */
+  RCC->CR |= RCC_CR_HSION; // Enable HSI
+  while((RCC->CR & RCC_CR_HSIRDY) == 0);
+
+  /* Main PLL configuration and activation */
+  RCC->PLLCFGR = (RCC_PLLCFGR_PLLSRC_HSI | RCC_PLLCFGR_PLLM_0 | (9 << RCC_PLLCFGR_PLLN_Pos) | RCC_PLLCFGR_PLLR_1);
+  RCC->PLLCFGR |= RCC_PLLCFGR_PLLREN; // RCC_PLL_EnableDomain_SYS
+  RCC->CR |= RCC_CR_PLLON; // RCC_PLL_Enable
+  while((RCC->CR & RCC_CR_PLLRDY) == 0);
+
+  /* Sysclk activation on the main PLL */
+  RCC->CFGR &= RCC_CFGR_SW;
+  RCC->CFGR |= RCC_CFGR_SW_1;
+  while((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_1);
+
+  /* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */
+  SystemCoreClock = 24000000;
+}
+
+/**
+  * @brief GPIO Initialization Function
+  * @param None
+  * @retval None
+  */
+static void GPIO_Init(void)
+{
+  /* Servo_1_Pin, Servo_2_Pin - Servos control, Alt PP out, middle speed */
+  GPIO_SetPinMode(Servo_1_Port, (Servo_1_Pin|Servo_2_Pin), GPIO_MODE_AFF);
+  GPIO_SetPinOutputType(Servo_1_Port, (Servo_1_Pin|Servo_2_Pin), GPIO_OTYPE_PP);
+  GPIO_SetPinSpeed(Servo_1_Port, (Servo_1_Pin|Servo_2_Pin), GPIO_OSPEED_LW);
+  GPIO_SetPinPull(Servo_1_Port, (Servo_1_Pin|Servo_2_Pin), GPIO_PUPDR_NO);
+  GPIO_SetAFPin_0_7(Servo_1_Port, (Servo_1_Pin|Servo_2_Pin), GPIO_AF_2);
+
+  /* Photo_Pin: analog in, pull none */
+  GPIO_SetPinPull(Photo_Port, Photo_Pin, GPIO_PUPDR_NO);
+  GPIO_SetPinMode(Photo_Port, Photo_Pin, GPIO_MODE_ANL);
+
+  /* Test out Pin A4 */
+  GPIO_SetPinMode(GPIOA, GPIO_PIN_4, GPIO_MODE_OUT);
+  GPIO_SetPinOutputType(GPIOA, GPIO_PIN_4, GPIO_OTYPE_PP);
+  GPIO_SetPinSpeed(GPIOA, GPIO_PIN_4, GPIO_OSPEED_LW);
+  GPIO_SetPinPull(GPIOA, GPIO_PIN_4, GPIO_PUPDR_NO);
+
+  /* Test in Pin A5 */
+  GPIO_SetPinPull(GPIOA, GPIO_PIN_4, GPIO_PUPDR_UP);
+}
+
+/**
+  * @brief ADC1 Initialization Function
+  * @param None
+  * @retval None
+  */
+static void ADC_Init(void)
+{
+  /* ADC1 interrupt Init */
+  NVIC_SetPriority(ADC1_IRQn, 0);
+  NVIC_EnableIRQ(ADC1_IRQn);
+
+  /* Configure the global features of the ADC
+   * (Clock, Resolution, Data Alignment and number of conversion)
+   */
+  //ADC synchronous clock derived from AHB clock divided by 2
+  ADC1->CFGR2 |= ADC_CFGR2_CKMODE_0;
+
+  /* Poll for ADC channel configuration ready */
+  while ((ADC1->ISR & ADC_ISR_CCRDY) == 0) {};
+  /* Clear flag ADC channel configuration ready */
+  ADC1->ISR |= ADC_ISR_CCRDY;
+
+  ADC1->CFGR1 |= (ADC_CFGR1_EXTSEL_1 | ADC_CFGR1_EXTSEL_0 | ADC_CFGR1_EXTEN_0) | ADC_CFGR1_OVRMOD | ADC_CFGR1_EXTEN_0;
+
+   /* Enable ADC internal voltage regulator */
+   ADC1->CR |= ADC_CR_ADVREGEN; // ???
+
+  /** Configure Regular Channel */
+  ADC1->CHSELR = ADC_CHSELR_CHSEL11;
+
+   /* Poll for ADC channel configuration ready */
+  while ((ADC1->ISR & ADC_ISR_CCRDY) == 0) {};
+  /* Clear flag ADC channel configuration ready */
+  ADC1->ISR |= ADC_ISR_CCRDY;
+
+  // SetChannelSamplingTime
+  ADC1->SMPR |= ADC_SMPR_SMPSEL11;
+
+  /* Calibration in single conversion mode */
+  ADC1->CR |= ADC_CR_ADCAL; // ADC calibration
+  while ((ADC1->CR & ADC_CR_ADCAL) != 0) {};
+
+  /* Enable Interrupt */
+  ADC1->IER |= ADC_IER_EOCIE; // ADC interrupt enable
+  /* Enable ADC */
+  ADC1->CR |= ADC_CR_ADEN; // ADC enable
+  /* Start ADC software conversion */
+  ADC1->CR |= ADC_CR_ADSTART; // ADC start
+}
+
+/**
+  * @brief TIM1 Initialization Function
+  * @param None
+  * @retval None
+  */
+static void TIM1_Init(void)
+{
+  /* target clock */
+  TIM1->PSC = TIM1_PSC; // prescaler
+  TIM1->ARR = TIM1_ARR; // auto reload value
+  TIM1->CR1 = TIM_CR1_ARPE;
+  // initial pwm value
+  TIM1->CCR1 = SERVO_INIT_VAL;
+  TIM1->CCR4 = SERVO_INIT_VAL;
+  // pwm mode 1 for chanels
+  TIM1->CCMR1 = (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1PE);
+  TIM1->CCMR2 = (TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4PE);
+  //TIM1->SR |= TIM_SR_UIF;
+  TIM1->BDTR = TIM_BDTR_MOE; // enable main output
+  TIM1->EGR = TIM_EGR_UG; // force timer update
+  /* TIM1 CC_EnableChannel */
+  TIM1->CCER = (TIM_CCER_CC1E | TIM_CCER_CC1P | TIM_CCER_CC4E | TIM_CCER_CC4P);
+  /* TIM_EnableCounter */
+  TIM1->CR1 |= TIM_CR1_CEN;
+}
+
+/**
+  * @brief TIM3 Initialization Function
+  * @param None
+  * @retval None
+  */
+static void TIM3_Init(void)
+{
+  /* target clock */
+  TIM3->PSC = TIM3_PSC; // prescaler
+  TIM3->ARR = TIM3_ARR; // auto reload value
+  TIM3->CR1 = TIM_CR1_ARPE;
+  // launch timer
+  TIM3->EGR = TIM_EGR_UG; // force timer update
+  /* Set the trigger output 2 (TRGO2) used for ADC synchronization */
+  TIM3->CR2 |= TIM_CR2_MMS2_2; // update event
+  /* TIM3 enable */
+  TIM3->CR1 |= TIM_CR1_CEN;
+}
+
+/**
+  * @brief IWDG Initialization Function
+  * @param None
+  * @retval None
+  */
+static void IWDG_Init(void) 
+{
+  IWDG->KR = 0xCCCC;
+  IWDG->KR = 0x5555;
+  IWDG->PR = 0x0;
+  IWDG->RLR = 4095;
+  while (IWDG->SR != 0x00000000) {};
+
+  IWDG->KR = 0xAAAA;
+}
+
+/**
+  * @brief  Inserts a delay time.
+  * @param  msec: specifies the delay time length, in milliseconds.
+  * @retval None
+  */
+void delay_ms(uint32_t msek) {
+  TDelay = msek;
+
+  do {
+    __WFI();
+  } while (TDelay != 0);
+}
+
+#pragma GCC optimize ("O3")
+/**
+  * @brief  This function handles SysTick Handler.
+  * @param  None
+  * @retval None
+  */
+void SysTick_Handler(void) {
+  if (TDelay != 0) {
+    TDelay --;
+  }
+}

+ 67 - 29
src/main.c

@@ -22,11 +22,16 @@
 /* Private includes ----------------------------------------------------------*/
 /* Private typedef -----------------------------------------------------------*/
 /* Private define ------------------------------------------------------------*/
+#define PHOTO_LEVEL (500)
+
 /* Private macro -------------------------------------------------------------*/
 /* Private variables ---------------------------------------------------------*/
+static const char msg1[] = {"russian warship go fuck yourself!\nfeel free to contact shilvn@gmail.com"};
 volatile flag_t Flag = {0};
+volatile uint32_t photo_Value;
 
 /* Private function prototypes -----------------------------------------------*/
+static void servo_demo(void);
 /* Private user code ---------------------------------------------------------*/
 
 /**
@@ -37,41 +42,58 @@ int main(void)
 {
   /* Initialize onBoard Hardware */
   Board_Init();
+  GPIO_PIN_SET(GPIOA, GPIO_PIN_4);
 
-  /* Initialize Scheduler */
-  RTOS_Init();
-  /* tdelay_ms() work now, I2C can work too */
-
-  /* Initialize Event State Machine */
-  ES_Init(stShowTime);
-
-  /* Init devices at I2C bus */
-  RTC_Init();
-  sensor_Init();
-
-  /* Init Clock module */
-  Clock_Init();
-
-  /** Set tasks for Sheduler */
-  RTOS_SetTask(btnProcess, 1, BTN_SCAN_PERIOD);
-
+  servo_demo();
+/*
+  while (photo_Value <= PHOTO_LEVEL) {
+    IWDG->KR = 0xAAAA;
+    __WFI();
+  }
+*/
+  GPIO_PIN_RES(GPIOA, GPIO_PIN_4);
   /* Infinite loop */
   while (1)
   {
-    /* new second interrupt from RTC */
-    if (Flag.RTC_IRQ != 0) {
-      Flag.RTC_IRQ = 0;
-      new_Second();
-    } /* end of New second */
-
-    es_event_t event = ES_GetEvent();
-    if (event) {
-      ES_Dispatch(event);
+    /* wait for light on */
+    while (photo_Value > PHOTO_LEVEL) {
+    IWDG->KR = 0xAAAA;
+    __WFI();
     }
-
-    RTOS_DispatchTask();
-
+    /* open servo 1 */
+    TIM1->CCR1 = SERVO_OPEN_VAL;
+    /* wait for light off */
+    while (photo_Value <= PHOTO_LEVEL) {
+      IWDG->KR = 0xAAAA;
+      __WFI();
+    }
+    /* close servo 1 */
+    TIM1->CCR1 = SERVO_INIT_VAL;
+    
+    /* wait for light on */
+    while (photo_Value > PHOTO_LEVEL) {
+    IWDG->KR = 0xAAAA;
     __WFI();
+    }
+    /* open servo 2 */
+    TIM1->CCR4 = SERVO_OPEN_VAL;
+    /* wait for light off */
+    while (photo_Value <= PHOTO_LEVEL) {
+      IWDG->KR = 0xAAAA;
+      __WFI();
+    }
+    /* close servo 2 */
+    TIM1->CCR4 = SERVO_INIT_VAL;
+
+    /* end of life */
+    while (1) {
+      char * msg = msg1;
+      while (*msg) {
+        USART1->TDR = *msg++;
+      }
+      IWDG->KR = 0xAAAA;
+      __WFI();
+    }
   }
 } /* End of mine() */
 
@@ -88,6 +110,22 @@ void Error_Handler(void)
   }
 }
 
+static void servo_demo(void) {
+  int i;
+  for (i=SERVO_INIT_VAL; i <= SERVO_OPEN_VAL; i++) {
+    TIM1->CCR1 = i;
+    TIM1->CCR4 = i;
+    delay_ms(10);
+  }
+
+  delay_ms(100);
+  for (i=SERVO_OPEN_VAL; i >= SERVO_INIT_VAL; i--) {
+    TIM1->CCR1 = i;
+    TIM1->CCR4 = i;
+    delay_ms(10);
+  }
+}
+
 #ifdef  USE_FULL_ASSERT
 /**
   * @brief  Reports the name of the source file and the source line number

+ 7 - 181
src/stm32g0xx_it.c

@@ -28,7 +28,7 @@
 /* Private function prototypes -----------------------------------------------*/
 /* Private user code ---------------------------------------------------------*/
 /* External variables --------------------------------------------------------*/
-extern volatile in15_pin_t SymbolIN15;
+extern volatile uint32_t photo_Value;
 
 /******************************************************************************/
 /*           Cortex-M0+ Processor Interruption and Exception Handlers          */
@@ -84,188 +84,14 @@ void PendSV_Handler(void)
 /******************************************************************************/
 
 /**
-  * @brief This function handles EXTI line 4 to 15 interrupts.
+  * @brief This function handles ADC1 interrupt.
   */
-
-void EXTI4_15_IRQHandler(void)
-{
-  if ((EXTI->FPR1 & EXTI_IMR1_IM14) != 0)
-  {
-    EXTI->FPR1 = EXTI_IMR1_IM14;
-    Flag.RTC_IRQ = 1;
-    ES_PlaceEvent(evNewSecond);
-  }
-}
-
-/**
-  * @brief This function handles DMA1 channel 1 interrupt.
-  */
-void DMA1_Channel1_IRQHandler(void)
-{
-  if ((DMA1->ISR & DMA_IFCR_CTCIF1) != 0) {
-    DMA1->IFCR |= DMA_IFCR_CTCIF1; // reset IRQ flag
-
-    Flag.SPI_TX_End = 1;
-
-    /* Stop SPI-DMA transfer */
-    DMA1_Channel1->CCR &= ~DMA_CCR_EN;
-
-    /* Wait for end SPI transmit */
-    LATCH_DOWN;
-    while ((SPI1->SR & SPI_SR_FTLVL) != 0);
-    while ((SPI1->SR & SPI_SR_BSY) != 0);
-    LATCH_UP;
-  }
-}
-
-/**
-  * @brief This function handles DMA1 channel 2 and channel 3 interrupts.
-  */
-void DMA1_Channel2_3_IRQHandler(void)
-{
-  if ((DMA1->ISR & DMA_ISR_TCIF2) != 0) {
-    /* reset IRQ flag */
-    DMA1->IFCR |= DMA_IFCR_CTCIF2;
-    /* Disable DMA channels for I2C RX */
-    DMA1_Channel2->CCR &= ~DMA_CCR_EN;
-    Flag.I2C_RX_End = 1;
-  }
-  if ((DMA1->ISR & DMA_ISR_TEIF2) != 0) {
-    DMA1->IFCR |= DMA_IFCR_CTEIF2;
-    DMA1_Channel2->CCR &= ~DMA_CCR_EN;
-    Flag.I2C_RX_End = 1;
-    Flag.I2C_RX_Err = 1;
-  }
-
-  if ((DMA1->ISR & DMA_ISR_TCIF3) != 0) {
-    /* reset IRQ flag */
-    DMA1->IFCR |= DMA_IFCR_CTCIF3;
-    /* Disable DMA channels for I2C TX */
-    DMA1_Channel3->CCR &= ~DMA_CCR_EN;
-    Flag.I2C_TX_End = 1;
-  }
-  if ((DMA1->ISR & DMA_ISR_TEIF3) != 0) {
-    DMA1->IFCR |= DMA_IFCR_CTEIF3;
-    DMA1_Channel3->CCR &= ~DMA_CCR_EN;
-    Flag.I2C_TX_End = 1;
-    Flag.I2C_TX_Err = 1;
-  }
-}
-
-/**
-  * @brief This function handles TIM14 global interrupt.
-  */
-void TIM14_IRQHandler(void)
-{
-  if ((TIM14->SR & TIM_SR_UIF) != 0) {
-    /* Update interrupt flag */
-    TIM14->SR &= ~TIM_SR_UIF;
-
-    /* enable channels */
-    if (Flag.Blink_1 != 0) {
-      TUBE_A_ON;
-    }
-    if (Flag.Blink_2 != 0) {
-      TUBE_B_ON;
-    }
-    if (Flag.Blink_3 != 0) {
-      TUBE_C_ON;
-    }
-    if (Flag.Blink_4 != 0) {
-      TUBE_D_ON;
-    }
-    if (Flag.Blink_5 != 0) {
-      TUBE_E_ON;
-    }
-  }
-  if ((TIM14->SR & TIM_SR_CC1IF) != 0) {
-    /* Capture/Compare Interrupt flag */
-    TIM14->SR &= ~TIM_SR_CC1IF;
-
-    /* disable unneeded channel */
-    if (Flag.Blink_1 != 0) {
-      TUBE_A_OFF;
-    }
-    if (Flag.Blink_2 != 0) {
-      TUBE_B_OFF;
-    }
-    if (Flag.Blink_3 != 0) {
-      TUBE_C_OFF;
-    }
-    if (Flag.Blink_4 != 0) {
-      TUBE_D_OFF;
-    }
-    if (Flag.Blink_5 != 0) {
-      TUBE_E_OFF;
-    }
-  }
-}
-
-/**
-  * @brief This function handles TIM16 global interrupt.
-  */
-#define STOP_FADE_TIME  20
-void TIM16_IRQHandler(void)
-{
-  static in15_pin_t sym_old = sym_Off;
-  static uint8_t ph = 0;
-  static uint8_t on = 0;
-  static uint8_t cnt = 0;
-
-  if ((TIM16->SR & TIM_SR_UIF) != 0) {
-    /* Clear interrupt flag */
-    TIM16->SR = 0;
-
-    if (SymbolIN15 != sym_None) {
-      if (cnt > 0) {
-        cnt --;
-      } else {
-
-        if (ph == 0) {
-          ph = 1;
-          GPIOA->BSRR = SymbolIN15;
-          if (on < STOP_FADE_TIME) {
-            on += 2;
-            cnt = on;
-          } else {
-            ph = 0; on = 0; cnt = 0;
-            sym_old = SymbolIN15;
-            SymbolIN15 = sym_None;
-          }
-        } else {
-          ph = 0;
-          GPIOA->BSRR = sym_old;
-          cnt = STOP_FADE_TIME - on;
-        }
-
-      } /* cnt == 0 */
-    } /* SymbolIN15 not empty */
-  }
-}
-
-/**
-  * @brief This function handles TIM17 global interrupt.
-  */
-void TIM17_IRQHandler(void)
-{
-  if ((TIM17->SR & TIM_SR_UIF) != 0) {
-    /* Update interrupt flag */
-    TIM17->SR = 0;
-  }
-}
-
-/**
-  * @brief This function handles SPI1 global interrupt.
-  */
-void SPI1_IRQHandler(void)
-{
-}
-
-/**
-  * @brief This function handles USART1 global interrupt / USART1 wake-up interrupt through EXTI line 25.
-  */
-void USART1_IRQHandler(void)
+void ADC1_IRQHandler(void)
 {
+  /* read ADC value */
+  photo_Value = ADC1->DR;
+  /* Clear the EOC flag */
+  ADC1->ISR |= ADC_ISR_EOC;
 }
 
 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/