diff --git a/examples/hardware_specific_examples/B_G431B_ESC1/B_G431B_ESC1_position_control.ino b/examples/hardware_specific_examples/B_G431B_ESC1/B_G431B_ESC1_position_control.ino new file mode 100644 index 00000000..41d9148b --- /dev/null +++ b/examples/hardware_specific_examples/B_G431B_ESC1/B_G431B_ESC1_position_control.ino @@ -0,0 +1,117 @@ +/** + * B-G431B-ESC1 position motion control example with encoder + * + */ +#include + +// Motor instance +BLDCMotor motor = BLDCMotor(11); +BLDCDriver6PWM driver = BLDCDriver6PWM(PHASE_UH, PHASE_UL, PHASE_VH, PHASE_VL, PHASE_WH, PHASE_WL); +InlineCurrentSense currentSense = InlineCurrentSense(0.003, -64.0/7.0, OP1_OUT, OP2_OUT, OP3_OUT); + + +// encoder instance +Encoder encoder = Encoder(HALL2, HALL3, 2048, HALL1); + +// Interrupt routine intialisation +// channel A and B callbacks +void doA(){encoder.handleA();} +void doB(){encoder.handleB();} +void doIndex(){encoder.handleIndex();} + +// angle set point variable +float target_angle = 0; +// instantiate the commander +Commander command = Commander(Serial); +void doTarget(char* cmd) { command.scalar(&target_angle, cmd); } + +void setup() { + + // initialize encoder sensor hardware + encoder.init(); + encoder.enableInterrupts(doA, doB); + + // link the motor to the sensor + motor.linkSensor(&encoder); + + // driver config + // power supply voltage [V] + driver.voltage_power_supply = 12; + driver.init(); + // link the motor and the driver + motor.linkDriver(&driver); + + // current sensing + currentSense.init(); + motor.linkCurrentSense(¤tSense); + + // aligning voltage [V] + motor.voltage_sensor_align = 3; + // index search velocity [rad/s] + motor.velocity_index_search = 3; + + // set motion control loop to be used + motor.controller = MotionControlType::velocity; + + // contoller configuration + // default parameters in defaults.h + + // velocity PI controller parameters + motor.PID_velocity.P = 0.2; + motor.PID_velocity.I = 20; + // default voltage_power_supply + motor.voltage_limit = 6; + // jerk control using voltage voltage ramp + // default value is 300 volts per sec ~ 0.3V per millisecond + motor.PID_velocity.output_ramp = 1000; + + // velocity low pass filtering time constant + motor.LPF_velocity.Tf = 0.01; + + // angle P controller + motor.P_angle.P = 20; + // maximal velocity of the position control + motor.velocity_limit = 4; + + + // use monitoring with serial + Serial.begin(115200); + // comment out if not needed + motor.useMonitoring(Serial); + + // initialize motor + motor.init(); + // align encoder and start FOC + motor.initFOC(); + + // add target command T + command.add('T', doTarget, "target angle"); + + Serial.println(F("Motor ready.")); + Serial.println(F("Set the target angle using serial terminal:")); + _delay(1000); +} + +// angle set point variable +float target_angle = 0; + +void loop() { + // main FOC algorithm function + // the faster you run this function the better + // Arduino UNO loop ~1kHz + // Bluepill loop ~10kHz + motor.loopFOC(); + + // Motion control function + // velocity, position or voltage (defined in motor.controller) + // this function can be run at much lower frequency than loopFOC() function + // You can also use motor.move() and set the motor.target in the code + motor.move(target_angle); + + // function intended to be used with serial plotter to monitor motor variables + // significantly slowing the execution down!!!! + // motor.monitor(); + + // user communication + command.run(); +} \ No newline at end of file diff --git a/examples/hardware_specific_examples/B_G431B_ESC1/build_opt.h b/examples/hardware_specific_examples/B_G431B_ESC1/build_opt.h new file mode 100644 index 00000000..6f547ecd --- /dev/null +++ b/examples/hardware_specific_examples/B_G431B_ESC1/build_opt.h @@ -0,0 +1 @@ +-DHAL_OPAMP_MODULE_ENABLED \ No newline at end of file diff --git a/src/current_sense/hardware_specific/generic_mcu.cpp b/src/current_sense/hardware_specific/generic_mcu.cpp index ecc0b79b..50f383ad 100644 --- a/src/current_sense/hardware_specific/generic_mcu.cpp +++ b/src/current_sense/hardware_specific/generic_mcu.cpp @@ -26,7 +26,6 @@ __attribute__((weak)) void _configureADCLowSide(const int pinA,const int pinB,c if( _isset(pinC) ) pinMode(pinC, INPUT); } - // sync driver and the adc __attribute__((weak)) void _driverSyncLowSide(){ } __attribute__((weak)) void _startADC3PinConversionLowSide(){ } diff --git a/src/current_sense/hardware_specific/stm32_mcu.cpp b/src/current_sense/hardware_specific/stm32_mcu.cpp index 19833e11..797ac6a1 100644 --- a/src/current_sense/hardware_specific/stm32_mcu.cpp +++ b/src/current_sense/hardware_specific/stm32_mcu.cpp @@ -1,7 +1,7 @@ #include "../hardware_api.h" -#if defined(_STM32_DEF_) +#if defined(_STM32_DEF_) and !defined(STM32G4xx) #define _ADC_VOLTAGE 3.3f #define _ADC_RESOLUTION 1024.0f diff --git a/src/current_sense/hardware_specific/stm32g4_hal.cpp b/src/current_sense/hardware_specific/stm32g4_hal.cpp new file mode 100644 index 00000000..f0204566 --- /dev/null +++ b/src/current_sense/hardware_specific/stm32g4_hal.cpp @@ -0,0 +1,333 @@ +#include "../hardware_api.h" +#if defined(STM32G4xx) + +#include "stm32g4xx_hal.h" +#include "stm32g4xx_ll_pwr.h" +#include "stm32g4xx_hal_adc.h" +#include "stm32g4_hal.h" +// From STM32 cube IDE +/** + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2020 STMicroelectronics. + * All rights reserved.

+ * + * 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 + * + ****************************************************************************** + */ + + +/** + * @brief GPIO Initialization Function + * @param None + * @retval None + */ +void MX_GPIO_Init(void) +{ + /* GPIO Ports Clock Enable */ + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOF_CLK_ENABLE(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + + __HAL_RCC_ADC12_CLK_ENABLE(); +} + +/** + * Enable DMA controller clock + */ +void MX_DMA_Init(void) +{ + /* DMA controller clock enable */ + __HAL_RCC_DMAMUX1_CLK_ENABLE(); + __HAL_RCC_DMA1_CLK_ENABLE(); + __HAL_RCC_DMA2_CLK_ENABLE(); + + /* DMA interrupt init */ + /* DMA1_Channel1_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn); + /* DMA1_Channel2_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn); + + // Enable external clock for ADC + RCC_PeriphCLKInitTypeDef PeriphClkInit; + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC12; + PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_PLL; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit); +} + + +/** + * @brief ADC1 Initialization Function + * @param None + * @retval None + */ +void MX_ADC1_Init(ADC_HandleTypeDef* hadc1) +{ + /* USER CODE BEGIN ADC1_Init 0 */ + + /* USER CODE END ADC1_Init 0 */ + + ADC_MultiModeTypeDef multimode = {0}; + ADC_ChannelConfTypeDef sConfig = {0}; + + /* USER CODE BEGIN ADC1_Init 1 */ + + /* USER CODE END ADC1_Init 1 */ + /** Common config + */ + hadc1->Instance = ADC1; + hadc1->Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV16; + hadc1->Init.Resolution = ADC_RESOLUTION_12B; + hadc1->Init.DataAlign = ADC_DATAALIGN_RIGHT; + hadc1->Init.GainCompensation = 0; + hadc1->Init.ScanConvMode = ADC_SCAN_ENABLE; + hadc1->Init.EOCSelection = ADC_EOC_SINGLE_CONV; + hadc1->Init.LowPowerAutoWait = DISABLE; + hadc1->Init.ContinuousConvMode = DISABLE; + hadc1->Init.NbrOfConversion = 2; + hadc1->Init.DiscontinuousConvMode = DISABLE; + hadc1->Init.ExternalTrigConv = ADC_EXTERNALTRIG_T1_TRGO; + hadc1->Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING; + hadc1->Init.DMAContinuousRequests = ENABLE; + hadc1->Init.Overrun = ADC_OVR_DATA_PRESERVED; + + if (HAL_ADC_Init(hadc1) != HAL_OK) + { + Error_Handler(); + } + + /** Configure the ADC multi-mode + */ + multimode.Mode = ADC_MODE_INDEPENDENT; + if (HAL_ADCEx_MultiModeConfigChannel(hadc1, &multimode) != HAL_OK) + { + Error_Handler(); + } + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_12; // ADC1_IN12 = PB1 = OP3_OUT + sConfig.Rank = ADC_REGULAR_RANK_1; + sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; + sConfig.SingleDiff = ADC_SINGLE_ENDED; + sConfig.OffsetNumber = ADC_OFFSET_NONE; + sConfig.Offset = 0; + if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_3; // ADC1_IN3 = PA2 = OP1_OUT + sConfig.Rank = ADC_REGULAR_RANK_2; + if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN ADC1_Init 2 */ + + /* USER CODE END ADC1_Init 2 */ + +} + +/** + * @brief ADC2 Initialization Function + * @param None + * @retval None + */ +void MX_ADC2_Init(ADC_HandleTypeDef* hadc2) +{ + /* USER CODE BEGIN ADC2_Init 0 */ + + /* USER CODE END ADC2_Init 0 */ + + ADC_ChannelConfTypeDef sConfig = {0}; + + /* USER CODE BEGIN ADC2_Init 1 */ + + /* USER CODE END ADC2_Init 1 */ + /** Common config + */ + hadc2->Instance = ADC2; + hadc2->Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV16; + hadc2->Init.Resolution = ADC_RESOLUTION_12B; + hadc2->Init.DataAlign = ADC_DATAALIGN_RIGHT; + hadc2->Init.GainCompensation = 0; + hadc2->Init.ScanConvMode = ADC_SCAN_ENABLE; + hadc2->Init.EOCSelection = ADC_EOC_SINGLE_CONV; + hadc2->Init.LowPowerAutoWait = DISABLE; + hadc2->Init.ContinuousConvMode = DISABLE; + hadc2->Init.NbrOfConversion = 1; + hadc2->Init.DiscontinuousConvMode = DISABLE; + hadc2->Init.ExternalTrigConv = ADC_EXTERNALTRIG_T1_TRGO; + hadc2->Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING; + hadc2->Init.DMAContinuousRequests = ENABLE; + hadc2->Init.Overrun = ADC_OVR_DATA_PRESERVED; + + if (HAL_ADC_Init(hadc2) != HAL_OK) + { + Error_Handler(); + } + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_3; // ADC2_IN3 = PA6 + sConfig.Rank = ADC_REGULAR_RANK_1; + sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; + sConfig.SingleDiff = ADC_SINGLE_ENDED; + sConfig.OffsetNumber = ADC_OFFSET_NONE; + sConfig.Offset = 0; + if (HAL_ADC_ConfigChannel(hadc2, &sConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN ADC2_Init 2 */ + + /* USER CODE END ADC2_Init 2 */ + +} + +/** +* @brief OPAMP MSP Initialization +* This function configures the hardware resources used in this example +* @param hopamp-> OPAMP handle pointer +* @retval None +*/ +void HAL_OPAMP_MspInit(OPAMP_HandleTypeDef* hopamp) +{ + GPIO_InitTypeDef GPIO_InitStruct = {0}; + if(hopamp->Instance==OPAMP1) + { + /* USER CODE BEGIN OPAMP1_MspInit 0 */ + + /* USER CODE END OPAMP1_MspInit 0 */ + + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**OPAMP1 GPIO Configuration + PA1 ------> OPAMP1_VINP + PA2 ------> OPAMP1_VOUT + PA3 ------> OPAMP1_VINM + */ + GPIO_InitStruct.Pin = GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* USER CODE BEGIN OPAMP1_MspInit 1 */ + + /* USER CODE END OPAMP1_MspInit 1 */ + } + else if(hopamp->Instance==OPAMP2) + { + /* USER CODE BEGIN OPAMP2_MspInit 0 */ + + /* USER CODE END OPAMP2_MspInit 0 */ + + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**OPAMP2 GPIO Configuration + PA5 ------> OPAMP2_VINM + PA6 ------> OPAMP2_VOUT + PA7 ------> OPAMP2_VINP + */ + GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* USER CODE BEGIN OPAMP2_MspInit 1 */ + + /* USER CODE END OPAMP2_MspInit 1 */ + } + else if(hopamp->Instance==OPAMP3) + { + /* USER CODE BEGIN OPAMP3_MspInit 0 */ + + /* USER CODE END OPAMP3_MspInit 0 */ + + __HAL_RCC_GPIOB_CLK_ENABLE(); + /**OPAMP3 GPIO Configuration + PB0 ------> OPAMP3_VINP + PB1 ------> OPAMP3_VOUT + PB2 ------> OPAMP3_VINM + */ + GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* USER CODE BEGIN OPAMP3_MspInit 1 */ + + /* USER CODE END OPAMP3_MspInit 1 */ + } + +} + +/** +* @brief OPAMP MSP De-Initialization +* This function freeze the hardware resources used in this example +* @param hopamp-> OPAMP handle pointer +* @retval None +*/ +void HAL_OPAMP_MspDeInit(OPAMP_HandleTypeDef* hopamp) +{ + if(hopamp->Instance==OPAMP1) + { + /* USER CODE BEGIN OPAMP1_MspDeInit 0 */ + + /* USER CODE END OPAMP1_MspDeInit 0 */ + + /**OPAMP1 GPIO Configuration + PA1 ------> OPAMP1_VINP + PA2 ------> OPAMP1_VOUT + PA3 ------> OPAMP1_VINM + */ + HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3); + + /* USER CODE BEGIN OPAMP1_MspDeInit 1 */ + + /* USER CODE END OPAMP1_MspDeInit 1 */ + } + else if(hopamp->Instance==OPAMP2) + { + /* USER CODE BEGIN OPAMP2_MspDeInit 0 */ + + /* USER CODE END OPAMP2_MspDeInit 0 */ + + /**OPAMP2 GPIO Configuration + PA5 ------> OPAMP2_VINM + PA6 ------> OPAMP2_VOUT + PA7 ------> OPAMP2_VINP + */ + HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7); + + /* USER CODE BEGIN OPAMP2_MspDeInit 1 */ + + /* USER CODE END OPAMP2_MspDeInit 1 */ + } + else if(hopamp->Instance==OPAMP3) + { + /* USER CODE BEGIN OPAMP3_MspDeInit 0 */ + + /* USER CODE END OPAMP3_MspDeInit 0 */ + + /**OPAMP3 GPIO Configuration + PB0 ------> OPAMP3_VINP + PB1 ------> OPAMP3_VOUT + PB2 ------> OPAMP3_VINM + */ + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2); + + /* USER CODE BEGIN OPAMP3_MspDeInit 1 */ + + /* USER CODE END OPAMP3_MspDeInit 1 */ + } + +} + +#endif \ No newline at end of file diff --git a/src/current_sense/hardware_specific/stm32g4_hal.h b/src/current_sense/hardware_specific/stm32g4_hal.h new file mode 100644 index 00000000..13dd1de3 --- /dev/null +++ b/src/current_sense/hardware_specific/stm32g4_hal.h @@ -0,0 +1,14 @@ +#ifndef stm32g4_hal +#define stm32g4_hal + +#if defined(STM32G4xx) +void MX_GPIO_Init(void); +void MX_DMA_Init(void); +void MX_ADC1_Init(ADC_HandleTypeDef* hadc1); +void MX_ADC2_Init(ADC_HandleTypeDef* hadc2); +void MX_OPAMP1_Init(OPAMP_HandleTypeDef* hopamp); +void MX_OPAMP2_Init(OPAMP_HandleTypeDef* hopamp); +void MX_OPAMP3_Init(OPAMP_HandleTypeDef* hopamp); +#endif + +#endif \ No newline at end of file diff --git a/src/current_sense/hardware_specific/stm32g4_mcu.cpp b/src/current_sense/hardware_specific/stm32g4_mcu.cpp new file mode 100644 index 00000000..f05f3514 --- /dev/null +++ b/src/current_sense/hardware_specific/stm32g4_mcu.cpp @@ -0,0 +1,122 @@ +#include "../hardware_api.h" +#include "stm32g4_hal.h" + +#if defined(STM32G4xx) +#define _ADC_VOLTAGE 3.3 +#define _ADC_RESOLUTION 4096.0 +#define ADC_BUF_LEN_1 2 +#define ADC_BUF_LEN_2 1 + +static ADC_HandleTypeDef hadc1; +static ADC_HandleTypeDef hadc2; +static OPAMP_HandleTypeDef hopamp1; +static OPAMP_HandleTypeDef hopamp2; +static OPAMP_HandleTypeDef hopamp3; + +static DMA_HandleTypeDef hdma_adc1; +static DMA_HandleTypeDef hdma_adc2; + +uint16_t adcBuffer1[ADC_BUF_LEN_1] = {0}; // Buffer for store the results of the ADC conversion +uint16_t adcBuffer2[ADC_BUF_LEN_2] = {0}; // Buffer for store the results of the ADC conversion + +#define _ADC_CONV ( (_ADC_VOLTAGE) / (_ADC_RESOLUTION) ) + +// function reading an ADC value and returning the read voltage +// As DMA is being used just return the DMA result +float _readADCVoltageInline(const int pin){ + uint32_t raw_adc = 0; + if(pin == PA2) // = ADC1_IN3 = phase U (OP1_OUT) on B-G431B-ESC1 + raw_adc = adcBuffer1[1]; + else if(pin == PA6) // = ADC2_IN3 = phase V (OP2_OUT) on B-G431B-ESC1 + raw_adc = adcBuffer2[0]; + else if(pin == PB1) // = ADC1_IN12 = phase W (OP3_OUT) on B-G431B-ESC1 + raw_adc = adcBuffer1[0]; + + return raw_adc * _ADC_CONV; +} + +void _configureOPAMP(OPAMP_HandleTypeDef *hopamp, OPAMP_TypeDef *OPAMPx_Def){ + // could this be replaced with LL_OPAMP calls?? + hopamp->Instance = OPAMPx_Def; + hopamp->Init.PowerMode = OPAMP_POWERMODE_HIGHSPEED; + hopamp->Init.Mode = OPAMP_PGA_MODE; + hopamp->Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0; + hopamp->Init.InternalOutput = DISABLE; + hopamp->Init.TimerControlledMuxmode = OPAMP_TIMERCONTROLLEDMUXMODE_DISABLE; + hopamp->Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0_BIAS; + hopamp->Init.PgaGain = OPAMP_PGA_GAIN_16_OR_MINUS_15; + hopamp->Init.UserTrimming = OPAMP_TRIMMING_FACTORY; + if (HAL_OPAMP_Init(hopamp) != HAL_OK) + { + Error_Handler(); + } +} +void _configureOPAMPs(OPAMP_HandleTypeDef *OPAMPA, OPAMP_HandleTypeDef *OPAMPB, OPAMP_HandleTypeDef *OPAMPC){ + // Configure the opamps + _configureOPAMP(OPAMPA, OPAMP1); + _configureOPAMP(OPAMPB, OPAMP2); + _configureOPAMP(OPAMPC, OPAMP3); +} + +void MX_DMA1_Init(ADC_HandleTypeDef *hadc, DMA_HandleTypeDef *hdma_adc, DMA_Channel_TypeDef* channel, uint32_t request) { + hdma_adc->Instance = channel; + hdma_adc->Init.Request = request; + hdma_adc->Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_adc->Init.PeriphInc = DMA_PINC_DISABLE; + hdma_adc->Init.MemInc = DMA_MINC_ENABLE; + hdma_adc->Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + hdma_adc->Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + hdma_adc->Init.Mode = DMA_CIRCULAR; + hdma_adc->Init.Priority = DMA_PRIORITY_LOW; + HAL_DMA_DeInit(hdma_adc); + if (HAL_DMA_Init(hdma_adc) != HAL_OK) + { + Error_Handler(); + } + __HAL_LINKDMA(hadc, DMA_Handle, *hdma_adc); +} + +void _configureADCInline(const int pinA,const int pinB,const int pinC){ + HAL_Init(); + MX_GPIO_Init(); + MX_DMA_Init(); + _configureOPAMPs(&hopamp1, &hopamp3, &hopamp2); + MX_ADC1_Init(&hadc1); + MX_ADC2_Init(&hadc2); + + MX_DMA1_Init(&hadc1, &hdma_adc1, DMA1_Channel1, DMA_REQUEST_ADC1); + MX_DMA1_Init(&hadc2, &hdma_adc2, DMA1_Channel2, DMA_REQUEST_ADC2); + + if (HAL_ADC_Start_DMA(&hadc1, (uint32_t*)adcBuffer1, ADC_BUF_LEN_1) != HAL_OK) + { + Error_Handler(); + } + if (HAL_ADC_Start_DMA(&hadc2, (uint32_t*)adcBuffer2, ADC_BUF_LEN_2) != HAL_OK) + { + Error_Handler(); + } + + HAL_OPAMP_Start(&hopamp1); + HAL_OPAMP_Start(&hopamp2); + HAL_OPAMP_Start(&hopamp3); + + // Check if the ADC DMA is collecting any data. + // If this fails, it likely means timer1 has not started. Verify that your application starts + // the motor pwm (usually BLDCDriver6PWM::init()) before initializing the ADC engine. + _delay(5); + if (adcBuffer1[0] == 0 || adcBuffer1[1] == 0 || adcBuffer2[0] == 0) { + Error_Handler(); + } +} + +extern "C" { +void DMA1_Channel1_IRQHandler(void) { + HAL_DMA_IRQHandler(&hdma_adc1); +} + +void DMA1_Channel2_IRQHandler(void) { + HAL_DMA_IRQHandler(&hdma_adc2); +} +} + +#endif \ No newline at end of file diff --git a/src/drivers/hardware_specific/stm32_mcu.cpp b/src/drivers/hardware_specific/stm32_mcu.cpp index 5efddf41..540dd6c2 100644 --- a/src/drivers/hardware_specific/stm32_mcu.cpp +++ b/src/drivers/hardware_specific/stm32_mcu.cpp @@ -141,6 +141,7 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in if (HardwareTimer_Handle[index] == NULL) { HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM)); HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; + HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1; HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle)); ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT); } @@ -159,8 +160,16 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear! LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N); + // Set Trigger out for DMA transfer + LL_TIM_SetTriggerOutput(HT->getHandle()->Instance, LL_TIM_TRGO_UPDATE); + HT->pause(); HT->refresh(); + + // adjust the initial timer state such that the trigger for DMA transfer aligns with the pwm peaks instead of throughs. + HT->getHandle()->Instance->CR1 |= TIM_CR1_DIR; + HT->getHandle()->Instance->CNT = TIM1->ARR; + HT->resume(); return HT; #else