Browse Source

Added one wire

Thomas Chef 3 years ago
parent
commit
fc9a1934ff

+ 2 - 0
STM32/Core/Inc/main.h

@@ -49,6 +49,8 @@ extern "C" {
 
 /* USER CODE END EM */
 
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
+
 /* Exported functions prototypes ---------------------------------------------*/
 void Error_Handler(void);
 

+ 19 - 0
STM32/Core/Inc/oneWire.h

@@ -0,0 +1,19 @@
+/*
+ * oneWire.h
+ *
+ *  Created on: 31 Jan 2022
+ *      Author: thomaschef
+ */
+
+#ifndef INC_ONEWIRE_H_
+#define INC_ONEWIRE_H_
+
+
+void initReadTemp();
+float readTemperature();
+
+void testOneWireTimingFunc();
+
+
+
+#endif /* INC_ONEWIRE_H_ */

+ 25 - 0
STM32/Core/Inc/oneWireDriver.h

@@ -0,0 +1,25 @@
+/*
+ * oneWireDriver.h
+ *
+ *  Created on: 1 Feb 2022
+ *      Author: thomaschef
+ */
+
+#ifndef INC_ONEWIREDRIVER_H_
+#define INC_ONEWIREDRIVER_H_
+
+void init_gpio_pin();
+void us_delay(uint16_t delay);
+void init_gpio_pin(void);
+void gpio_set_input(void);
+void gpio_set_output(void);
+int readInput();
+void writeBitHigh();
+void writeBitLow();
+void writeSlot(uint8_t data);
+uint8_t readSlot(void);
+void writeByte(uint8_t data);
+uint8_t readByte(void);
+uint8_t oneWire_init(void);
+
+#endif /* INC_ONEWIREDRIVER_H_ */

+ 1 - 1
STM32/Core/Inc/stm32f1xx_hal_conf.h

@@ -64,7 +64,7 @@
 /*#define HAL_SMARTCARD_MODULE_ENABLED   */
 /*#define HAL_SPI_MODULE_ENABLED   */
 /*#define HAL_SRAM_MODULE_ENABLED   */
-/*#define HAL_TIM_MODULE_ENABLED   */
+#define HAL_TIM_MODULE_ENABLED
 #define HAL_UART_MODULE_ENABLED
 /*#define HAL_USART_MODULE_ENABLED   */
 /*#define HAL_WWDG_MODULE_ENABLED   */

STM32/Core/Src/uart.h → STM32/Core/Inc/uart.h


+ 112 - 9
STM32/Core/Src/main.c

@@ -22,6 +22,8 @@
 /* Private includes ----------------------------------------------------------*/
 /* USER CODE BEGIN Includes */
 #include<stdio.h>
+#include "oneWire.h"
+#include "oneWireDriver.h"
 
 /* USER CODE END Includes */
 
@@ -42,6 +44,8 @@
 /* Private variables ---------------------------------------------------------*/
 ADC_HandleTypeDef hadc1;
 
+TIM_HandleTypeDef htim1;
+
 UART_HandleTypeDef huart2;
 
 /* USER CODE BEGIN PV */
@@ -55,6 +59,7 @@ void SystemClock_Config(void);
 static void MX_GPIO_Init(void);
 static void MX_USART2_UART_Init(void);
 static void MX_ADC1_Init(void);
+static void MX_TIM1_Init(void);
 static void MX_NVIC_Init(void);
 /* USER CODE BEGIN PFP */
 
@@ -75,13 +80,20 @@ static void MX_NVIC_Init(void);
 uint16_t getADCDiff() {
 
 	volatile uint32_t firstCnt;
-	volatile uint16_t value;
-	do {
-		firstCnt = adcCounter;
-		value = maxWaveDiff;
+	int32_t timeoutCnt = 20;
+
+	firstCnt = adcCounter;
+	ADC1->CR1  = ADC_IT_EOC; // Enable interrupts
+
+	while( timeoutCnt > 0 && adcCounter < (firstCnt+3) ) {
+		timeoutCnt--;
+		HAL_Delay(10);	// Three measurements takes around 140mS. 20*10 = 200mS timeout
+	}
+	ADC1->CR1  = 0; // Disable interrupts
 
-	} while( firstCnt != adcCounter );
-	return value;
+	if( timeoutCnt == 0 ) return 0;
+
+	return maxWaveDiff;
 }
 
 
@@ -117,21 +129,26 @@ int main(void)
   MX_GPIO_Init();
   MX_USART2_UART_Init();
   MX_ADC1_Init();
+  MX_TIM1_Init();
 
   /* Initialize interrupts */
   MX_NVIC_Init();
   /* USER CODE BEGIN 2 */
 
+  // Start TIM1 (used for uS delays)
+  HAL_TIM_Base_Start(&htim1);
+
   // Enable USART1 Interrupts
   USART2->CR1 |= USART_CR1_RXNEIE | USART_CR1_TXEIE;
 
-
+  // Enable OneWire sensors
+  init_gpio_pin();
 
   // Start continous ADC-conversion
   HAL_Delay(10);
   ADC1->SR   = 0;
   ADC1->CR2  = ADC_CR2_ADON | ADC_CR2_CONT;
-  ADC1->CR1  = ADC_IT_EOC;
+  //ADC1->CR1  = ADC_IT_EOC; // Only start IT_EOC when actually reading data
   ADC1->CR2 |= ADC_CR2_ADON;
 
 
@@ -142,6 +159,8 @@ int main(void)
 
   printf("VVB Energy Sensor\n");
 
+//  testOneWireTimingFunc();
+
 
 
   while (1)
@@ -151,10 +170,13 @@ int main(void)
     /* USER CODE BEGIN 3 */
 	  HAL_GPIO_TogglePin (GPIOC, GPIO_PIN_13);
 	  HAL_Delay (500);
+	  initReadTemp();
+	  HAL_Delay(750);
+	  float temp = readTemperature();
 
 
 
-	  printf("Cnt:%lu  Diff:%u   mV:%u \n",adcCounter, getADCDiff(), (getADCDiff()*805)/1000);
+	  printf("Cnt:%lu  Diff:%u   mV:%u  %f\n",adcCounter, getADCDiff(), (getADCDiff()*805)/1000, temp);
 
   }
   /* USER CODE END 3 */
@@ -285,6 +307,81 @@ static void MX_ADC1_Init(void)
 
 }
 
+/**
+  * @brief TIM1 Initialization Function
+  * @param None
+  * @retval None
+  */
+static void MX_TIM1_Init(void)
+{
+
+  /* USER CODE BEGIN TIM1_Init 0 */
+
+  /* USER CODE END TIM1_Init 0 */
+
+  TIM_ClockConfigTypeDef sClockSourceConfig = {0};
+  TIM_MasterConfigTypeDef sMasterConfig = {0};
+  TIM_OC_InitTypeDef sConfigOC = {0};
+  TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
+
+  /* USER CODE BEGIN TIM1_Init 1 */
+
+  /* USER CODE END TIM1_Init 1 */
+  htim1.Instance = TIM1;
+  htim1.Init.Prescaler = 55;
+  htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
+  htim1.Init.Period = 0xfffe;
+  htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+  htim1.Init.RepetitionCounter = 0;
+  htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+  if (HAL_TIM_Base_Init(&htim1) != HAL_OK)
+  {
+    Error_Handler();
+  }
+  sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
+  if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK)
+  {
+    Error_Handler();
+  }
+  if (HAL_TIM_OC_Init(&htim1) != HAL_OK)
+  {
+    Error_Handler();
+  }
+  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
+  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
+  if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
+  {
+    Error_Handler();
+  }
+  sConfigOC.OCMode = TIM_OCMODE_FORCED_ACTIVE;
+  sConfigOC.Pulse = 0;
+  sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+  sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+  sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+  sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
+  sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+  if (HAL_TIM_OC_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
+  {
+    Error_Handler();
+  }
+  sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
+  sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
+  sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
+  sBreakDeadTimeConfig.DeadTime = 0;
+  sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
+  sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
+  sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
+  if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
+  {
+    Error_Handler();
+  }
+  /* USER CODE BEGIN TIM1_Init 2 */
+
+  /* USER CODE END TIM1_Init 2 */
+  HAL_TIM_MspPostInit(&htim1);
+
+}
+
 /**
   * @brief USART2 Initialization Function
   * @param None
@@ -342,6 +439,12 @@ static void MX_GPIO_Init(void)
   GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_MEDIUM;
   HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
 
+  /*Configure GPIO pin : PC14 */
+  GPIO_InitStruct.Pin = GPIO_PIN_14;
+  GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+  GPIO_InitStruct.Pull = GPIO_NOPULL;
+  HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
 }
 
 /* USER CODE BEGIN 4 */

+ 64 - 0
STM32/Core/Src/oneWire.c

@@ -0,0 +1,64 @@
+#include "stm32f1xx_hal.h"
+#include "oneWireDriver.h"
+#include<stdio.h>
+
+
+uint8_t check = 2, temp_l = 0, temp_h = 0;
+int16_t temp = 0;
+float temperature;
+int tempInt;
+
+
+
+
+
+void testOneWireTimingFunc() {
+
+	HAL_Delay(100);
+	gpio_set_input(); // set as output
+	while(1) {
+		writeByte(0xAA);
+		us_delay(100);
+		/*writeBitOn();
+		us_delay(40);
+		gpio_set_input(); // set as output
+		us_delay(10);
+		gpio_set_output(); // set as output
+		writeBitOff();
+		us_delay(20);
+		*/
+	}
+}
+
+void initReadTemp()
+{
+    uint32_t noOfSlots = 0;
+	oneWire_init();
+    writeByte(0xCC); // skip ROM
+    writeByte(0x44); // convert t
+    while( readSlot() == 0 ) {
+    	noOfSlots++;
+    	us_delay(10);
+    }
+    printf("Sl:%u\n",noOfSlots);
+}
+
+float readTemperature()
+{
+	uint8_t retVal = oneWire_init();
+    writeByte(0xCC); // skip ROM
+    writeByte(0xBE); // Read Scratchpad
+    temp_l = readByte();
+    temp_h = readByte();
+    uint8_t b3 = readByte();
+    uint8_t b4 = readByte();
+    uint8_t b5 = readByte();
+    uint8_t b6 = readByte();
+    uint8_t b7 = readByte();
+    uint8_t b8 = readByte();
+    temp = (int16_t)((temp_h << 8) | temp_l);
+    temperature = (float)temp / 16;
+    printf("retVal=%u    %u %u %u %u %u ",retVal,temp_l,temp_h,b3,b4,b5);
+    printf(" %u %u %u\n",b6,b7,b8);
+    return temperature;
+}

+ 130 - 0
STM32/Core/Src/oneWireDriver.c

@@ -0,0 +1,130 @@
+#include "stm32f1xx_hal.h"
+#include<stdio.h>
+
+#define DS18B20_PIN GPIO_PIN_14
+#define DS18B20_PORT GPIOC
+
+void us_delay(uint16_t delay)
+{
+    TIM1->CNT = 0;
+    while (TIM1->CNT < delay);
+}
+
+/**
+ * Control registers for F1xx GPIOs are 2 x 2 bits
+ * For Port C, CRH, pin 14 bits 27-24
+ * CNF: Input mode: 01=Float input  Output mode: 01=Open-drain (Reset stage is 01)
+ * MODE: 00=Input   10=Out 2 MHz
+ *
+ * So bits should be for                   |   XXXX                       |
+ * Input:  0100     AND-Mask: 0xF4FFFFFF   11110100111111111111111111111111
+ * Output: 0110      OR-Mask: 0x06000000   00000110000000000000000000000000
+ *
+ * For init use OR 0x04000000 and then AND 0xF4FFFFFF = Input
+ *
+ */
+void init_gpio_pin(void)
+{
+    DS18B20_PORT->CRH |= 0x04000000;
+    DS18B20_PORT->CRH &= 0xF4FFFFFF;
+}
+void gpio_set_input(void)
+{
+    DS18B20_PORT->CRH &= 0xF4FFFFFF;
+    DS18B20_PORT->BSRR = (1 << 14);
+}
+
+void gpio_set_output(void)
+{
+    DS18B20_PORT->BSRR = (1 << 14);
+    DS18B20_PORT->CRH |= 0x06000000;
+}
+
+int readInput()
+{
+    if (((DS18B20_PORT->IDR) & (1 << 14)) == 0)
+        return 0;
+    else
+        return 1;
+}
+
+void writeBitHigh()  { DS18B20_PORT->BSRR = (1 << 14); }
+void writeBitLow() { DS18B20_PORT->BSRR = (1 << 30); }
+
+void writeSlot(uint8_t data) {
+	gpio_set_output(); // set as output
+	if( data == 1 ) {
+		// write 1
+		writeBitLow();
+		us_delay(1);
+		writeBitHigh();
+		us_delay(64);
+	}
+	else {
+		// write 0
+		writeBitLow();
+		us_delay(65);
+		writeBitHigh();
+	}
+	gpio_set_input();
+	us_delay(5);
+}
+
+
+uint8_t readSlot(void) {
+	uint8_t retVal = 0;
+    gpio_set_output(); // set as output
+    writeBitLow();
+    us_delay(1);
+    writeBitHigh();
+    gpio_set_input();  // 2.5mS has passed
+    us_delay(10);	   // 12.5mS has passed
+    if (readInput() == 1) // if the pin is HIGH
+    {
+    	retVal = 1;
+    }
+    us_delay(55);
+    return retVal;
+}
+
+void writeByte(uint8_t data)
+{
+    for (int i = 0; i < 8; i++)
+    {
+    	writeSlot( ((data & (1 << i)) == 0) ? 0:1 );
+    }
+}
+
+
+uint8_t readByte(void)
+{
+    uint8_t value = 0;
+
+    for (int i = 0; i < 8; i++)
+    {
+        if (readSlot() == 1) value |= 1 << i;
+    }
+    return value;
+}
+
+uint8_t oneWire_init(void)
+{
+    volatile int i;
+    uint8_t retVal = 0;
+
+    gpio_set_output();
+    writeBitLow();
+    us_delay(500);
+    writeBitHigh();
+    gpio_set_input();
+
+    us_delay(20);
+
+    for(i=0;i<48;i++) {     // We must wait minimum 480uS in total. Every loop is 10uS
+
+        if( readInput() == 0 ) retVal = 1; // Ok, sensor was found
+        us_delay(10);
+    }
+
+    return retVal;
+}

+ 71 - 1
STM32/Core/Src/stm32f1xx_hal_msp.c

@@ -57,7 +57,9 @@
 /* USER CODE BEGIN 0 */
 
 /* USER CODE END 0 */
-/**
+
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
+                    /**
   * Initializes the Global MSP.
   */
 void HAL_MspInit(void)
@@ -142,6 +144,74 @@ void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc)
 
 }
 
+/**
+* @brief TIM_Base MSP Initialization
+* This function configures the hardware resources used in this example
+* @param htim_base: TIM_Base handle pointer
+* @retval None
+*/
+void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base)
+{
+  if(htim_base->Instance==TIM1)
+  {
+  /* USER CODE BEGIN TIM1_MspInit 0 */
+
+  /* USER CODE END TIM1_MspInit 0 */
+    /* Peripheral clock enable */
+    __HAL_RCC_TIM1_CLK_ENABLE();
+  /* USER CODE BEGIN TIM1_MspInit 1 */
+
+  /* USER CODE END TIM1_MspInit 1 */
+  }
+
+}
+
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
+{
+  GPIO_InitTypeDef GPIO_InitStruct = {0};
+  if(htim->Instance==TIM1)
+  {
+  /* USER CODE BEGIN TIM1_MspPostInit 0 */
+
+  /* USER CODE END TIM1_MspPostInit 0 */
+
+    __HAL_RCC_GPIOA_CLK_ENABLE();
+    /**TIM1 GPIO Configuration
+    PA8     ------> TIM1_CH1
+    */
+    GPIO_InitStruct.Pin = GPIO_PIN_8;
+    GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+    GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+    HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+  /* USER CODE BEGIN TIM1_MspPostInit 1 */
+
+  /* USER CODE END TIM1_MspPostInit 1 */
+  }
+
+}
+/**
+* @brief TIM_Base MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param htim_base: TIM_Base handle pointer
+* @retval None
+*/
+void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base)
+{
+  if(htim_base->Instance==TIM1)
+  {
+  /* USER CODE BEGIN TIM1_MspDeInit 0 */
+
+  /* USER CODE END TIM1_MspDeInit 0 */
+    /* Peripheral clock disable */
+    __HAL_RCC_TIM1_CLK_DISABLE();
+  /* USER CODE BEGIN TIM1_MspDeInit 1 */
+
+  /* USER CODE END TIM1_MspDeInit 1 */
+  }
+
+}
+
 /**
 * @brief UART MSP Initialization
 * This function configures the hardware resources used in this example

+ 1 - 0
STM32/Core/Src/uart.c

@@ -37,6 +37,7 @@ PUTCHAR_PROTOTYPE
 
 	uart_send_byte(c);
 	//HAL_UART_Transmit(&huart2, (uint8_t *)&ch, 1, 0xFFFF);
+	return ch;
 }
 
 

+ 27 - 12
STM32/VVBPowerSensor.ioc

@@ -14,20 +14,24 @@ Mcu.IP0=ADC1
 Mcu.IP1=NVIC
 Mcu.IP2=RCC
 Mcu.IP3=SYS
-Mcu.IP4=USART2
-Mcu.IPNb=5
+Mcu.IP4=TIM1
+Mcu.IP5=USART2
+Mcu.IPNb=6
 Mcu.Name=STM32F103C(8-B)Tx
 Mcu.Package=LQFP48
 Mcu.Pin0=PC13-TAMPER-RTC
-Mcu.Pin1=PD0-OSC_IN
-Mcu.Pin2=PD1-OSC_OUT
-Mcu.Pin3=PA2
-Mcu.Pin4=PA3
-Mcu.Pin5=PA5
-Mcu.Pin6=PA13
-Mcu.Pin7=PA14
-Mcu.Pin8=VP_SYS_VS_Systick
-Mcu.PinsNb=9
+Mcu.Pin1=PC14-OSC32_IN
+Mcu.Pin10=VP_SYS_VS_Systick
+Mcu.Pin11=VP_TIM1_VS_ClockSourceINT
+Mcu.Pin2=PD0-OSC_IN
+Mcu.Pin3=PD1-OSC_OUT
+Mcu.Pin4=PA2
+Mcu.Pin5=PA3
+Mcu.Pin6=PA5
+Mcu.Pin7=PA8
+Mcu.Pin8=PA13
+Mcu.Pin9=PA14
+Mcu.PinsNb=12
 Mcu.ThirdPartyNb=0
 Mcu.UserConstants=
 Mcu.UserName=STM32F103C8Tx
@@ -56,11 +60,14 @@ PA3.Mode=Asynchronous
 PA3.Signal=USART2_RX
 PA5.Locked=true
 PA5.Signal=ADCx_IN5
+PA8.Signal=S_TIM1_CH1
 PC13-TAMPER-RTC.GPIOParameters=GPIO_Speed,PinState
 PC13-TAMPER-RTC.GPIO_Speed=GPIO_SPEED_FREQ_MEDIUM
 PC13-TAMPER-RTC.Locked=true
 PC13-TAMPER-RTC.PinState=GPIO_PIN_SET
 PC13-TAMPER-RTC.Signal=GPIO_Output
+PC14-OSC32_IN.Locked=true
+PC14-OSC32_IN.Signal=GPIO_Input
 PD0-OSC_IN.Mode=HSE-External-Oscillator
 PD0-OSC_IN.Signal=RCC_OSC_IN
 PD1-OSC_OUT.Mode=HSE-External-Oscillator
@@ -93,7 +100,7 @@ ProjectManager.StackSize=0x400
 ProjectManager.TargetToolchain=STM32CubeIDE
 ProjectManager.ToolChainLocation=
 ProjectManager.UnderRoot=true
-ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_USART2_UART_Init-USART2-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true
+ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_USART2_UART_Init-USART2-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true,5-MX_TIM1_Init-TIM1-false-HAL-true
 RCC.ADCFreqValue=14000000
 RCC.ADCPresc=RCC_ADCPCLK2_DIV4
 RCC.AHBFreq_Value=56000000
@@ -118,10 +125,18 @@ RCC.USBFreq_Value=56000000
 RCC.VCOOutput2Freq_Value=8000000
 SH.ADCx_IN5.0=ADC1_IN5,IN5
 SH.ADCx_IN5.ConfNb=1
+SH.S_TIM1_CH1.0=TIM1_CH1,Forced Output1 CH1
+SH.S_TIM1_CH1.ConfNb=1
+TIM1.Channel-Forced\ Output1\ CH1=TIM_CHANNEL_1
+TIM1.IPParameters=Prescaler,Period,Channel-Forced Output1 CH1
+TIM1.Period=0xfffe
+TIM1.Prescaler=55
 USART2.BaudRate=19200
 USART2.IPParameters=VirtualMode,BaudRate
 USART2.VirtualMode=VM_ASYNC
 VP_SYS_VS_Systick.Mode=SysTick
 VP_SYS_VS_Systick.Signal=SYS_VS_Systick
+VP_TIM1_VS_ClockSourceINT.Mode=Internal
+VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
 board=custom
 isbadioc=false