Fully renew the example with cmake integration. ioc deleted

This commit is contained in:
donghoonpark 2024-11-10 16:29:58 +09:00 committed by Valerio De Benedetto
parent c94da49b12
commit fbe94cf0b7
13 changed files with 1413 additions and 651 deletions

View File

@ -1,11 +1,8 @@
# Auto-generated from *.ioc file
cmake/*
build/*
Core/*
Drivers/*
.cproject
.mxproject
*.s
.project
*.ld
CMakePresets.json
# Editor setting
.vscode/*

View File

@ -11,7 +11,7 @@
"executable": "${command:cmake.launchTargetPath}", //or fixed file path: build/stm32h735g-dk-led.elf
"request": "launch", //Use "attach" to connect to target w/o elf download
"servertype": "openocd",
"device": "STM32F401CE", //MCU used, ex. "STM32H735IG"
"device": "STM32F401", //MCU used, ex. "STM32H735IG"
"interface": "swd",
"serialNumber": "", //Set ST-Link ID if you use multiple at the same time
"runToEntryPoint": "main",
@ -21,12 +21,9 @@
"interface/stlink.cfg",
"target/stm32f4x.cfg"
],
"postLaunchCommands": [
"monitor arm semihosting enable",
],
"liveWatch": {
"enabled": true,
"samplesPerSecond": 1
"samplesPerSecond": 4
}
}
]

View File

@ -1,14 +1,86 @@
{
"version": "2.0.0",
"tasks": [
{
"type": "cmake",
"label": "CMake: build",
"command": "build",
"preset": "${command:cmake.activeBuildPresetName}",
"group": "build",
"problemMatcher": [],
"detail": "CMake template build task"
}
]
"version": "2.0.0",
"tasks": [
{
"type": "cppbuild",
"label": "Build project",
"command": "cmake",
"args": ["--build", "${command:cmake.buildDirectory}", "-j", "8"],
"options": {
"cwd": "${workspaceFolder}"
},
"problemMatcher": ["$gcc"],
"group": {
"kind": "build",
"isDefault": true
}
},
{
"type": "shell",
"label": "Re-build project",
"command": "cmake",
"args": ["--build", "${command:cmake.buildDirectory}", "--clean-first", "-v", "-j", "8"],
"options": {
"cwd": "${workspaceFolder}"
},
"problemMatcher": ["$gcc"],
},
{
"type": "shell",
"label": "Clean project",
"command": "cmake",
"args": ["--build", "${command:cmake.buildDirectory}", "--target", "clean"],
"options": {
"cwd": "${workspaceFolder}"
},
"problemMatcher": []
},
{
"type": "shell",
"label": "CubeProg: Flash project (SWD)",
"command": "STM32_Programmer_CLI",
"args": [
"--connect",
"port=swd",
"--download", "${command:cmake.launchTargetPath}",
"-hardRst", // Hardware reset - if rst pin is connected
"-rst", // Software reset (backup)
"--start" // Start execution
],
"options": {
"cwd": "${workspaceFolder}"
},
"problemMatcher": []
},
{
"type": "shell",
"label": "CubeProg: Flash project with defined serial number (SWD) - you must set serial number first",
"command": "STM32_Programmer_CLI",
"args": [
"--connect",
"port=swd",
"sn=<yourserialnumber>",
"--download", "${command:cmake.launchTargetPath}",
"-hardRst", // Hardware reset - if rst pin is connected
"-rst", // Software reset (backup)
"--start" // Start execution
],
"options": {
"cwd": "${workspaceFolder}"
},
"problemMatcher": []
},
{
"type": "shell",
"label": "CubeProg: List all available communication interfaces",
"command": "STM32_Programmer_CLI",
"args": [
"--list",
],
"options": {
"cwd": "${workspaceFolder}"
},
"problemMatcher": []
},
]
}

View File

@ -1,72 +1,110 @@
cmake_minimum_required(VERSION 3.22)
cmake_minimum_required(VERSION 3.16)
set(PROJ_NAME stm32-blackpill)
#
# This file is generated only once,
# and is not re-generated if converter is called multiple times.
#
# User is free to modify the file as much as necessary
#
include(FetchContent)
FetchContent_Declare( stm32_cmake
GIT_REPOSITORY https://github.com/ObKo/stm32-cmake
GIT_TAG v2.1.0
GIT_SHALLOW TRUE
)
FetchContent_Populate(stm32_cmake)
set(CMAKE_TOOLCHAIN_FILE ${stm32_cmake_SOURCE_DIR}/cmake/stm32_gcc.cmake)
# Setup compiler settings
set(CMAKE_C_STANDARD 11)
set(CMAKE_C_STANDARD_REQUIRED ON)
set(CMAKE_C_EXTENSIONS ON)
project(${PROJ_NAME} CXX C ASM)
set(CMAKE_INCLUDE_CURRENT_DIR TRUE)
set(TARGET_NAME ${PROJ_NAME})
# Define the build type
if(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE "Debug")
add_executable(${TARGET_NAME}
main.c
bsp/blackpill/blackpill.c
nmbs/port.c
)
target_include_directories(
${TARGET_NAME} PRIVATE
${CMAKE_CURRENT_SOURCE_DIR}/bsp
${CMAKE_CURRENT_SOURCE_DIR}/nmbs
)
stm32_fetch_cmsis(F4)
stm32_fetch_hal(F4)
find_package(CMSIS COMPONENTS STM32F401CC REQUIRED)
find_package(HAL COMPONENTS STM32F4 REQUIRED)
add_compile_options(
-mcpu=cortex-m4
-mfpu=fpv4-sp-d16
-mfloat-abi=hard
)
set(CMAKE_INCLUDE_CURRENT_DIR ON)
set( FREERTOS_HEAP "4")
set( FREERTOS_PORT "GCC_ARM_CM4F")
add_library(freertos_config INTERFACE)
target_include_directories(freertos_config SYSTEM
INTERFACE
${CMAKE_CURRENT_SOURCE_DIR}
)
FetchContent_Declare( freertos_kernel
GIT_REPOSITORY https://github.com/FreeRTOS/FreeRTOS-Kernel.git
GIT_TAG V11.1.0
GIT_SHALLOW TRUE
)
FetchContent_MakeAvailable(freertos_kernel)
set(WIZ_CHIP W5500)
FetchContent_Declare(
wizchip
GIT_REPOSITORY https://github.com/donghoonpark/wizchip-cmake
GIT_SHALLOW TRUE
)
FetchContent_MakeAvailable(wizchip)
FetchContent_Declare(
nanomodbus
GIT_REPOSITORY https://github.com/debevv/nanoMODBUS
GIT_TAG v1.18.1
GIT_SHALLOW TRUE
)
FetchContent_GetProperties(nanomodbus)
if(NOT nanomodbus_POPULATED)
FetchContent_Populate(nanomodbus)
endif()
# Set the project name
set(CMAKE_PROJECT_NAME stm32f401ccux)
add_library(nanomodbus ${nanomodbus_SOURCE_DIR}/nanomodbus.c)
target_include_directories(nanomodbus PUBLIC ${nanomodbus_SOURCE_DIR})
# Include toolchain file
include("cmake/gcc-arm-none-eabi.cmake")
# Enable compile command to ease indexing with e.g. clangd
set(CMAKE_EXPORT_COMPILE_COMMANDS TRUE)
# Enable CMake support for ASM and C languages
enable_language(C ASM)
# Core project settings
project(${CMAKE_PROJECT_NAME})
message("Build type: " ${CMAKE_BUILD_TYPE})
# Create an executable object type
add_executable(${CMAKE_PROJECT_NAME})
# Add STM32CubeMX generated sources
add_subdirectory(cmake/stm32cubemx)
# Link directories setup
target_link_directories(${CMAKE_PROJECT_NAME} PRIVATE
# Add user defined library search paths
target_link_libraries(
${TARGET_NAME}
STM32::NoSys
CMSIS::STM32::F401CC
HAL::STM32::F4::CORTEX
HAL::STM32::F4::RCC
HAL::STM32::F4::PWR
HAL::STM32::F4::GPIO
HAL::STM32::F4::TIM
HAL::STM32::F4::UART
HAL::STM32::F4::USART
HAL::STM32::F4::SPI
HAL::STM32::F4::DMA
wizchip
freertos_kernel
nanomodbus
)
# Add sources to executable
target_sources(${CMAKE_PROJECT_NAME} PRIVATE
# Add user sources here
nanomodbus_port.c
${CMAKE_CURRENT_SOURCE_DIR}/../../nanomodbus.c
add_custom_command(TARGET ${TARGET_NAME} POST_BUILD
COMMAND ${CMAKE_SIZE} $<TARGET_FILE:${TARGET_NAME}>
)
# Add include paths
target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE
# Add user defined include paths
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_CURRENT_SOURCE_DIR}/../../
)
# Add project symbols (macros)
target_compile_definitions(${CMAKE_PROJECT_NAME} PRIVATE
# Add user defined symbols
)
# Add linked libraries
target_link_libraries(${CMAKE_PROJECT_NAME}
stm32cubemx
# Add user defined libraries
add_custom_command(TARGET ${TARGET_NAME} POST_BUILD
COMMAND ${CMAKE_OBJCOPY} -O ihex $<TARGET_FILE:${TARGET_NAME}> ${TARGET_NAME}.hex
)
add_custom_command(TARGET ${TARGET_NAME} POST_BUILD
COMMAND ${CMAKE_OBJCOPY} -O binary $<TARGET_FILE:${TARGET_NAME}> ${TARGET_NAME}.bin
)

View File

@ -1,292 +0,0 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2024 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.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "nanomodbus_port.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
#define TEST_SERVER 1
#define TEST_CLIENT 0
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
UART_HandleTypeDef huart1;
DMA_HandleTypeDef hdma_usart1_rx;
DMA_HandleTypeDef hdma_usart1_tx;
/* USER CODE BEGIN PV */
nmbs_t nmbs;
nmbs_server_t nmbs_server =
{
.id = 0x01,
.coils = {0,},
.regs = {0,},
};
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_DMA_Init(void);
static void MX_USART1_UART_Init(void);
/* USER CODE BEGIN PFP */
/* 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--------------------------------------------------------*/
/* 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_DMA_Init();
MX_USART1_UART_Init();
/* USER CODE BEGIN 2 */
#if TEST_SERVER
nmbs_server_init(&nmbs, &nmbs_server);
#endif
#if TEST_CLIENT
uint8_t coils_test[32];
uint16_t regs_test[32];
nmbs_client_init(&nmbs);
#endif
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
// If you use rtos, this polling can processed in a task
#if TEST_SERVER
nmbs_server_poll(&nmbs);
#endif
#if TEST_CLIENT
nmbs_set_destination_rtu_address(&nmbs, 0x01);
nmbs_error status = nmbs_read_holding_registers(&nmbs, 0, 32, regs_test);
status = nmbs_write_multiple_registers(&nmbs, 0, 32, regs_test);
if(status != NMBS_ERROR_NONE)
{
while(true){}
}
#endif
}
/* 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 RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLM = 16;
RCC_OscInitStruct.PLL.PLLN = 128;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLQ = 4;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
Error_Handler();
}
}
/**
* @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 = 115200;
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 */
}
/**
* Enable DMA controller clock
*/
static void MX_DMA_Init(void)
{
/* DMA controller clock enable */
__HAL_RCC_DMA2_CLK_ENABLE();
/* DMA interrupt init */
/* DMA2_Stream2_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn);
/* DMA2_Stream7_IRQn interrupt configuration */
HAL_NVIC_SetPriority(DMA2_Stream7_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream7_IRQn);
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOA_CLK_ENABLE();
/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
__disable_irq();
while (1)
{
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

View File

@ -0,0 +1,159 @@
/*
* FreeRTOS Kernel V10.4.1
* Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*
* See http://www.freertos.org/a00110.html
*----------------------------------------------------------*/
#include <stdint.h>
extern uint32_t SystemCoreClock;
#if defined STM32L5
#define configENABLE_TRUSTZONE 0
#if configENABLE_TRUSTZONE
#define configMINIMAL_SECURE_STACK_SIZE ((uint16_t)1024)
#endif
#define configRUN_FREERTOS_SECURE_ONLY 0
#define configENABLE_FPU 1
#define configENABLE_MPU 0
#endif
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ ( SystemCoreClock )
#define configTICK_RATE_HZ ( ( TickType_t ) 1000 )
#if !defined USE_CMSIS_RTOS_V2
#define configMAX_PRIORITIES ( 5 )
#endif
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 50 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 32 * 1024 ) )
#define configMAX_TASK_NAME_LEN ( 10 )
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 1
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configCHECK_FOR_STACK_OVERFLOW 0
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_MALLOC_FAILED_HOOK 0
#define configUSE_APPLICATION_TASK_TAG 0
#define configUSE_COUNTING_SEMAPHORES 1
#define configGENERATE_RUN_TIME_STATS 0
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* Software timer definitions. */
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY ( 2 )
#define configTIMER_QUEUE_LENGTH 10
#define configTIMER_TASK_STACK_DEPTH ( configMINIMAL_STACK_SIZE * 2 )
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 1
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#if defined USE_CMSIS_RTOS_V2
#ifndef CMSIS_RTOS_V2_DEVICE_HEADER
#error "CMSIS device header needs to be passed by the build system"
#endif
#define CMSIS_device_header CMSIS_RTOS_V2_DEVICE_HEADER
/* Needed for CMSIS RTOS_V2 */
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
#define configMAX_PRIORITIES 56
#define INCLUDE_xSemaphoreGetMutexHolder 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#define INCLUDE_eTaskGetState 1
#define INCLUDE_xTimerPendFunctionCall 1
#endif
/* Cortex-M specific definitions. */
#ifdef __NVIC_PRIO_BITS
/* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 4 /* 15 priority levels */
#endif
/* The lowest interrupt priority that can be used in a call to a "set priority"
function. */
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 0xf
/* The highest interrupt priority that can be used by any interrupt service
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
/* Interrupt priorities used by the kernel port layer itself. These are generic
to all Cortex-M ports, and do not rely on any particular library functions. */
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
#define configASSERT( x ) if( ( x ) == 0 ) { taskDISABLE_INTERRUPTS(); for( ;; ); }
/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
standard names. */
#define vPortSVCHandler SVC_Handler
#define xPortPendSVHandler PendSV_Handler
/* When using CMSIS RTOS V2, this define causes a multiple definition error */
#if !defined USE_CMSIS_RTOS_V2
#define xPortSysTickHandler SysTick_Handler
#endif
#endif /* FREERTOS_CONFIG_H */

View File

@ -0,0 +1,371 @@
/*
* STM32F401CCU6 Board Support Package (BSP) Summary:
*
* 1. System Clock Configuration:
* - External high-speed oscillator (HSE) enabled.
* - PLL is configured with source from HSE, PLLM = 25, PLLN = 336, PLLP = 4, PLLQ = 7.
* - System clock (SYSCLK) sourced from PLL output at 84 MHz.
* - AHB clock (HCLK) running at SYSCLK.
* - APB1 clock (PCLK1) running at HCLK / 2 (42 MHz).
* - APB2 clock (PCLK2) running at HCLK.
*
* 2. GPIO Configuration:
* - GPIOC Pin 13: Configured as output (Push Pull), used for LED control, low frequency.
* - GPIOB Pin 7: Configured as input, no pull-up/pull-down, used as input for interrupts.
* - GPIOB Pin 6: Configured as open-drain output, low frequency, initially set high.
* - GPIOA Pin 15: Configured as output (Push Pull), used for NSS in SPI1 communication, very high frequency.
* - GPIOA Pins 9 (TX), 10 (RX): Configured as alternate function (AF7) for USART1 communication.
* - GPIOB Pins 3 (SCLK), 4 (MISO), 5 (MOSI): Configured as alternate function (AF5) for SPI1 communication.
*
* 3. SPI1 Configuration:
* - Mode: Master.
* - Data Direction: 2-line unidirectional.
* - Data Size: 8-bit.
* - Clock Polarity: Low when idle.
* - Clock Phase: First edge capture.
* - NSS (Chip Select): Software management.
* - Baud Rate Prescaler: 2.
* - First Bit: MSB.
* - TI Mode: Disabled.
* - CRC Calculation: Disabled.
* - Pins: PB3 (SCLK), PB4 (MISO), PB5 (MOSI) configured as alternate function.
*
* 4. USART1 Configuration:
* - Baud Rate: 115200.
* - Word Length: 8 bits.
* - Stop Bits: 1.
* - Parity: None.
* - Mode: TX/RX.
* - Hardware Flow Control: None.
* - Oversampling: 16x.
* - Pins: PA9 (TX), PA10 (RX) configured as alternate function.
*
* 5. DMA Configuration:
* - DMA2_Stream3 (SPI1_TX): Used for SPI1 TX, configured for memory-to-peripheral, channel 3.
* - Memory increment enabled, peripheral increment disabled, normal mode, low priority.
* - Linked to SPI1_TX using __HAL_LINKDMA.
* - Interrupt priority level 0, enabled.
* - DMA2_Stream0 (SPI1_RX): Used for SPI1 RX, configured for peripheral-to-memory, channel 3.
* - Memory increment enabled, peripheral increment disabled, normal mode, high priority.
* - Linked to SPI1_RX using __HAL_LINKDMA.
* - Interrupt priority level 0, enabled.
* - DMA2_Stream7 (USART1_TX): Used for USART1 TX, configured for memory-to-peripheral, channel 4.
* - Memory increment enabled, peripheral increment disabled, normal mode, low priority.
* - Linked to USART1_TX using __HAL_LINKDMA.
* - Interrupt priority level 0, enabled.
* - DMA2_Stream2 (USART1_RX): Used for USART1 RX, configured for peripheral-to-memory, channel 4.
* - Memory increment enabled, peripheral increment disabled, normal mode, high priority.
* - Linked to USART1_RX using __HAL_LINKDMA.
* - Interrupt priority level 0, enabled.
*
* 6. Peripheral Clocks:
* - GPIOC, GPIOB, GPIOA clocks enabled for GPIO configuration.
* - USART1 clock enabled for UART communication.
* - SPI1 clock enabled for SPI communication.
* - DMA2 clock enabled for DMA streams (used for SPI1 and USART1).
*
* 7. Interrupt Configuration:
* - DMA2_Stream3 (SPI1_TX), DMA2_Stream0 (SPI1_RX), DMA2_Stream7 (USART1_TX), DMA2_Stream2 (USART1_RX).
* - All configured with priority level 0 and interrupts enabled.
*
* 8. Error Handling:
* - Error_Handler function enters an infinite loop to indicate an error state.
*/
#include "blackpill/blackpill.h"
#include "blackpill.h"
#include "stm32f4xx_hal.h"
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_SPI1_Init(void);
static void MX_DMA_Init(void);
static void MX_USART1_UART_Init(void);
SPI_HandleTypeDef hspi1;
DMA_HandleTypeDef hdma_spi1_tx;
DMA_HandleTypeDef hdma_spi1_rx;
UART_HandleTypeDef huart1;
DMA_HandleTypeDef hdma_usart1_tx;
DMA_HandleTypeDef hdma_usart1_rx;
void BSP_Init(void)
{
// Initialize the HAL Library
HAL_Init();
// Configure the system clock
SystemClock_Config();
// Initialize all configured peripherals (GPIO and SPI1)
MX_GPIO_Init();
MX_SPI1_Init();
MX_DMA_Init();
MX_USART1_UART_Init();
}
void SystemClock_Config(void)
{
// System Clock Configuration Code
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
// Configure the main internal regulator output voltage
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = 25;
RCC_OscInitStruct.PLL.PLLN = 336;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4;
RCC_OscInitStruct.PLL.PLLQ = 7;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
// Initialize the CPU, AHB, and APB buses clocks
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2);
}
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
// Enable GPIOC clock
__HAL_RCC_GPIOC_CLK_ENABLE();
// Configure GPIOC Pin 13 for LED output (Output Push Pull mode)
GPIO_InitStruct.Pin = GPIO_PIN_13;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
// Enable GPIOB clock
__HAL_RCC_GPIOB_CLK_ENABLE();
// Configure GPIOB Pin 7 as input for interrupt (Input mode)
GPIO_InitStruct.Pin = GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
// Configure GPIOB Pin 6 as output with Open Drain mode
GPIO_InitStruct.Pin = GPIO_PIN_6;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_6, GPIO_PIN_SET);
// Enable GPIOA clock
__HAL_RCC_GPIOA_CLK_ENABLE();
// Configure NSS pin (PA15) as Output Push Pull
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}
static void MX_USART1_UART_Init(void)
{
// USART1 initialization settings
__HAL_RCC_USART1_CLK_ENABLE();
huart1.Instance = USART1;
huart1.Init.BaudRate = 115200;
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)
{
// Initialization error handling
Error_Handler();
}
// USART1 Pin configuration: TX (PA9), RX (PA10)
GPIO_InitTypeDef GPIO_InitStruct = {0};
// Enable GPIOA clock
__HAL_RCC_GPIOA_CLK_ENABLE();
// Configure USART1 TX (PA9) and RX (PA10) pins as Alternate Function Push Pull
GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}
static void MX_SPI1_Init(void)
{
__HAL_RCC_SPI1_CLK_ENABLE();
// SPI1 initialization settings
hspi1.Instance = SPI1;
hspi1.Init.Mode = SPI_MODE_MASTER; // Set SPI1 as master
hspi1.Init.Direction = SPI_DIRECTION_2LINES; // Set bidirectional data mode
hspi1.Init.DataSize = SPI_DATASIZE_8BIT; // Set data frame size to 8 bits
hspi1.Init.CLKPolarity = SPI_POLARITY_LOW; // Clock polarity low when idle
hspi1.Init.CLKPhase = SPI_PHASE_1EDGE; // First clock transition is the first data capture edge
hspi1.Init.NSS = SPI_NSS_SOFT; // Hardware chip select management
hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; // Set baud rate prescaler to 2
hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB; // Data is transmitted MSB first
hspi1.Init.TIMode = SPI_TIMODE_DISABLE; // Disable TI mode
hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; // Disable CRC calculation
hspi1.Init.CRCPolynomial = 10; // CRC polynomial value
if (HAL_SPI_Init(&hspi1) != HAL_OK)
{
// Initialization error handling
Error_Handler();
}
// SPI1 Pin configuration: SCLK (PB3), MISO (PB4), MOSI (PB5)
GPIO_InitTypeDef GPIO_InitStruct = {0};
// Enable GPIOB clock
__HAL_RCC_GPIOB_CLK_ENABLE();
// Configure SPI1 SCLK, MISO, MOSI pins as Alternate Function Push Pull
GPIO_InitStruct.Pin = GPIO_PIN_3 | GPIO_PIN_4 | GPIO_PIN_5;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF5_SPI1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
static void MX_DMA_Init(void)
{
// DMA controller clock enable
__HAL_RCC_DMA2_CLK_ENABLE();
// Configure DMA request hdma_spi1_tx on DMA2_Stream3
hdma_spi1_tx.Instance = DMA2_Stream3;
hdma_spi1_tx.Init.Channel = DMA_CHANNEL_3;
hdma_spi1_tx.Init.Direction = DMA_MEMORY_TO_PERIPH;
hdma_spi1_tx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_spi1_tx.Init.MemInc = DMA_MINC_ENABLE;
hdma_spi1_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_spi1_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_spi1_tx.Init.Mode = DMA_NORMAL;
hdma_spi1_tx.Init.Priority = DMA_PRIORITY_LOW;
hdma_spi1_tx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_spi1_tx) != HAL_OK)
{
// Initialization error handling
Error_Handler();
}
__HAL_LINKDMA(&hspi1, hdmatx, hdma_spi1_tx);
// Configure DMA request hdma_spi1_rx on DMA2_Stream0
hdma_spi1_rx.Instance = DMA2_Stream0;
hdma_spi1_rx.Init.Channel = DMA_CHANNEL_3;
hdma_spi1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_spi1_rx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_spi1_rx.Init.MemInc = DMA_MINC_ENABLE;
hdma_spi1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_spi1_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_spi1_rx.Init.Mode = DMA_NORMAL;
hdma_spi1_rx.Init.Priority = DMA_PRIORITY_HIGH;
hdma_spi1_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_spi1_rx) != HAL_OK)
{
// Initialization error handling
Error_Handler();
}
__HAL_LINKDMA(&hspi1, hdmarx, hdma_spi1_rx);
// Configure DMA request hdma_usart1_tx on DMA2_Stream7
hdma_usart1_tx.Instance = DMA2_Stream7;
hdma_usart1_tx.Init.Channel = DMA_CHANNEL_4;
hdma_usart1_tx.Init.Direction = DMA_MEMORY_TO_PERIPH;
hdma_usart1_tx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_usart1_tx.Init.MemInc = DMA_MINC_ENABLE;
hdma_usart1_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_usart1_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_usart1_tx.Init.Mode = DMA_NORMAL;
hdma_usart1_tx.Init.Priority = DMA_PRIORITY_LOW;
hdma_usart1_tx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_usart1_tx) != HAL_OK)
{
// Initialization error handling
Error_Handler();
}
__HAL_LINKDMA(&huart1, hdmatx, hdma_usart1_tx);
// Configure DMA request hdma_usart1_rx on DMA2_Stream2
hdma_usart1_rx.Instance = DMA2_Stream2;
hdma_usart1_rx.Init.Channel = DMA_CHANNEL_4;
hdma_usart1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_usart1_rx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_usart1_rx.Init.MemInc = DMA_MINC_ENABLE;
hdma_usart1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_usart1_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_usart1_rx.Init.Mode = DMA_NORMAL;
hdma_usart1_rx.Init.Priority = DMA_PRIORITY_HIGH;
hdma_usart1_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
if (HAL_DMA_Init(&hdma_usart1_rx) != HAL_OK)
{
// Initialization error handling
Error_Handler();
}
// DMA2_Stream3 (SPI1_TX) Interrupt Configuration
HAL_NVIC_SetPriority(DMA2_Stream3_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn);
// DMA2_Stream0 (SPI1_RX) Interrupt Configuration
HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn);
// DMA2_Stream7 (USART1_TX) Interrupt Configuration
HAL_NVIC_SetPriority(DMA2_Stream7_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream7_IRQn);
// DMA2_Stream2 (USART1_RX) Interrupt Configuration
HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn);
}
void Error_Handler(void)
{
// If an error occurs, stay in infinite loop
while(1) {}
}
void DMA2_Stream3_IRQHandler(void)
{
HAL_DMA_IRQHandler(&hdma_spi1_tx);
}
void DMA2_Stream0_IRQHandler(void)
{
HAL_DMA_IRQHandler(&hdma_spi1_rx);
}
void DMA2_Stream7_IRQHandler(void)
{
HAL_DMA_IRQHandler(&hdma_usart1_tx);
}
void DMA2_Stream2_IRQHandler(void)
{
HAL_DMA_IRQHandler(&hdma_usart1_rx);
}

View File

@ -0,0 +1,17 @@
#ifndef BLACKPILL_H_
#define BLACKPILL_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f4xx_hal.h"
void BSP_Init(void);
#ifdef __cplusplus
}
#endif
#endif

129
examples/stm32/main.c Normal file
View File

@ -0,0 +1,129 @@
#include "blackpill/blackpill.h"
#include "wizchip.h"
#include <stdio.h>
#include <stdbool.h>
#include "FreeRTOS.h"
#include "task.h"
#include <socket.h>
#include "nanomodbus.h"
#include "nmbs/port.h"
extern SPI_HandleTypeDef hspi1;
wiz_NetInfo net_info = {
.mac = { 0xEA, 0x11, 0x22, 0x33, 0x44, 0xEA },
.ip = {192, 168, 137, 100}, // You can find this ip if you set your ethernet port ip as 192.168.137.XXX
.sn = {255, 255, 255, 0},
.gw = {192, 168, 137, 1},
.dns = {0, 0, 0, 0},
}; // Network information.
uint8_t transaction_buf_sizes[] = {
2, 2, 2, 2, 2, 2, 2, 2
}; // All 2kB buffer setting for each sockets
#if USE_HAL_SPI_REGISTER_CALLBACKS == 0
void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi)
{
wizchip_dma_rx_cplt((void*) hspi);
}
void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi)
{
wizchip_dma_tx_cplt((void*) hspi);
}
#endif
uint32_t HAL_GetTick(void)
{
return xTaskGetTickCount();
}
static void blink(void* args);
static void modbus(void* args);
int main(void)
{
BSP_Init();
wizchip_register_hal(
&hspi1,
(fHalSpiTransaction) HAL_SPI_Receive,
(fHalSpiTransaction) HAL_SPI_Transmit,
(fHalSpiTransactionDma) HAL_SPI_Receive_DMA,
(fHalSpiTransactionDma) HAL_SPI_Transmit_DMA,
GPIOA,
GPIO_PIN_15,
(fHalGpioWritePin) HAL_GPIO_WritePin
);
wizchip_init(transaction_buf_sizes, transaction_buf_sizes);
setSHAR(net_info.mac);
setSIPR(net_info.ip);
setSUBR(net_info.sn);
setGAR (net_info.gw);
xTaskCreate(blink, "blink", 128, NULL, 4, NULL);
xTaskCreate(modbus, "modbus", 128 * 16, NULL, 2, NULL);
vTaskStartScheduler();
while(true)
{
}
}
static void blink(void* args)
{
for(;;)
{
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_13, GPIO_PIN_SET);
vTaskDelay(500);
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_13, GPIO_PIN_RESET);
vTaskDelay(500);
}
}
static nmbs_t nmbs;
static nmbs_server_t nmbs_server =
{
.id = 0x01,
.coils = {0,},
.regs = {0,},
};
static void modbus(void* args)
{
int status;
nmbs_server_init(&nmbs, &nmbs_server);
for(;;)
{
switch ((status = getSn_SR(MB_SOCKET)))
{
case SOCK_ESTABLISHED:
nmbs_server_poll(&nmbs);
break;
case SOCK_INIT :
listen(MB_SOCKET);
break;
case SOCK_CLOSED:
socket(MB_SOCKET, Sn_MR_TCP, 502, 0);
break;
case SOCK_CLOSE_WAIT :
disconnect(MB_SOCKET);
break;
default:
taskYIELD();
break;
}
}
}

View File

@ -1,25 +1,15 @@
#include <string.h>
#include "nanomodbus_port.h"
#include "nmbs/port.h"
#include "FreeRTOS.h"
#ifdef NMBS_TCP
static int32_t read_socket(uint8_t* buf, uint16_t count, int32_t byte_timeout_ms, void* arg);
static int32_t write_socket(const uint8_t* buf, uint16_t count, int32_t byte_timeout_ms, void* arg);
#endif
#ifdef NMBS_RTU
static int32_t read_serial(uint8_t* buf, uint16_t count, int32_t byte_timeout_ms, void* arg);
static int32_t write_serial(const uint8_t* buf, uint16_t count, int32_t byte_timeout_ms, void* arg);
// Dual buffer setting to isolate dma implementation and ring buffer.
// You may integrate this feature with dma counter register to minimize memory footprint
static uint8_t rx_dma_buf[RX_BUF_SIZE];
// Ring buffer structure definition
typedef struct tRingBuf {
uint8_t data[RX_BUF_SIZE];
uint16_t head;
uint16_t tail;
bool full;
void (*overflow_callback)(struct tRingBuf* rq);
} ringBuf;
static ringBuf rb;
static void ringbuf_init(ringBuf* rb, void (*overflow_callback)(struct tRingBuf* rq));
static void ringbuf_overflow_error(ringBuf* rb);
#endif
static nmbs_server_t* server;
@ -32,15 +22,20 @@ static nmbs_error server_write_multiple_registers(uint16_t address, uint16_t qua
nmbs_error nmbs_server_init(nmbs_t* nmbs, nmbs_server_t* _server)
{
ringbuf_init(&rb, ringbuf_overflow_error);
nmbs_platform_conf conf;
nmbs_callbacks cb;
nmbs_platform_conf_create(&conf);
#ifdef NMBS_TCP
conf.transport = NMBS_TRANSPORT_TCP;
conf.read = read_socket;
conf.write = write_socket;
#endif
#ifdef NMBS_RTU
conf.transport = NMBS_TRANSPORT_RTU;
conf.read = read_serial;
conf.write = write_serial;
#endif
server = _server;
@ -52,41 +47,43 @@ nmbs_error nmbs_server_init(nmbs_t* nmbs, nmbs_server_t* _server)
cb.write_single_register = server_write_single_register;
cb.write_multiple_registers = server_write_multiple_registers;
nmbs_error status = nmbs_server_create(nmbs, server->id, &conf, &cb);
if(status != NMBS_ERROR_NONE)
{
return status;
}
nmbs_set_byte_timeout(nmbs, 100);
nmbs_set_read_timeout(nmbs, 1000);
HAL_UARTEx_ReceiveToIdle_DMA(&NANOMB_UART, rx_dma_buf, RX_BUF_SIZE);
return NMBS_ERROR_NONE;
}
nmbs_error nmbs_client_init(nmbs_t* nmbs)
{
ringbuf_init(&rb, ringbuf_overflow_error);
nmbs_platform_conf conf;
nmbs_platform_conf_create(&conf);
#ifdef NMBS_TCP
conf.transport = NMBS_TRANSPORT_TCP;
conf.read = read_socket;
conf.write = write_socket;
#endif
#ifdef NMBS_RTU
conf.transport = NMBS_TRANSPORT_RTU;
conf.read = read_serial;
conf.write = write_serial;
#endif
nmbs_error status = nmbs_client_create(nmbs, &conf);
if(status != NMBS_ERROR_NONE)
{
return status;
}
nmbs_set_byte_timeout(nmbs, 100);
nmbs_set_read_timeout(nmbs, 1000);
HAL_UARTEx_ReceiveToIdle_DMA(&NANOMB_UART, rx_dma_buf, RX_BUF_SIZE);
return NMBS_ERROR_NONE;
}
@ -101,13 +98,13 @@ static nmbs_server_t* get_server(uint8_t id)
{
return NULL;
}
}
static nmbs_error server_read_coils(uint16_t address, uint16_t quantity, nmbs_bitfield coils_out, uint8_t unit_id, void* arg)
{
nmbs_server_t* server = get_server(unit_id);
for(size_t i = 0; i < quantity; i++)
{
if((address>>3) > COIL_BUF_SIZE)
@ -123,7 +120,7 @@ static nmbs_error server_read_coils(uint16_t address, uint16_t quantity, nmbs_bi
static nmbs_error server_read_holding_registers(uint16_t address, uint16_t quantity, uint16_t* registers_out, uint8_t unit_id, void* arg)
{
nmbs_server_t* server = get_server(unit_id);
for(size_t i = 0; i < quantity; i++)
{
if(address > REG_BUF_SIZE)
@ -142,13 +139,13 @@ static nmbs_error server_write_single_coil(uint16_t address, bool value, uint8_t
{
coil |= 0x01;
}
server_write_multiple_coils(address, 1, &coil, unit_id, arg);
return server_write_multiple_coils(address, 1, &coil, unit_id, arg);
}
static nmbs_error server_write_multiple_coils(uint16_t address, uint16_t quantity, const nmbs_bitfield coils, uint8_t unit_id, void* arg)
{
nmbs_server_t* server = get_server(unit_id);
for(size_t i = 0; i < quantity; i++)
{
if((address>>3) > COIL_BUF_SIZE)
@ -164,13 +161,13 @@ static nmbs_error server_write_multiple_coils(uint16_t address, uint16_t quantit
static nmbs_error server_write_single_register(uint16_t address, uint16_t value, uint8_t unit_id, void* arg)
{
uint16_t reg = value;
server_write_multiple_registers(address, 1, &reg, unit_id, arg);
return server_write_multiple_registers(address, 1, &reg, unit_id, arg);
}
static nmbs_error server_write_multiple_registers(uint16_t address, uint16_t quantity, const uint16_t* registers, uint8_t unit_id, void* arg)
{
nmbs_server_t* server = get_server(unit_id);
for(size_t i = 0; i < quantity; i++)
{
if(address > REG_BUF_SIZE)
@ -182,113 +179,22 @@ static nmbs_error server_write_multiple_registers(uint16_t address, uint16_t qua
return NMBS_ERROR_NONE;
}
// Function to initialize the ring buffer
static void ringbuf_init(ringBuf* rb, void (*overflow_callback)(struct tRingBuf* rq)) {
memset(rb->data, 0, sizeof(rb->data));
rb->head = 0;
rb->tail = 0;
rb->full = false;
rb->overflow_callback = overflow_callback;
}
// Function to check if the ring buffer is empty
static bool ringbuf_is_empty(ringBuf* rb) {
return (!rb->full && (rb->head == rb->tail));
}
// Function to write multiple bytes to the ring buffer
static void ringbuf_put(ringBuf* rb, const uint8_t* data, uint16_t length) {
for (uint16_t i = 0; i < length; i++) {
rb->data[rb->head] = data[i];
if (rb->full) { // If the buffer is full
if (rb->overflow_callback) {
rb->overflow_callback(rb); // Call the overflow callback
}
rb->tail = (rb->tail + 1) % RX_BUF_SIZE; // Move tail to overwrite data
}
rb->head = (rb->head + 1) % RX_BUF_SIZE;
rb->full = (rb->head == rb->tail);
}
}
// Function to read multiple bytes from the ring buffer
static bool ringbuf_get(ringBuf* rb, uint8_t* data, uint16_t length) {
if (ringbuf_is_empty(rb)) {
return false; // Return false if the buffer is empty
}
for (uint16_t i = 0; i < length; i++) {
if (ringbuf_is_empty(rb)) {
return false; // If no more data, stop reading
}
data[i] = rb->data[rb->tail];
rb->tail = (rb->tail + 1) % RX_BUF_SIZE;
rb->full = false; // Buffer is no longer full after reading
}
return true;
}
uint16_t ringbuf_size(ringBuf* rb) {
if (rb->full) {
return RX_BUF_SIZE;
}
if (rb->head >= rb->tail) {
return rb->head - rb->tail;
} else {
return RX_BUF_SIZE + rb->head - rb->tail;
}
}
// Example callback function to handle buffer overflow
static void ringbuf_overflow_error(ringBuf* rb)
{
//In here we may check the overflow situation
while(true){}
}
// RX event callback from dma
void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size)
{
if(huart == &NANOMB_UART)
{
ringbuf_put(&rb, rx_dma_buf, Size);
HAL_UARTEx_ReceiveToIdle_DMA(huart, rx_dma_buf, RX_BUF_SIZE);
}
// You may add your additional uart handler below
}
static int32_t read_serial(uint8_t* buf, uint16_t count, int32_t byte_timeout_ms, void* arg)
#ifdef NMBS_TCP
int32_t read_socket(uint8_t *buf, uint16_t count, int32_t byte_timeout_ms, void *arg)
{
uint32_t tick_start = HAL_GetTick();
while(ringbuf_size(&rb) < count)
while(recv(MB_SOCKET, buf, count) != count)
{
if(HAL_GetTick() - tick_start >= (uint32_t)byte_timeout_ms)
{
uint16_t size_to_read = ringbuf_size(&rb);
ringbuf_get(&rb, buf, size_to_read);
return size_to_read;
return 0;
}
}
// Read from ring buffer
if(ringbuf_get(&rb, buf, count))
{
return count;
}
else
{
return 0;
}
}
static int32_t write_serial(const uint8_t* buf, uint16_t count, int32_t byte_timeout_ms, void* arg)
{
HAL_StatusTypeDef status = HAL_UART_Transmit_DMA(&NANOMB_UART, buf, count);
return count;
}
int32_t write_socket(const uint8_t *buf, uint16_t count, int32_t byte_timeout_ms, void *arg)
{
return send(MB_SOCKET, buf, count);
}
#endif

View File

@ -5,19 +5,25 @@
extern "C" {
#endif
#define NANOMB_UART huart1
#define RX_BUF_SIZE 256
// Max size of coil and register area
#define COIL_BUF_SIZE 1024
#define REG_BUF_SIZE 2048
// Other hardware configuration have done in *.ioc file
// Core name may vary with your hardware
#include "stm32f4xx_hal.h"
// NanoModbus include
#include "nanomodbus.h"
#include "stm32f4xx_hal.h"
#ifdef NMBS_TCP
// modbus tcp
#define MB_SOCKET 1
#include <socket.h>
#endif
#ifdef NMBS_RTU
// modbus rtu
#define MB_UART huart1
#define RX_BUF_SIZE 256
#endif
typedef struct tNmbsServer{
uint8_t id;
@ -28,10 +34,8 @@ typedef struct tNmbsServer{
nmbs_error nmbs_server_init(nmbs_t* nmbs, nmbs_server_t* server);
nmbs_error nmbs_client_init(nmbs_t* nmbs);
extern UART_HandleTypeDef NANOMB_UART;
#ifdef __cplusplus
}
#endif
#endif
#endif

View File

@ -1,131 +0,0 @@
#MicroXplorer Configuration settings - do not modify
CAD.formats=
CAD.pinconfig=
CAD.provider=
Dma.Request0=USART1_RX
Dma.Request1=USART1_TX
Dma.RequestsNb=2
Dma.USART1_RX.0.Direction=DMA_PERIPH_TO_MEMORY
Dma.USART1_RX.0.FIFOMode=DMA_FIFOMODE_DISABLE
Dma.USART1_RX.0.Instance=DMA2_Stream2
Dma.USART1_RX.0.MemDataAlignment=DMA_MDATAALIGN_BYTE
Dma.USART1_RX.0.MemInc=DMA_MINC_ENABLE
Dma.USART1_RX.0.Mode=DMA_NORMAL
Dma.USART1_RX.0.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.USART1_RX.0.PeriphInc=DMA_PINC_DISABLE
Dma.USART1_RX.0.Priority=DMA_PRIORITY_LOW
Dma.USART1_RX.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode
Dma.USART1_TX.1.Direction=DMA_MEMORY_TO_PERIPH
Dma.USART1_TX.1.FIFOMode=DMA_FIFOMODE_DISABLE
Dma.USART1_TX.1.Instance=DMA2_Stream7
Dma.USART1_TX.1.MemDataAlignment=DMA_MDATAALIGN_BY∏TE
Dma.USART1_TX.1.MemInc=DMA_MINC_ENABLE
Dma.USART1_TX.1.Mode=DMA_NORMAL
Dma.USART1_TX.1.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.USART1_TX.1.PeriphInc=DMA_PINC_DISABLE
Dma.USART1_TX.1.Priority=DMA_PRIORITY_LOW
Dma.USART1_TX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode
File.Version=6
GPIO.groupedBy=
KeepUserPlacement=false
Mcu.CPN=STM32F401CCU6
Mcu.Family=STM32F4
Mcu.IP0=DMA
Mcu.IP1=NVIC
Mcu.IP2=RCC
Mcu.IP3=SYS
Mcu.IP4=USART1
Mcu.IPNb=5
Mcu.Name=STM32F401C(B-C)Ux
Mcu.Package=UFQFPN48
Mcu.Pin0=PA9
Mcu.Pin1=PA10
Mcu.Pin2=VP_SYS_VS_Systick
Mcu.PinsNb=3
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F401CCUx
MxCube.Version=6.11.1
MxDb.Version=DB.6.0.111
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DMA2_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
NVIC.DMA2_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
NVIC.USART1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA10.Mode=Asynchronous
PA10.Signal=USART1_RX
PA9.Mode=Asynchronous
PA9.Signal=USART1_TX
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=false
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F401CCUx
ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.28.1
ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=0
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=stm32f401ccux.ioc
ProjectManager.ProjectName=stm32f401ccux
ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=CMake
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-HAL-true
RCC.48MHZClocksFreq_Value=32000000
RCC.AHBFreq_Value=64000000
RCC.APB1CLKDivider=RCC_HCLK_DIV2
RCC.APB1Freq_Value=32000000
RCC.APB1TimFreq_Value=64000000
RCC.APB2Freq_Value=64000000
RCC.APB2TimFreq_Value=64000000
RCC.CortexFreq_Value=64000000
RCC.FCLKCortexFreq_Value=64000000
RCC.HCLKFreq_Value=64000000
RCC.HSE_VALUE=25000000
RCC.HSI_VALUE=16000000
RCC.I2SClocksFreq_Value=96000000
RCC.IPParameters=48MHZClocksFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2SClocksFreq_Value,LSE_VALUE,LSI_VALUE,PLLCLKFreq_Value,PLLN,PLLQCLKFreq_Value,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VcooutputI2S
RCC.LSE_VALUE=32768
RCC.LSI_VALUE=32000
RCC.PLLCLKFreq_Value=64000000
RCC.PLLN=128
RCC.PLLQCLKFreq_Value=32000000
RCC.RTCFreq_Value=32000
RCC.RTCHSEDivFreq_Value=12500000
RCC.SYSCLKFreq_VALUE=64000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.VCOI2SOutputFreq_Value=192000000
RCC.VCOInputFreq_Value=1000000
RCC.VCOOutputFreq_Value=128000000
RCC.VcooutputI2S=96000000
USART1.IPParameters=VirtualMode
USART1.VirtualMode=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
board=custom

View File

@ -0,0 +1,495 @@
/**
******************************************************************************
* @file stm32f4xx_hal_conf_template.h
* @author MCD Application Team
* @brief HAL configuration template file.
* This file should be copied to the application folder and renamed
* to stm32f4xx_hal_conf.h.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 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
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_HAL_CONF_H
#define __STM32F4xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
// #define HAL_ADC_MODULE_ENABLED
// #define HAL_CAN_MODULE_ENABLED
// #define HAL_CAN_LEGACY_MODULE_ENABLED
// #define HAL_CRC_MODULE_ENABLED
// #define HAL_CEC_MODULE_ENABLED
// #define HAL_CRYP_MODULE_ENABLED
// #define HAL_DAC_MODULE_ENABLED
// #define HAL_DCMI_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
// #define HAL_DMA2D_MODULE_ENABLED
// #define HAL_ETH_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
// #define HAL_NAND_MODULE_ENABLED
// #define HAL_NOR_MODULE_ENABLED
// #define HAL_PCCARD_MODULE_ENABLED
// #define HAL_SRAM_MODULE_ENABLED
// #define HAL_SDRAM_MODULE_ENABLED
// #define HAL_HASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
// #define HAL_EXTI_MODULE_ENABLED
// #define HAL_I2C_MODULE_ENABLED
// #define HAL_SMBUS_MODULE_ENABLED
// #define HAL_I2S_MODULE_ENABLED
// #define HAL_IWDG_MODULE_ENABLED
// #define HAL_LTDC_MODULE_ENABLED
// #define HAL_DSI_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
// #define HAL_QSPI_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
// #define HAL_RNG_MODULE_ENABLED
// #define HAL_RTC_MODULE_ENABLED
// #define HAL_SAI_MODULE_ENABLED
// #define HAL_SD_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
// #define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
// #define HAL_IRDA_MODULE_ENABLED
// #define HAL_SMARTCARD_MODULE_ENABLED
// #define HAL_WWDG_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
// #define HAL_PCD_MODULE_ENABLED
// #define HAL_HCD_MODULE_ENABLED
// #define HAL_FMPI2C_MODULE_ENABLED
// #define HAL_SPDIFRX_MODULE_ENABLED
// #define HAL_DFSDM_MODULE_ENABLED
// #define HAL_LPTIM_MODULE_ENABLED
// #define HAL_MMC_MODULE_ENABLED
/* ########################## HSE/HSI Values adaptation ##################### */
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSE) value.
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S peripheral
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE 3300U /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 1U
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 1U
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Ethernet peripheral configuration ##################### */
/* Section 1 : Ethernet peripheral configuration */
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0 2U
#define MAC_ADDR1 0U
#define MAC_ADDR2 0U
#define MAC_ADDR3 0U
#define MAC_ADDR4 0U
#define MAC_ADDR5 0U
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
/* Section 2: PHY configuration section */
/* DP83848 PHY Address*/
#define DP83848_PHY_ADDRESS 0x01U
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY 0x000000FFU
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY 0x00000FFFU
#define PHY_READ_TO 0x0000FFFFU
#define PHY_WRITE_TO 0x0000FFFFU
/* Section 3: Common PHY Registers */
#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)0x0010) /*!< PHY status register Offset */
#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */
#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */
#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */
#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */
#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */
#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */
#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */
#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#define USE_SPI_CRC 1U
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32f4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f4xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
#include "stm32f4xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32f4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
#include "stm32f4xx_hal_dma2d.h"
#endif /* HAL_DMA2D_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_DCMI_MODULE_ENABLED
#include "stm32f4xx_hal_dcmi.h"
#endif /* HAL_DCMI_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32f4xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f4xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_SDRAM_MODULE_ENABLED
#include "stm32f4xx_hal_sdram.h"
#endif /* HAL_SDRAM_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32f4xx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f4xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LTDC_MODULE_ENABLED
#include "stm32f4xx_hal_ltdc.h"
#endif /* HAL_LTDC_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32f4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32f4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32f4xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f4xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32f4xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_DSI_MODULE_ENABLED
#include "stm32f4xx_hal_dsi.h"
#endif /* HAL_DSI_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32f4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f4xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_FMPI2C_MODULE_ENABLED
#include "stm32f4xx_hal_fmpi2c.h"
#endif /* HAL_FMPI2C_MODULE_ENABLED */
#ifdef HAL_SPDIFRX_MODULE_ENABLED
#include "stm32f4xx_hal_spdifrx.h"
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
#ifdef HAL_DFSDM_MODULE_ENABLED
#include "stm32f4xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32f4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f4xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
/* 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 /* __STM32F4xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/