summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Makefile200
-rw-r--r--src/main-hs.c322
2 files changed, 124 insertions, 398 deletions
diff --git a/Makefile b/Makefile
deleted file mode 100644
index 761fa4c..0000000
--- a/Makefile
+++ /dev/null
@@ -1,200 +0,0 @@
-##########################################################################################################################
-# File automatically-generated by tool: [projectgenerator] version: [3.5.2] date: [Mon Mar 23 16:58:19 EDT 2020]
-##########################################################################################################################
-
-# ------------------------------------------------
-# Generic Makefile (based on gcc)
-#
-# ChangeLog :
-# 2017-02-10 - Several enhancements + project update mode
-# 2015-07-22 - first version
-# ------------------------------------------------
-
-######################################
-# target
-######################################
-TARGET = master
-
-
-######################################
-# building variables
-######################################
-# debug build?
-DEBUG = 1
-# optimization
-OPT = -Og
-
-
-#######################################
-# paths
-#######################################
-# Build path
-BUILD_DIR = build
-
-######################################
-# source
-######################################
-# C sources
-C_SOURCES = \
-src/main-hs.c \
-src/stm32f4xx_it.c \
-src/stm32f4xx_hal_msp.c \
-src/system_stm32f4xx.c \
-src/pb_decode.c \
-src/pb_encode.c \
-src/pb_common.c \
-src/handshake.pb.c \
-lib/f4/stm32f4xx_hal_i2c.c \
-lib/f4/stm32f4xx_hal_i2c_ex.c \
-lib/f4/stm32f4xx_hal_rcc.c \
-lib/f4/stm32f4xx_hal_rcc_ex.c \
-lib/f4/stm32f4xx_hal_flash.c \
-lib/f4/stm32f4xx_hal_flash_ex.c \
-lib/f4/stm32f4xx_hal_flash_ramfunc.c \
-lib/f4/stm32f4xx_hal_gpio.c \
-lib/f4/stm32f4xx_hal_dma_ex.c \
-lib/f4/stm32f4xx_hal_dma.c \
-lib/f4/stm32f4xx_hal_pwr.c \
-lib/f4/stm32f4xx_hal_pwr_ex.c \
-lib/f4/stm32f4xx_hal_cortex.c \
-lib/f4/stm32f4xx_hal.c \
-lib/f4/stm32f4xx_hal_exti.c \
-lib/f4/stm32f4xx_hal_tim.c \
-lib/f4/stm32f4xx_hal_tim_ex.c \
-lib/f4/stm32f4xx_hal_uart.c
-
-# ASM sources
-ASM_SOURCES = \
-startup_stm32f401xc.s
-
-
-#######################################
-# binaries
-#######################################
-PREFIX = arm-none-eabi-
-# The gcc compiler bin path can be either defined in make command via GCC_PATH variable (> make GCC_PATH=xxx)
-# either it can be added to the PATH environment variable.
-ifdef GCC_PATH
-CC = $(GCC_PATH)/$(PREFIX)gcc
-AS = $(GCC_PATH)/$(PREFIX)gcc -x assembler-with-cpp
-CP = $(GCC_PATH)/$(PREFIX)objcopy
-SZ = $(GCC_PATH)/$(PREFIX)size
-else
-CC = $(PREFIX)gcc
-AS = $(PREFIX)gcc -x assembler-with-cpp
-CP = $(PREFIX)objcopy
-SZ = $(PREFIX)size
-endif
-HEX = $(CP) -O ihex
-BIN = $(CP) -O binary -S
-
-#######################################
-# CFLAGS
-#######################################
-# cpu
-CPU = -mcpu=cortex-m4
-
-# fpu
-FPU = -mfpu=fpv4-sp-d16
-
-# float-abi
-FLOAT-ABI = -mfloat-abi=hard
-
-# mcu
-MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI)
-
-# macros for gcc
-# AS defines
-AS_DEFS =
-
-# C defines
-C_DEFS = \
--DUSE_HAL_DRIVER \
--DSTM32F401xC
-
-
-# AS includes
-AS_INCLUDES =
-
-# C includes
-C_INCLUDES = \
--Isrc \
--Ilib/f4 \
--Ilib/f4/Legacy \
--Ilib/cmsis \
--Ilib/cmsis/f4
-
-
-
-
-
-# compile gcc flags
-ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
-
-CFLAGS = $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
-
-ifeq ($(DEBUG), 1)
-CFLAGS += -g -gdwarf-2
-endif
-
-
-# Generate dependency information
-CFLAGS += -MMD -MP -MF"$(@:%.o=%.d)"
-
-
-#######################################
-# LDFLAGS
-#######################################
-# link script
-LDSCRIPT = STM32F401CCUx_FLASH.ld
-
-# libraries
-LIBS = -lc -lm -lnosys
-LIBDIR =
-LDFLAGS = $(MCU) -specs=nosys.specs -specs=nano.specs -u _printf_float -T$(LDSCRIPT) $(LIBDIR) $(LIBS) -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections
-
-# default action: build all
-all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin
-
-
-#######################################
-# build the application
-#######################################
-# list of objects
-OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(C_SOURCES:.c=.o)))
-vpath %.c $(sort $(dir $(C_SOURCES)))
-# list of ASM program objects
-OBJECTS += $(addprefix $(BUILD_DIR)/,$(notdir $(ASM_SOURCES:.s=.o)))
-vpath %.s $(sort $(dir $(ASM_SOURCES)))
-
-$(BUILD_DIR)/%.o: %.c Makefile | $(BUILD_DIR)
- $(CC) -c $(CFLAGS) -Wa,-a,-ad,-alms=$(BUILD_DIR)/$(notdir $(<:.c=.lst)) $< -o $@
-
-$(BUILD_DIR)/%.o: %.s Makefile | $(BUILD_DIR)
- $(AS) -c $(CFLAGS) $< -o $@
-
-$(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) Makefile
- $(CC) $(OBJECTS) $(LDFLAGS) -o $@
- $(SZ) $@
-
-$(BUILD_DIR)/%.hex: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
- $(HEX) $< $@
-
-$(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
- $(BIN) $< $@
-
-$(BUILD_DIR):
- mkdir $@
-
-#######################################
-# clean up
-#######################################
-clean:
- -rm -fR $(BUILD_DIR)/*
-
-#######################################
-# dependencies
-#######################################
--include $(wildcard $(BUILD_DIR)/*.d)
-
-# *** EOF ***
diff --git a/src/main-hs.c b/src/main-hs.c
index e843b66..9a98fd4 100644
--- a/src/main-hs.c
+++ b/src/main-hs.c
@@ -6,42 +6,24 @@
******************************************************************************
* @attention
*
-* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
-* All rights reserved.</center></h2>
-*
-* 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"
-/* Private includes ----------------------------------------------------------*/
-/* USER CODE BEGIN Includes */
+/* Standard library includes */
#include <stdio.h>
+
+/* Library includes */
#include <pb_encode.h>
#include <pb_decode.h>
#include "handshake.pb.h"
+
+/* Project includes */
#include "devices.h"
#include "config.h"
-/* USER CODE END Includes */
-
-/* Private typedef -----------------------------------------------------------*/
-/* USER CODE BEGIN PTD */
-
-/* USER CODE END PTD */
-
-/* Private define ------------------------------------------------------------*/
-/* USER CODE BEGIN PD */
-/* USER CODE END PD */
+#include "main.h"
-/* Private macro -------------------------------------------------------------*/
-/* USER CODE BEGIN PM */
+/* Private Macros */
#define device_MDR s2m_MDR_response
#define GET_IDX_FROM_ADDR(i2c_addr) i2c_addr-1
#define GET_BIT_FROM_IDX(a, b) a[b>>5]&(1<<(b%32))
@@ -49,75 +31,51 @@
#define COUNTOF(__BUFFER__) (sizeof(__BUFFER__) / sizeof(*(__BUFFER__)))
#define I2C_ADDRESS 0x05
-
#define BUS_DEVICE_LIMIT 128
+
/* Macro to toggle between master and slave firmware */
/* #define MASTER */
-/* USER CODE END PM */
-/* Private variables ---------------------------------------------------------*/
+/* Private globals */
I2C_HandleTypeDef hi2c1;
-
UART_HandleTypeDef huart1;
-/* USER CODE BEGIN PV */
device_info_t *device_info[BUS_DEVICE_LIMIT] = {NULL};
subscription_info_t* subs_info[BUS_DEVICE_LIMIT];
uint32_t allocated[4]={0};
uint8_t dev_sts[BUS_DEVICE_LIMIT] = {OFFLINE};
-/* USER CODE END PV */
-/* Private function prototypes -----------------------------------------------*/
+/* Function prototypes */
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_I2C1_Init(void);
static void MX_USART1_UART_Init(void);
-/* USER CODE BEGIN PFP */
bool decode_subscriptions_callback(pb_istream_t *istream, const pb_field_t *field, void **args);
hs_status_t handshake(uint32_t i2c_addr);
bool todo_hs_or_not_todo_hs(uint8_t i2c_addr);
state_t get_state_from_hs_status(uint16_t device_addr, hs_status_t hs_status);
bool encode_subscription_callback(pb_ostream_t *ostream, const pb_field_t *field, void * const *arg);
-/* USER CODE END PFP */
-
-/* Private user code ---------------------------------------------------------*/
-/* USER CODE BEGIN 0 */
-/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
-{
- /* USER CODE BEGIN 1 */
-
- /* USER CODE END 1 */
-
-
- /* MCU Configuration--------------------------------------------------------*/
+{
+ /* MCU Configuration */
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
- /* USER CODE BEGIN Init */
-
- /* USER CODE END Init */
-
/* Configure the system clock */
SystemClock_Config();
- /* USER CODE BEGIN SysInit */
-
- /* USER CODE END SysInit */
-
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_I2C1_Init();
MX_USART1_UART_Init();
- /* USER CODE BEGIN 2 */
#ifdef TESTING_ENABLE
#ifdef MASTER
@@ -138,7 +96,7 @@ int main(void)
}
}
-#else /* MASTER */
+#else /* Slave code*/
{
uint8_t MDR_buf[128], debug_buf[128], term[]="\r\n";
size_t MDR_enc_size;
@@ -292,151 +250,12 @@ int main(void)
}
#endif /* MASTER */
- /* USER CODE END 2 */
- /* Infinite loop */
- /* USER CODE BEGIN WHILE */
while (1)
{
- /* USER CODE END WHILE */
- /* USER CODE BEGIN 3 */
-
- }
- /* USER CODE END 3 */
-}
-
-/**
- * @brief System Clock Configuration
- * @retval None
- */
-void SystemClock_Config(void)
-{
- RCC_OscInitTypeDef RCC_OscInitStruct = {0};
- RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
-
- /** Configure the main internal regulator output voltage
- */
- __HAL_RCC_PWR_CLK_ENABLE();
- __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2);
- /** Initializes the CPU, AHB and APB busses clocks
- */
- RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
- RCC_OscInitStruct.HSIState = RCC_HSI_ON;
- RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
- RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
- if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
- {
- Error_Handler();
- }
- /** Initializes the CPU, AHB and APB busses clocks
- */
- RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
- |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
- RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI;
- RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
- RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
- RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
- if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK)
- {
- Error_Handler();
}
}
-/**
- * @brief I2C1 Initialization Function
- * @param None
- * @retval None
- */
-static void MX_I2C1_Init(void)
-{
-
- /* USER CODE BEGIN I2C1_Init 0 */
-
- /* USER CODE END I2C1_Init 0 */
-
- /* USER CODE BEGIN I2C1_Init 1 */
-
- /* USER CODE END I2C1_Init 1 */
- hi2c1.Instance = I2C1;
- hi2c1.Init.ClockSpeed = 100000;
- hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2;
- hi2c1.Init.OwnAddress1 = I2C_ADDRESS;
- hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
- hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
- hi2c1.Init.OwnAddress2 = 0xFF;
- hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
- hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
- if (HAL_I2C_Init(&hi2c1) != HAL_OK)
- {
- Error_Handler();
- }
- /* USER CODE BEGIN I2C1_Init 2 */
-
- /* USER CODE END I2C1_Init 2 */
-
-}
-
-/**
- * @brief USART1 Initialization Function
- * @param None
- * @retval None
- */
-static void MX_USART1_UART_Init(void)
-{
-
- /* USER CODE BEGIN USART1_Init 0 */
-
- /* USER CODE END USART1_Init 0 */
-
- /* USER CODE BEGIN USART1_Init 1 */
-
- /* USER CODE END USART1_Init 1 */
- huart1.Instance = USART1;
- huart1.Init.BaudRate = 9600;
- huart1.Init.WordLength = UART_WORDLENGTH_8B;
- huart1.Init.StopBits = UART_STOPBITS_1;
- huart1.Init.Parity = UART_PARITY_NONE;
- huart1.Init.Mode = UART_MODE_TX_RX;
- huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
- huart1.Init.OverSampling = UART_OVERSAMPLING_16;
- if (HAL_UART_Init(&huart1) != HAL_OK)
- {
- Error_Handler();
- }
- /* USER CODE BEGIN USART1_Init 2 */
-
- /* USER CODE END USART1_Init 2 */
-
-}
-
-/**
- * @brief GPIO Initialization Function
- * @param None
- * @retval None
- */
-static void MX_GPIO_Init(void)
-{
- GPIO_InitTypeDef GPIO_InitStruct = {0};
-
- /* GPIO Ports Clock Enable */
- __HAL_RCC_GPIOC_CLK_ENABLE();
- __HAL_RCC_GPIOH_CLK_ENABLE();
- __HAL_RCC_GPIOA_CLK_ENABLE();
- __HAL_RCC_GPIOB_CLK_ENABLE();
-
- /*Configure GPIO pin Output Level */
- HAL_GPIO_WritePin(led_GPIO_Port, led_Pin, GPIO_PIN_RESET);
-
- /*Configure GPIO pin : led_Pin */
- GPIO_InitStruct.Pin = led_Pin;
- GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
- GPIO_InitStruct.Pull = GPIO_NOPULL;
- GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
- HAL_GPIO_Init(led_GPIO_Port, &GPIO_InitStruct);
-
-}
-
-/* USER CODE BEGIN 4 */
hs_status_t handshake(uint32_t i2c_addr)
{
@@ -834,7 +653,116 @@ bool encode_subscription_callback(pb_ostream_t *ostream, const pb_field_t *field
}
return true;
}
-/* USER CODE END 4 */
+
+/**
+ * @brief System Clock Configuration
+ * @retval None
+ */
+void SystemClock_Config(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+
+ /** Configure the main internal regulator output voltage
+ */
+ __HAL_RCC_PWR_CLK_ENABLE();
+ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2);
+ /** Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK)
+ {
+ Error_Handler();
+ }
+}
+
+/**
+ * @brief I2C1 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_I2C1_Init(void)
+{
+ hi2c1.Instance = I2C1;
+ hi2c1.Init.ClockSpeed = 100000;
+ hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2;
+ hi2c1.Init.OwnAddress1 = I2C_ADDRESS;
+ hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
+ hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
+ hi2c1.Init.OwnAddress2 = 0xFF;
+ hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
+ hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
+ if (HAL_I2C_Init(&hi2c1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+/**
+ * @brief USART1 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_USART1_UART_Init(void)
+{
+ huart1.Instance = USART1;
+ huart1.Init.BaudRate = 9600;
+ huart1.Init.WordLength = UART_WORDLENGTH_8B;
+ huart1.Init.StopBits = UART_STOPBITS_1;
+ huart1.Init.Parity = UART_PARITY_NONE;
+ huart1.Init.Mode = UART_MODE_TX_RX;
+ huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart1.Init.OverSampling = UART_OVERSAMPLING_16;
+ if (HAL_UART_Init(&huart1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+}
+
+/**
+ * @brief GPIO Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_GPIO_Init(void)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOH_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(led_GPIO_Port, led_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin : led_Pin */
+ GPIO_InitStruct.Pin = led_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(led_GPIO_Port, &GPIO_InitStruct);
+
+}
/**
* @brief This function is executed in case of error occurrence.
@@ -867,5 +795,3 @@ void assert_failed(uint8_t *file, uint32_t line)
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/