Skip to main content
Visitor II
May 30, 2025
Question

Issue Generating SBUS Signal on STM32F303ZET6 (Timing/Framing Problem)

  • May 30, 2025
  • 0 replies
  • 541 views
/* USER CODE BEGIN Header */
/**
 ******************************************************************************
 * @file : main.c
 * @brief : Main program body
 ******************************************************************************
 * @attention
 *
 * Copyright (c) 2025 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 <stdio.h>
#include <string.h>
#include "time.h"
/* USER CODE END Includes */

/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */

/* USER CODE END PTD */

/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
//#define SBUS_FRAME_PERIOD_MS 3.3f
/* USER CODE END PD */

/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */

/* USER CODE END PM */

/* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim2;

UART_HandleTypeDef huart2;

/* USER CODE BEGIN PV */

uint16_t channels[16]= {
	 1000, 900, 1200, 900,
	 1500, 1500, 1500, 1500,
	 1500, 1500, 1500, 1500,
	 1500, 1500, 1500, 1500
	 };
//uint8_t sbus_test[25] = {
// 0x0F, // SBUS header
// 0x00, 0x04, 0x10, 0x20, // Ch0–1 data bits
// 0x40, 0x80, 0x00, 0x00, // Ch2–5
// 0x00, 0x00, 0x00, 0x00, // Ch6–9
// 0x00, 0x00, 0x00, 0x00, // Ch10–13
// 0x00, 0x00, 0x00, 0x00, // Ch14–15
// 0x00, // Flags
// 0x00 // End byte
//};
/* USER CODE END PV */

/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_USART2_UART_Init(void);
static void MX_TIM2_Init(void);
/* USER CODE BEGIN PFP */

/* USER CODE END PFP */

/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */

void SBUS_GenerateFrame(uint16_t channels[16], uint8_t sbus_data[25]) {
	 memset(sbus_data, 0, 25);
	 sbus_data[0] = 0x0F;
 uint32_t ch[16];
 for (int i = 0; i < 16; i++) {
// ch[i] = channels[i] & 0x07FF; // 11-bit channel data
	 ch[i]=channels[i];
 }
// sbus_data[0] = 0x0F;
 sbus_data[1] = (uint8_t)(ch[0] & 0xFF);
 sbus_data[2] = (uint8_t)((ch[0] >> | (ch[1] << 3));
 sbus_data[3] = (uint8_t)((ch[1] >> 5) | (ch[2] << 6));
 sbus_data[4] = (uint8_t)(ch[2] >> 2);
 sbus_data[5] = (uint8_t)((ch[2] >> 10) | (ch[3] << 1));
 sbus_data[6] = (uint8_t)((ch[3] >> 7) | (ch[4] << 4));
 sbus_data[7] = (uint8_t)((ch[4] >> 4) | (ch[5] << 7));
 sbus_data[8] = (uint8_t)(ch[5] >> 1);
 sbus_data[9] = (uint8_t)((ch[5] >> 9) | (ch[6] << 2));
 sbus_data[10] = (uint8_t)((ch[6] >> 6) | (ch[7] << 5));
 sbus_data[11] = (uint8_t)(ch[7] >> 3);
 sbus_data[12] = (uint8_t)(ch[8] & 0xFF);
 sbus_data[13] = (uint8_t)((ch[8] >> | (ch[9] << 3));
 sbus_data[14] = (uint8_t)((ch[9] >> 5) | (ch[10] << 6));
 sbus_data[15] = (uint8_t)(ch[10] >> 2);
 sbus_data[16] = (uint8_t)((ch[10] >> 10) | (ch[11] << 1));
 sbus_data[17] = (uint8_t)((ch[11] >> 7) | (ch[12] << 4));
 sbus_data[18] = (uint8_t)((ch[12] >> 4) | (ch[13] << 7));
 sbus_data[19] = (uint8_t)(ch[13] >> 1);
 sbus_data[20] = (uint8_t)((ch[13] >> 9) | (ch[14] << 2));
 sbus_data[21] = (uint8_t)((ch[14] >> 6) | (ch[15] << 5));
 sbus_data[22] = (uint8_t)(ch[15] >> 3);
 sbus_data[23] = 0x00; // flags
 sbus_data[24] = 0x00; // end byte
// printf("sbus_data= ");
// 	 			 	 	 for(int i=0;i<16;i++)
// 	 			 	 		 printf(" %d ",sbus_data[i] );
// 	 			 	 	 printf("\r\n");

}
void SBUS_Transmit(UART_HandleTypeDef *huart, uint16_t channels[16]) {
 uint8_t sbus_data[25];
 SBUS_GenerateFrame(channels, sbus_data);
 HAL_UART_Transmit(huart, sbus_data, 25, HAL_MAX_DELAY);
}
//void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
//{
// if (htim->Instance == TIM2)
// {
// 	SBUS_Transmit(&huart2, channels); // Call your SBUS send function here
//// 	HAL_GPIO_TogglePin(GPIOB, GPIO_PIN_0);
//// 	HAL_UART_Transmit(&huart2, sbus_test, 25, 3.3);
// }
//}

/* 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_USART2_UART_Init();
 MX_TIM2_Init();
 /* USER CODE BEGIN 2 */
// HAL_TIM_Base_Start_IT(&htim2);
 /* USER CODE END 2 */

 /* Infinite loop */
 /* USER CODE BEGIN WHILE */
 while (1)
 {
//
//	 SBUS_Transmit(&huart2, channels);
//	 HAL_Delay(10);
	 HAL_GPIO_TogglePin(GPIOB, GPIO_PIN_0);
 /* 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};
 RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};

 /** Initializes the RCC Oscillators according to the specified parameters
 * in the RCC_OscInitTypeDef structure.
 */
 RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
 RCC_OscInitStruct.HSEState = RCC_HSE_ON;
 RCC_OscInitStruct.HSIState = RCC_HSI_ON;
 RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
 RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
 RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
 RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
 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();
 }
 PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_TIM2;
 PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
 PeriphClkInit.Tim2ClockSelection = RCC_TIM2CLK_HCLK;
 if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
 {
 Error_Handler();
 }
}

/**
 * @brief TIM2 Initialization Function
 * None
 * @retval None
 */
static void MX_TIM2_Init(void)
{

 /* USER CODE BEGIN TIM2_Init 0 */

 /* USER CODE END TIM2_Init 0 */

 TIM_ClockConfigTypeDef sClockSourceConfig = {0};
 TIM_MasterConfigTypeDef sMasterConfig = {0};
 TIM_OC_InitTypeDef sConfigOC = {0};

 /* USER CODE BEGIN TIM2_Init 1 */

 /* USER CODE END TIM2_Init 1 */
 htim2.Instance = TIM2;
 htim2.Init.Prescaler = 71;
 htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
 htim2.Init.Period = 3299;
 htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
 htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
 if (HAL_TIM_Base_Init(&htim2) != HAL_OK)
 {
 Error_Handler();
 }
 sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
 if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK)
 {
 Error_Handler();
 }
 if (HAL_TIM_OC_Init(&htim2) != HAL_OK)
 {
 Error_Handler();
 }
 sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
 sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
 if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
 {
 Error_Handler();
 }
 sConfigOC.OCMode = TIM_OCMODE_TIMING;
 sConfigOC.Pulse = 0;
 sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
 sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
 if (HAL_TIM_OC_ConfigChannel(&htim2, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
 {
 Error_Handler();
 }
 /* USER CODE BEGIN TIM2_Init 2 */

 /* USER CODE END TIM2_Init 2 */
 HAL_TIM_MspPostInit(&htim2);

}

/**
 * @brief USART2 Initialization Function
 * None
 * @retval None
 */
static void MX_USART2_UART_Init(void)
{

 /* USER CODE BEGIN USART2_Init 0 */

 /* USER CODE END USART2_Init 0 */

 /* USER CODE BEGIN USART2_Init 1 */

 /* USER CODE END USART2_Init 1 */
 huart2.Instance = USART2;
 huart2.Init.BaudRate = 100000;
 huart2.Init.WordLength = UART_WORDLENGTH_8B;
 huart2.Init.StopBits = UART_STOPBITS_2;
 huart2.Init.Parity = UART_PARITY_EVEN;
 huart2.Init.Mode = UART_MODE_TX_RX;
 huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
 huart2.Init.OverSampling = UART_OVERSAMPLING_16;
 huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
 huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_TXINVERT_INIT;
 huart2.AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE;
 if (HAL_UART_Init(&huart2) != HAL_OK)
 {
 Error_Handler();
 }
 /* USER CODE BEGIN USART2_Init 2 */

 /* USER CODE END USART2_Init 2 */

}

/**
 * @brief GPIO Initialization Function
 * None
 * @retval None
 */
static void MX_GPIO_Init(void)
{
 GPIO_InitTypeDef GPIO_InitStruct = {0};
 /* USER CODE BEGIN MX_GPIO_Init_1 */

 /* USER CODE END MX_GPIO_Init_1 */

 /* GPIO Ports Clock Enable */
 __HAL_RCC_GPIOF_CLK_ENABLE();
 __HAL_RCC_GPIOA_CLK_ENABLE();
 __HAL_RCC_GPIOB_CLK_ENABLE();

 /*Configure GPIO pin Output Level */
 HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET);

 /*Configure GPIO pin : PB0 */
 GPIO_InitStruct.Pin = GPIO_PIN_0;
 GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
 GPIO_InitStruct.Pull = GPIO_NOPULL;
 GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
 HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

 /* 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.
 * file: pointer to the source file name
 * 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 */

Hello ST Community,

I'm facing an issue Generating and transmitting SBUS signals on a (STM32F303ZET6) NUCLEO F303ZE board.

  1. [Part Number]

STM32F303ZET6 (LQFP144, ARM Cortex-M4)

  1. [Environment]
  • Toolchain: STM32CubeIDE v[YourVersion]

  • HAL or LL Drivers: [HAL/LL version]

  • Debug Interface: ST-Link V2

  • Board:  Nucleo-F303ZE 
  • UART configured at 100000 baud, 8E2 Inverted
  1. [Details – Problem Description]
    I’m trying to generate an SBUS signal on a UART configured for 100000 baud, 8E2 using STM32F303ZET6. The signal is meant to replicate a Futaba-compatible SBUS stream with 25-byte frames at ~7ms intervals.

However:

  • The output frame timing or logic levels are inconsistent.

  • Some receivers fail to detect valid SBUS frames.

  • (Include screenshots from logic analyzer/scope if available)

  1. [Expected Behavior]
  • Consistent, valid SBUS frames every 7ms

  • UART configured to send SBUS frames that match the Futaba protocol:

    • Start byte: 0x0F

    • 22 bytes of data (16 channels packed)

    • 1 flag byte

    • End byte: 0x00

  1. [How to Reproduce]
  1. Configure UARTx on STM32F303ZET6 to 100000 baud, Even parity, 2 stop bits

  2. Transmit hardcoded SBUS frame buffer (25 bytes)

  3. Observe output on logic analyzer or oscilloscope

  4. Attempt to read signal on SBUS-compatible receiver or decoder

  1. [Occurrence]

 


Systematic: Happens every time I transmit SBUS

One or two time the sbus was detected when i transmitted only 16 bytes via uart with using command

memset(sbus_data, 0, 16);

 HAL_UART_Transmit(huart, sbus_data, 16, HAL_MAX_DELAY);

  1. [Sanity Checks Performed]
  • Verified baud, parity, and stop bits

  • Manually calculated timing of each byte

  • Compared with SBUS specification and working SBUS signal from known-good transmitter

  • Attempted both HAL and LL UART implementations

  • Searched STM32 forums and GitHub for existing SBUS implementations



    This topic has been closed for replies.