Lepton v2 revised design --- tested working 30V / 80A MOSFETs

So, if you still have the boot0 [PA14] pin broken out, you can tell the stm32g031 to go into bootloader mode AKA look at PA2/PA3 or PA9/PA10 for uart input. Then, you can connect STM32Programmer over USART and it is basically equivalent to using the SWD pins.

The reason I am reiterating this is because you have the option to use PA2/PA3 or PA9/PA10, as they are available via alternate pin mapping (see picture). Additionally, the original board had I2C2 pins (PA9/PA10) labeled on the schematic, but not broken out to a connector. It seems this board is just itching to have full USART support!

(Also this is sort of a vicarious effort on my part, since I don’t know much about PCB design lol)

PA14 is the presently-unavailable SWCLK, so I’ll have to get it accessible. Maybe if I get CSS on the encoder header, its former pin can be repurposed for this, and I can have my easy FTDI interface. But then I’m only one pin short of proper SWD access…

Do you know if it will have to be manually reset after every upload of a new program, or if it will auto-execute like Atmel-based Arduinos? I stuck that reset solder pad on there just incase, but it would be nice to know for sure whether it’s needed.

So that’s what the PA9/PA10 in brackets meant :slight_smile: Those are already accessible as MOSI and MISO, so maybe either that or PA2/PA3 will work regardless of the initial state of the boot selector bit.

So unless you want to have problems you should definitely provide a way to access the SWD pins. They will not only allow debugging, SWD will allow programming in any situation, while UART or other options depend on you getting into the boot loader…
You should also expose nRST for a seamless experience.

To use SWD you need a STLink programmer, the STLink Mini v3 is cheap and ideally suited, but if it’s not available, an STLink v2 (there are also clones) is enough…
To use it you need the following connections:
gnd
swclk
swdio
nRST
vdd (output to STLink, not input)

Maybe adding a JST-SH connector is a solution?

1 Like

Ok, here is the next candidate, 25x25mm. The only casualty this time was my HV-to-VCC jumper, so now you must have a separate supply wire for the mid voltage rail even if the main voltage is low enough to use.

The idea behind this one is to have compact solder connections to the power and communication pins in final use, and a 1.25mm pitch connector for all the pins that will be used during programming. The encoder will use a 1.25mm connector even in final use. I could potentially fit 6 holes over there if I stagger them or use 2x3, but connectors are kind of nice anyway. The ones I chose are LCSC parts C519006 and C519009. They look compatible with JST female, but let me know if there is a better choice. JST-SH seemed to be all SMD, which has a larger footprint.

I also managed to fit the second 10uF, despite the loss of some board area to the connectors. It was a hard fought battle routing around everything, but I managed.

I currently have I2C2 on the programming connector and I2C1 as the two communication pins. I may change it so UART2 goes to both of those, since SimpleFOC commander uses UART. But because I’m planning to have 4 boards stacked on top of eachother, if I can get each one to respond as a different I2C slave address then I can communicate to the whole stack from a single pair of wires running axially through the holes. That’s how I plan to do the power wires too.

One of the connectors seems to be floating in the 3D model. Presumably it will not float in real life :slight_smile:
Front4
Back4

2 Likes

Not sure if it is JST SH compatible, it looks a bit different… you’ll have to try. The reason I like JST is that there are plenty of cheap, pre-made cables you can order on AliExpress…
But I understand the footprint is larger in SMD…

We also have an I2CCommander in our drivers repository…running 4 on the same I2C bus should be quite possible.
If you don’t provide a way to set the I2C address in hardware (jumpers, switches) then you will have to do it in software, which means flashing a different firmware image to each board, or connecting to them individually via a different protocol first to configure them.

Right, these are not SH compatible. Upon paying better attention, SH is 1mm pitch. But these do look compatible with cheaply available 1.25mm pitch pre-made cables, which is what I had in mind. I’ll be ordering the connectors separately from the PCBs to avoid the manual soldering fee, so I’ll get a couple different brands to try since they’re so cheap.

Great to hear the work is already done on I2C communication :slight_smile:

I made a few more minor modifications, and placed the order for the boards. The most significant thing is that I moved the 2mm pitch communication pins over with the power pins on the right, and changed it so both those and the programming connector use I2C1 so you can issue commands via the programming connector as well without having to change the code. You can still use an I2C LCD or other devices on the same bus, so there wasn’t much advantage in having I2C2 available, plus this simplifies the routing.

Unfortunately at some point I forgot to pay attention to which SPI pins are also ADC, and ended up with only one ADC pin on the encoder connector so I won’t be able to use linear hall sensors on it. I’ve since corrected it, and I will be able to connect linear halls via the programming connector so no big deal. It’s a great relief to have the MOSFETs confirmed before they’re out of stock. Now even if I did make any serious mistakes, the worst case is I have to transplant them to new boards.

Thank you to everyone for your input! And sorry for taking over your thread, Valentine :slight_smile: I’ll start a new thread when my boards arrive in a few weeks. For now it’s back to machining aluminum while I wait.
Front6
Back6

2 Likes

Hi Runger,
I could not start the UART port on LEPTON V2 board.
Can somebody help me.
Serial.begin() does no action.
Serial2.begin() does no action

HardwareSerial Serial2(PA15, PA2); gives error (multiple definition of `Serial2’; )

Metin

Hi Metin,

I’m sorry but I don’t have a Lepton board myself… I’m afraid I can’t help you there, but I know @Valentine made a guide for one of his boards… did you check it out?

Metin:

Could you please post the entire code? It’s very difficult to debug without the full code. I need to be able to load it on the board.

Cheers,
Valentine

Hi Valentine,

please find the code below;

#include <SimpleFOC.h>

BLDCMotor motor = BLDCMotor(4);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PA7, PB3, PB0, PB6, PB1);

float target_velocity = 2.0;
float target_voltage = 1.0;
unsigned long timer = 0;

//HardwareSerial Serial2(PA15, PA2);

void setup() {
  Serial2.begin(115200);
  Serial2.print("TEST\n");
  driver.voltage_power_supply = 12;
  driver.pwm_frequency = 15000;
  driver.init();
  motor.linkDriver(&driver);
  motor.voltage_limit = 12;   // [V]
  motor.velocity_limit = 300; // [rad/s]
  motor.voltage_limit = target_voltage;
  motor.controller = MotionControlType::velocity_openloop;
  motor.useMonitoring(Serial2);
  motor.init();
  _delay(1000);
  }

void loop() {

    if((millis()-timer)>100){  
      target_velocity = target_velocity +10;
      if (target_velocity  > 100) target_velocity =100 ;
      target_voltage = 1+ target_velocity * 0.02;
      timer = millis();
    }
  //  target_velocity = 5.0;
  //  target_voltage  = 1.0;
    motor.voltage_limit = target_voltage;
    motor.move(target_velocity);
    motor.loopFOC();
    motor. Monitor();
}

Got it, will look into it.

How are you connecting to the Serial port? What serial debugger are you using?

Cheers,
Valentine

same module as you suggested

FT232RL FTDI Mini USB to TTL Serial Converter

1 Like

I’m traveling and will be back in a day, will look into this.

Metin:

I am away on a business trip for work, however, these are my suggestions until I get to be able to look into this on the bench:

  1. Please double check that you included the optional build .h file to enable the hardware serial. This is a file called

build_opt.h

which must be placed in your arduino project file directory

-D ENABLE_HWSERIAL1 -D ENABLE_HWSERIAL2 -D ENABLE_HWSERIAL3

After you do that, try hardware Serial2 again, but read the other points below first.

  1. Lower your baud rate to 9600 to make sure you exclude/filter any noise in the lines.

  2. Make sure your FTDI converter is set to work with 3.3V, not 5V logic.

  3. Make sure your Lepton RX goes into the FTDI TX, and the TX into the RX (they must be crossed).

  4. If the hardware serial still fails, here is sample code for you to try software serial, this works on any two pins. I edited the code to match the Lepton Serial pins. This will override the hardware serial and should be able to get the Serial working.

#include "SoftwareSerial.h"

#define SS_USB_RX  PA15
#define SS_USB_TX  PA2

// ANY OTHER SOFT SERIAL BAUD RATE WILL CHOKE
// BAUD RATE MUST BE BETWEEN 9600..38400
// ANY OTHER BAUD RATE WILL CHOKE

SoftwareSerial SoftSerialUSB(SS_USB_RX, SS_USB_TX);

void setup()
{
  //set pins for Software Serial communication
  SoftSerialUSB.begin(9600);
  pinMode(SS_USB_RX, INPUT);
  pinMode(SS_USB_TX, OUTPUT);

  delay(1000);
}

void loop()
{
  SoftSerialUSB.println("TEST SSERIAL_USB");
  delay(100);
}

You need to include this software serial sample code in your SimpleFOC code.

Cheers,
Valentine

1 Like

@Juan-Antonio_Soren_E

Your post is out of topic. Please respect others.

Sorry, to much to drink :sweat_smile:

1 Like

Thanks, HardwareSerial working now,

I had to correct the line;

HardwareSerial Serial2(USART2); //HardwareSerial Serial2(PA15, PA2);

Cheers Metin

1 Like

I’m still working on the openerv, and pretty much bent on using the lepton at this point, will review the stuff above. I think I need an integral angle sensor though. It costs more and takes more room and stuff to have a separate board, the boards are quite expensive, I would think the chip costs a lot less.

Lepton Performance MCU internal clock maximum setup.

This below will set your Lepton Arduino project to maximum clock performance at 64MHz since this Lepton PCB has an MCU that is using an internal clock and not using an external clock to save on space and cost.

I credit @runger for the write-up on how to do it and copy here his steps:

  • use STM32CubeIDE to create a new project for your exact MCU type
  • use the clock configuration screen like in Valentine’s screenshot to set up a valid configuration. The tool will help you and warn you about mistakes.
  • save the MCU configuration in CubeIDE, and choose “Yes” when it asks you about generating code.
  • it will generate a file in the Core/src/ directory of the project called “main.c”, and this will contain a function called “SystemClock_Config”
  • copy this function into your Arduino project, either into your .ino file or in its own .cpp file.
  • you don’t need to call the function, Arduino framework for STM32 will call it automatically
  • if using platformIO, make sure you have the option lib_archive = false in your platformio.ini

That should get you running with a working clock, but really there should be a board variant file for the Lepton which describes its setup details

/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file           : main.c
  * @brief          : Main program body
  ******************************************************************************
  * @attention
  *
  * <h2><center>&copy; Copyright (c) 2023 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 */

/* USER CODE END Includes */

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

/* USER CODE END PTD */

/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */

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

/* USER CODE END PM */

/* Private variables ---------------------------------------------------------*/
ADC_HandleTypeDef hadc1;

I2C_HandleTypeDef hi2c1;
I2C_HandleTypeDef hi2c2;

SPI_HandleTypeDef hspi1;

TIM_HandleTypeDef htim1;

UART_HandleTypeDef huart2;

/* USER CODE BEGIN PV */

/* USER CODE END PV */

/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_ADC1_Init(void);
static void MX_I2C1_Init(void);
static void MX_I2C2_Init(void);
static void MX_SPI1_Init(void);
static void MX_TIM1_Init(void);
static void MX_USART2_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_ADC1_Init();
  MX_I2C1_Init();
  MX_I2C2_Init();
  MX_SPI1_Init();
  MX_TIM1_Init();
  MX_USART2_UART_Init();
  /* USER CODE BEGIN 2 */

  /* 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};
  RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};

  /** Configure the main internal regulator output voltage
  */
  HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1);
  /** 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.HSIDiv = RCC_HSI_DIV1;
  RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
  RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
  RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
  RCC_OscInitStruct.PLL.PLLN = 12;
  RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
  RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
  RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV3;
  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_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;

  if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
  {
    Error_Handler();
  }
  /** Initializes the peripherals clocks
  */
  PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_ADC
                              |RCC_PERIPHCLK_TIM1;
  PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1;
  PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_SYSCLK;
  PeriphClkInit.Tim1ClockSelection = RCC_TIM1CLKSOURCE_PCLK1;
  if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
  {
    Error_Handler();
  }
}

/**
  * @brief ADC1 Initialization Function
  * @param None
  * @retval None
  */
static void MX_ADC1_Init(void)
{

  /* USER CODE BEGIN ADC1_Init 0 */

  /* USER CODE END ADC1_Init 0 */

  ADC_ChannelConfTypeDef sConfig = {0};

  /* USER CODE BEGIN ADC1_Init 1 */

  /* USER CODE END ADC1_Init 1 */
  /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
  */
  hadc1.Instance = ADC1;
  hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV2;
  hadc1.Init.Resolution = ADC_RESOLUTION_12B;
  hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
  hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
  hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
  hadc1.Init.LowPowerAutoWait = DISABLE;
  hadc1.Init.LowPowerAutoPowerOff = DISABLE;
  hadc1.Init.ContinuousConvMode = DISABLE;
  hadc1.Init.NbrOfConversion = 1;
  hadc1.Init.DiscontinuousConvMode = DISABLE;
  hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
  hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
  hadc1.Init.DMAContinuousRequests = DISABLE;
  hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED;
  hadc1.Init.SamplingTimeCommon1 = ADC_SAMPLETIME_1CYCLE_5;
  hadc1.Init.SamplingTimeCommon2 = ADC_SAMPLETIME_1CYCLE_5;
  hadc1.Init.OversamplingMode = DISABLE;
  hadc1.Init.TriggerFrequencyMode = ADC_TRIGGER_FREQ_HIGH;
  if (HAL_ADC_Init(&hadc1) != HAL_OK)
  {
    Error_Handler();
  }
  /** Configure Regular Channel
  */
  sConfig.Channel = ADC_CHANNEL_0;
  sConfig.Rank = ADC_REGULAR_RANK_1;
  sConfig.SamplingTime = ADC_SAMPLINGTIME_COMMON_1;
  if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN ADC1_Init 2 */

  /* USER CODE END ADC1_Init 2 */

}

/**
  * @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.Timing = 0x10707DBC;
  hi2c1.Init.OwnAddress1 = 0;
  hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
  hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
  hi2c1.Init.OwnAddress2 = 0;
  hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
  hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
  hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
  if (HAL_I2C_Init(&hi2c1) != HAL_OK)
  {
    Error_Handler();
  }
  /** Configure Analogue filter
  */
  if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
  {
    Error_Handler();
  }
  /** Configure Digital filter
  */
  if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN I2C1_Init 2 */

  /* USER CODE END I2C1_Init 2 */

}

/**
  * @brief I2C2 Initialization Function
  * @param None
  * @retval None
  */
static void MX_I2C2_Init(void)
{

  /* USER CODE BEGIN I2C2_Init 0 */

  /* USER CODE END I2C2_Init 0 */

  /* USER CODE BEGIN I2C2_Init 1 */

  /* USER CODE END I2C2_Init 1 */
  hi2c2.Instance = I2C2;
  hi2c2.Init.Timing = 0x10707DBC;
  hi2c2.Init.OwnAddress1 = 0;
  hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
  hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
  hi2c2.Init.OwnAddress2 = 0;
  hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
  hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
  hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
  if (HAL_I2C_Init(&hi2c2) != HAL_OK)
  {
    Error_Handler();
  }
  /** Configure Analogue filter
  */
  if (HAL_I2CEx_ConfigAnalogFilter(&hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
  {
    Error_Handler();
  }
  /** Configure Digital filter
  */
  if (HAL_I2CEx_ConfigDigitalFilter(&hi2c2, 0) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN I2C2_Init 2 */

  /* USER CODE END I2C2_Init 2 */

}

/**
  * @brief SPI1 Initialization Function
  * @param None
  * @retval None
  */
static void MX_SPI1_Init(void)
{

  /* USER CODE BEGIN SPI1_Init 0 */

  /* USER CODE END SPI1_Init 0 */

  /* USER CODE BEGIN SPI1_Init 1 */

  /* USER CODE END SPI1_Init 1 */
  /* SPI1 parameter configuration*/
  hspi1.Instance = SPI1;
  hspi1.Init.Mode = SPI_MODE_MASTER;
  hspi1.Init.Direction = SPI_DIRECTION_2LINES;
  hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
  hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
  hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
  hspi1.Init.NSS = SPI_NSS_HARD_INPUT;
  hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
  hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
  hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
  hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
  hspi1.Init.CRCPolynomial = 7;
  hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
  hspi1.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
  if (HAL_SPI_Init(&hspi1) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN SPI1_Init 2 */

  /* USER CODE END SPI1_Init 2 */

}

/**
  * @brief TIM1 Initialization Function
  * @param None
  * @retval None
  */
static void MX_TIM1_Init(void)
{

  /* USER CODE BEGIN TIM1_Init 0 */

  /* USER CODE END TIM1_Init 0 */

  TIM_MasterConfigTypeDef sMasterConfig = {0};
  TIM_OC_InitTypeDef sConfigOC = {0};
  TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};

  /* USER CODE BEGIN TIM1_Init 1 */

  /* USER CODE END TIM1_Init 1 */
  htim1.Instance = TIM1;
  htim1.Init.Prescaler = 0;
  htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
  htim1.Init.Period = 65535;
  htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
  htim1.Init.RepetitionCounter = 0;
  htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
  if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
  {
    Error_Handler();
  }
  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
  sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
  if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
  {
    Error_Handler();
  }
  sConfigOC.OCMode = TIM_OCMODE_PWM1;
  sConfigOC.Pulse = 0;
  sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
  sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
  sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
  sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
  sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
  if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
  {
    Error_Handler();
  }
  if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
  {
    Error_Handler();
  }
  if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
  {
    Error_Handler();
  }
  sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
  sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
  sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
  sBreakDeadTimeConfig.DeadTime = 0;
  sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
  sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
  sBreakDeadTimeConfig.BreakFilter = 0;
  sBreakDeadTimeConfig.BreakAFMode = TIM_BREAK_AFMODE_INPUT;
  sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
  sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
  sBreakDeadTimeConfig.Break2Filter = 0;
  sBreakDeadTimeConfig.Break2AFMode = TIM_BREAK_AFMODE_INPUT;
  sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
  if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN TIM1_Init 2 */

  /* USER CODE END TIM1_Init 2 */
  HAL_TIM_MspPostInit(&htim1);

}

/**
  * @brief USART2 Initialization Function
  * @param None
  * @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 = 115200;
  huart2.Init.WordLength = UART_WORDLENGTH_8B;
  huart2.Init.StopBits = UART_STOPBITS_1;
  huart2.Init.Parity = UART_PARITY_NONE;
  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.Init.ClockPrescaler = UART_PRESCALER_DIV1;
  huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
  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
  * @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_GPIOA_CLK_ENABLE();
  __HAL_RCC_GPIOB_CLK_ENABLE();

  /*Configure GPIO pin : PC15 */
  GPIO_InitStruct.Pin = GPIO_PIN_15;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF1_OSC;
  HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);

}

/* 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 */

  /* 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,
     tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
  /* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

The original @runger and a longer thread post is here, where @dekutree64 is setting this up:

3 Likes

What a nice and compact explanation!
Would be great to have that somewhere as educational material.

1 Like