Candas1 / Split_Hoverboard_SimpleFOC

Split Hoverboards with C++ SimpleFOC (not yet)
MIT License
7 stars 5 forks source link

adding LowsideCurrentSense ... #6

Open RoboDurden opened 1 year ago

RoboDurden commented 1 year ago

In continuation of https://github.com/Candas1/Split_Hoverboard_SimpleFOC/issues/5

I have added the needed code to my cloned fork but can not push because Github_Desktop hangs and therefore can not make a pull request. But we might already talk about the best approach to add LowsideCurrentSense:

...
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(BLDC_POLE_PAIRS);
BLDCDriver6PWM driver = BLDCDriver6PWM( BLDC_BH_PIN,BLDC_BL_PIN,  BLDC_GH_PIN,BLDC_GL_PIN,  BLDC_YH_PIN,BLDC_YL_PIN );

// shunt resistor value , gain value,  pins phase A,B,C
LowsideCurrentSense current_sense = LowsideCurrentSense(BLDC_CUR_Rds, BLDC_CUR_Gain, BLDC_CUR_G_PIN, BLDC_CUR_B_PIN, BLDC_CUR_Y_PIN);
setup()
{
...
/*  
  // succeeds but motor.initFOC(2.09,Direction::CCW)  hangs 
  // motor.initFOC() will turn motor forward and backward a bit and then also hangs
  // We probably need a SimpleFOC/src/current_sense/hardware_specific/gd32/gd32_mcu.cpp
  if (current_sense.init())
  {
    motor.linkCurrentSense(&current_sense);
    Blink(3,oLedOrange);
  }
  else
  {
    Blink(5);
    OUTN("current_sense.init() failed.")
    return;   // cancel simpleFOC setup
  }
*/

loop()
{
...
    if (current_sense.initialized)
    {
      PhaseCurrent_s currents = current_sense.getPhaseCurrents();
      float current_magnitude = current_sense.getDCCurrent();
      OUT2T("mA",current_magnitude*1000)  // milli Amps
      OUT2T("B mA",currents.b*1000)  // milli Amps
      OUT2T("C mA",currents.c*1000)  // milli Amps
    }
RoboDurden commented 1 year ago

Hi @Candas1 , maybe you are back from holidays and fully refreshed start doing/porting the current sensing in the next days..

I really think we need some 16 kHz timer to get the loopFOCout of the main loop() ! It is not acceptable that sometimes there is more than a milliseconds delay in the loopFOC calls. All my speed testing is not really accurate when loopFOC does not get called peridoically at some rate as 16 kHz.

And if simpleFOC does not yet offer such a interrupt, why not doing it the Gen2 way and call loopFOC when adc has finished - will be the best time to do it anyway.

Should be no problem to allow an optional callback to our current sensor that gets initialized with motor.loopFOC ..

But feel free to do your "inserted adc" :-)

Candas1 commented 1 year ago

There is still a lot for work to be done on the 6PWM driver before starting to work on current sensing.

RoboDurden commented 1 year ago

You mean that the init code of the 6 pwm drivers need to be improved ? That of course would impact my speed tests :-) Or do you want to complete the gd32_mcu.cpp to support different timers (some different boards) or even add other motors like steppers ? I see these functions in stm32_mcu.cpp that i don't find in your (and @robcazzaro ?) nice gd32_mcu.cpp:

_configure1PWM
_configure2PWM
_configure3PWM
_configure4PWM
_writeDutyCycle2PWM
_writeDutyCycle3PWM
_writeDutyCycle4PWM

_initPinPWM
_initPinPWMHigh
_initPinPWMLow

_stopTimers
_startTimers

void _alignPWMTimers(HardwareTimer *HT1, HardwareTimer *HT2, HardwareTimer *HT3);
void _alignPWMTimers(HardwareTimer *HT1, HardwareTimer *HT2, HardwareTimer *HT3, HardwareTimer *HT4);
_alignTimersNew

_initHardware6PWMPair
_initHardware6PWMInterface

int findBestTimerCombination(int numPins, int index, int pins[], PinMap* pinTimers[]);
int findBestTimerCombination(int numPins, int pins[], PinMap* pinTimers[]);
scoreCombination
_isChannelEnabled
findIndexOfFirstPinMapEntry
findIndexOfLastPinMapEntry

printTimerCombination
getTimerNumber

finding available/optimal timers might be good for supporting multiple bldc motors like with Gen1 boards.

robcazzaro commented 1 year ago

I think that @Candas1 meant that the GD32 implementation of 6PWM is not complete. For example, we don't correctly process the various flags for the signal polarity. It's an item on my todo list. But we won't improve performance by doing so. After all, the 6PWM is simply setting up a timer for the complementary PWM signals of the 3 phases. Once the timer is properly set, there're no further gains to have: a timer is a timer, and PWM is PWM. It's the rest of the code that can be improved.

Gen1 boards do not use the GD32F130, as far as I know, so there's no value in doing the other PWMs. The Gen 2 boards only support 6PWM. I mean, it might be good to have a truly generic GD32 implementation, but before we spend the time, we might as well ensure that the Gen2 boards work properly. Once that works, if there is interest from the community, we could consider adding the remaining PWM types.

STM32 implements all those types because there are widely used STM32 boards (e.g. BluePill, Nucleo, etc) that can be connected to any type of drivers. There are no GD32F130 boards available, and very few GD32F103 ones as well

RoboDurden commented 1 year ago

So i have begun to port the Gen2 adc code and maybe @robcazzaro would like to help me with my low-level code problems. @Candas1 only read this if you intentionally droped the update event handler init code while porting from Gen2 to your nice drivers\hardware_specific\gd32\gd32_mcu.cpp.

I now think that adc sampling is not triggered by a new timer but by the bldc pwm timer0 !

//----------------------------------------------------------------------------
// Timer0_Update_Handler
// Is called when upcouting of timer0 is finished and the UPDATE-flag is set
// AND when downcouting of timer0 is finished and the UPDATE-flag is set
// -> pwm of timer0 running with 16kHz -> interrupt every 31,25us
//----------------------------------------------------------------------------
void TIMER0_BRK_UP_TRG_COM_IRQHandler(void)
{
    LowsideTimerCurrentSense::iCount1++;

    // Start ADC conversion
    adc_software_trigger_enable(ADC_REGULAR_CHANNEL);

    // Clear timer update interrupt flag
    timer_interrupt_flag_clear(TIMER_BLDC, TIMER_INT_UP);
}

Yes i began with a new sub class LowsideTimerCurrentSense and a static member iCount1 to check if this functions get called.

The Gen2 init code for adc compiles nicely and if the TIMER_BLDC triggered TIMER0_BRK_UP_TRG_COM_IRQHandler this handler function then calls

//----------------------------------------------------------------------------
// This function handles DMA_Channel0_IRQHandler interrupt
// Is called, when the ADC scan sequence is finished
// -> ADC is triggered from timer0-update-interrupt -> every 31,25us
//----------------------------------------------------------------------------
void DMA_Channel0_IRQHandler(void)
{
    LowsideTimerCurrentSense::iCount2++;
    // Calculate motor PWMs
    //CalculateBLDC();

    if (dma_interrupt_flag_get(DMA_CH0, DMA_INT_FLAG_FTF))
    {
        dma_interrupt_flag_clear(DMA_CH0, DMA_INT_FLAG_FTF);        
    }
}

I monitor the two iCountX in main.c but they stay at 0.

OUT2T(current_sense.iCount1, current_sense.iCount2 )

Now i do not see crucial changes in the pwm port from Candas to GD32F130C8\Simple FOC\src\drivers\hardware_specific\gd32\gd32_mcu.cpp

Only thing that was missing (droped by Candas) was

    nvic_irq_enable(TIMER0_BRK_UP_TRG_COM_IRQn, 0, 0);
    timer_interrupt_enable(TIMER_BLDC, TIMER_INT_UP);

But TIMER0_BRK_UP_TRG_COM_IRQHandler() does not get called :-/

When i place that function in two different files i get a linker error of mulitple definitions. So my one function does get compiled and linked into the binary.

Now TIMER0_BRK_UP_TRG_COM_IRQHandler might be a Keil specific naming convention defined in Gen2 startup_gd32f1x0.s

                DCD     ADC_CMP_IRQHandler                ; 28:ADC and Comparator 0-1
                DCD     TIMER0_BRK_UP_TRG_COM_IRQHandler  ; 29:TIMER0 Break,Update,Trigger and Commutation
                DCD     TIMER0_Channel_IRQHandler         ; 30:TIMER0 Channel
                DCD     TIMER1_IRQHandler                 ; 31:TIMER1

and PlatformIO might have a different handler definition ? The Gen2 and Gen2.1 github repos also do not have a platformio.ini file..

I found a code example TIMER0_6-steps that also utilizes such a handler function: https://github.com/EFeru/hoverboard-sideboard-hack-GD/blob/main/docs/GD32F1x0_Firmware_Library_v3.1.0/Examples/TIMER/TIMER0_6-steps/main.c#L78C9-L78C9 . EFeru/hoverboard-sideboard-hack-GD has a platformio.ini but i am not sure if these exmaples were made for PlatformIO.

// configure the nested vectored interrupt controller void nvic_config(void) { nvic_priority_group_set(NVIC_PRIGROUP_PRE1_SUB3); nvic_irq_enable(TIMER0_BRK_UP_TRG_COM_IRQn, 0, 1); }

The handler function is found in https://github.com/EFeru/hoverboard-sideboard-hack-GD/blob/main/docs/GD32F1x0_Firmware_Library_v3.1.0/Examples/TIMER/TIMER0_6-steps/gd32f1x0_it.c#L125

// this function handles TIMER0 interrupt request
void TIMER0_BRK_UP_TRG_COM_IRQHandler(void)
{
    timer_interrupt_flag_clear(TIMER0, TIMER_INT_FLAG_CMT);

This is a Timer2 handler function example from the GD-Arduino community that i will try to compile: https://github.com/CommunityGD32Cores/gd32-pio-projects/blob/main/gd32-spl-timer/src/main.c#L82

void TIMER2_IRQHandler(void)
{
    // clear interrupt request to enable next run
    if (timer_interrupt_flag_get(TIMER2, TIMER_INT_FLAG_UP) != RESET) {
        timer_interrupt_flag_clear(TIMER2, TIMER_INT_FLAG_UP);
        /* our own reaction to timer update interrupt triggering: invert GPIO pin, blinky blink */
        gpio_bit_write(LEDPORT, LEDPIN, state);
        state ^= 1; // invert for next run
    }
}

and

    nvic_irq_enable(TIMER2_IRQn, 2, 2); // hardcode enable Timer2 interrupt in NVIC
...
    timer_interrupt_flag_clear(TIMER2, TIMER_INT_FLAG_UP);
    timer_interrupt_enable(TIMER2, TIMER_INT_UP);

But these changes do also not work for me.

Only changes between the Candas port and Gen2.x seems to be

  timerBldc_break_parameter_struct.breakstate         = TIMER_BREAK_DISABLE;       // same as Gen2.x but Gen2.2 HarleyBob used TIMER_BREAK_DISABLE instead of TIMER_BREAK_ENABLE
  timerBldc_break_parameter_struct.outputautostate  = TIMER_OUTAUTO_DISABLE;  // Gen2.x = TIMER_OUTAUTO_ENABLE

But i tried all 4 combinations and no interrupt handler gets called. Is there a manual out there that really explains these lots of config parameters ?

Candas added close to the end what is not in the Gen2.x code but in that TIMER0_6-steps example:

  /* TIMER0 primary output function enable */
  timer_primary_output_config(TIMER_BLDC, ENABLE);

This is the init code from Candas that i am working on at the moment:

void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
  if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 16khz
  else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
  // center-aligned frequency is uses two periods
  pwm_frequency *=2;

  // timeout timer parameter structs
  timer_parameter_struct timeoutTimer_paramter_struct;

  // PWM timer Parameter structs
  timer_parameter_struct timerBldc_parameter_struct;    
  timer_break_parameter_struct timerBldc_break_parameter_struct;
  timer_oc_parameter_struct timerBldc_oc_parameter_struct;

  // Init PWM output Pins (Configure as alternate functions, push-pull, no pullup)
  gpio_mode_set(TIMER_BLDC_GH_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_GH_PIN);
  gpio_mode_set(TIMER_BLDC_BH_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_BH_PIN);
  gpio_mode_set(TIMER_BLDC_YH_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_YH_PIN);
  gpio_mode_set(TIMER_BLDC_GL_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_GL_PIN);
  gpio_mode_set(TIMER_BLDC_BL_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_BL_PIN);
  gpio_mode_set(TIMER_BLDC_YL_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_YL_PIN);

  gpio_output_options_set(TIMER_BLDC_GH_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, TIMER_BLDC_GH_PIN);
  gpio_output_options_set(TIMER_BLDC_BH_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, TIMER_BLDC_BH_PIN);
  gpio_output_options_set(TIMER_BLDC_YH_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, TIMER_BLDC_YH_PIN);
  gpio_output_options_set(TIMER_BLDC_GL_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, TIMER_BLDC_GL_PIN);
  gpio_output_options_set(TIMER_BLDC_BL_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, TIMER_BLDC_BL_PIN);
  gpio_output_options_set(TIMER_BLDC_YL_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, TIMER_BLDC_YL_PIN);

  gpio_af_set(TIMER_BLDC_GH_PORT, GPIO_AF_2, TIMER_BLDC_GH_PIN);
  gpio_af_set(TIMER_BLDC_BH_PORT, GPIO_AF_2, TIMER_BLDC_BH_PIN);
  gpio_af_set(TIMER_BLDC_YH_PORT, GPIO_AF_2, TIMER_BLDC_YH_PIN);
  gpio_af_set(TIMER_BLDC_GL_PORT, GPIO_AF_2, TIMER_BLDC_GL_PIN);
  gpio_af_set(TIMER_BLDC_BL_PORT, GPIO_AF_2, TIMER_BLDC_BL_PIN);
  gpio_af_set(TIMER_BLDC_YL_PORT, GPIO_AF_2, TIMER_BLDC_YL_PIN);

  // dead time is set in nanoseconds
  uint32_t dead_time_ns = (float)(1e9f/pwm_frequency)*dead_zone;

  // #todo this needs to be converted
  // uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns);

  // Enable timer clock
  rcu_periph_clock_enable(RCU_TIMER_BLDC);  // same as Gen2.x

  // Initial deinitialize of the timer
  timer_deinit(TIMER_BLDC); // same as Gen2.x
  //dbg_periph_enable(DBG_TIMER0_HOLD); // Hold counter of timer 0 during debug

  // Set up the basic parameter struct for the timer
  timer_struct_para_init(&timerBldc_parameter_struct);
  timerBldc_parameter_struct.counterdirection  = TIMER_COUNTER_UP;    // same as Gen2.x
  timerBldc_parameter_struct.prescaler           = 0;                   // same as Gen2.x
  timerBldc_parameter_struct.alignedmode         = TIMER_COUNTER_CENTER_DOWN;         // same as Gen2.x
  timerBldc_parameter_struct.period                = SystemCoreClock / pwm_frequency;   // Gen2.x = 72000000 / 2 / PWM_FREQ
  timerBldc_parameter_struct.clockdivision     = TIMER_CKDIV_DIV1;    // same as Gen2.x
  timerBldc_parameter_struct.repetitioncounter = 0;                   // same as Gen2.x

  // Initialize timer with basic parameter struct
  timer_init(TIMER_BLDC, &timerBldc_parameter_struct);
  timer_auto_reload_shadow_enable(TIMER_BLDC);
  //timer_auto_reload_shadow_disable(TIMER_BLDC);   // Gen2.x

  // Set up the output channel parameter struct
  timer_channel_output_struct_para_init(&timerBldc_oc_parameter_struct);
  timerBldc_oc_parameter_struct.outputstate   = TIMER_CCX_DISABLE;      // Gen2.x = TIMER_CCX_ENABLE = no change at runtime
  timerBldc_oc_parameter_struct.outputnstate  = TIMER_CCXN_DISABLE;     // Gen2.x = TIMER_CCXN_ENABLE = no change at runtime
  timerBldc_oc_parameter_struct.ocpolarity    = TIMER_OC_POLARITY_HIGH;   // same as Gen2.x
  timerBldc_oc_parameter_struct.ocnpolarity     = TIMER_OCN_POLARITY_LOW;   // same as Gen2.x
  timerBldc_oc_parameter_struct.ocidlestate     = TIMER_OC_IDLE_STATE_LOW;  // same as Gen2.x
  timerBldc_oc_parameter_struct.ocnidlestate    = TIMER_OCN_IDLE_STATE_HIGH;  // same as Gen2.x

  // Configure all three output channels with the output channel parameter struct
  timer_channel_output_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, &timerBldc_oc_parameter_struct);
  timer_channel_output_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_B, &timerBldc_oc_parameter_struct);
  timer_channel_output_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_Y, &timerBldc_oc_parameter_struct);

  // Set output channel PWM type to PWM0
  timer_channel_output_mode_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, TIMER_OC_MODE_PWM0); // Gen2.x = TIMER_OC_MODE_PWM1
  timer_channel_output_mode_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_B, TIMER_OC_MODE_PWM0);
  timer_channel_output_mode_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_Y, TIMER_OC_MODE_PWM0);

  // Deactivate output channel fastmode
  timer_channel_output_fast_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, TIMER_OC_FAST_DISABLE);  // same as Gen2.x
  timer_channel_output_fast_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_B, TIMER_OC_FAST_DISABLE);
  timer_channel_output_fast_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_Y, TIMER_OC_FAST_DISABLE);

  // Deactivate output channel shadow function
  timer_channel_output_shadow_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, TIMER_OC_SHADOW_ENABLE); // Gen2.x = TIMER_OC_SHADOW_DISABLE
  timer_channel_output_shadow_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_B, TIMER_OC_SHADOW_ENABLE);
  timer_channel_output_shadow_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_Y, TIMER_OC_SHADOW_ENABLE);

  // Initialize pulse length with value 0 (pulse duty factor = zero)
  timer_channel_output_pulse_value_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, 0);   // same as Gen2.x
  timer_channel_output_pulse_value_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_B, 0);
  timer_channel_output_pulse_value_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_Y, 0);

  // Set up the break parameter struct
  timer_break_struct_para_init(&timerBldc_break_parameter_struct);
  timerBldc_break_parameter_struct.runoffstate      = TIMER_ROS_STATE_ENABLE;     // same as Gen2.x
  timerBldc_break_parameter_struct.ideloffstate     = TIMER_IOS_STATE_DISABLE;    // same as Gen2.x
  timerBldc_break_parameter_struct.protectmode      = TIMER_CCHP_PROT_OFF;       // same as Gen2.x
  timerBldc_break_parameter_struct.deadtime           = DEAD_TIME; // 0~255        // same as Gen2.x
  timerBldc_break_parameter_struct.breakstate         = TIMER_BREAK_DISABLE;       // same as Gen2.x but Gen2.2 HarleyBob used TIMER_BREAK_DISABLE instead of TIMER_BREAK_ENABLE
  timerBldc_break_parameter_struct.breakpolarity      = TIMER_BREAK_POLARITY_LOW; // same as Gen2.x
  timerBldc_break_parameter_struct.outputautostate  = TIMER_OUTAUTO_DISABLE;  // Gen2.x = TIMER_OUTAUTO_ENABLE

  // Configure the timer with the break parameter struct
  timer_break_config(TIMER_BLDC, &timerBldc_break_parameter_struct);

  /* TIMER0 primary output function enable */
  timer_primary_output_config(TIMER_BLDC, ENABLE);

  //----------------  robo added to trigger interrupt handler in LowsideTimerCurrentSense.cpp ..
  // Enable TIMER_INT_UP interrupt and set priority
  //nvic_irq_enable(TIMER0_BRK_UP_TRG_COM_IRQn, 0, 0);  // Gen2.x
  nvic_irq_enable(TIMER0_Channel_IRQn, 0, 0); // https://github.com/CommunityGD32Cores/gd32-pio-projects/blob/main/gd32-spl-timer/src/main.c#L47
  timer_interrupt_flag_clear(TIMER_BLDC, TIMER_INT_FLAG_UP);  // also from gd32-spl-timer/src/main.c#L64
  timer_interrupt_enable(TIMER_BLDC, TIMER_INT_UP);
  // TIMER0 break interrupt disable from https://github.com/EFeru/hoverboard-sideboard-hack-GD/blob/main/docs/GD32F1x0_Firmware_Library_v3.1.0/Examples/TIMER/TIMER0_6-steps/main.c#L156
  timer_interrupt_disable(TIMER_BLDC, TIMER_INT_BRK);

  // Enable the timer and start PWM
  timer_enable(TIMER_BLDC);

  GD32DriverParams* params = new GD32DriverParams {
    .timers = { TIMER_BLDC, TIMER_BLDC, TIMER_BLDC, TIMER_BLDC, TIMER_BLDC, TIMER_BLDC },
    .channels = { TIMER_BLDC_CHANNEL_G, TIMER_BLDC_CHANNEL_G, TIMER_BLDC_CHANNEL_B, TIMER_BLDC_CHANNEL_B, TIMER_BLDC_CHANNEL_Y, TIMER_BLDC_CHANNEL_Y },
    .pwm_frequency  = pwm_frequency,
    .range          = SystemCoreClock/pwm_frequency,
    .dead_zone      = dead_zone,
    .interface_type = _HARDWARE_6PWM
  };

And my latest handler function:

void TIMER0_IRQHandler(void)
{
    LowsideTimerCurrentSense::iCount1++;
    //iCounter3++;

    // clear interrupt request to enable next run
    if (timer_interrupt_flag_get(TIMER0, TIMER_INT_FLAG_UP) != RESET) 
    {
        timer_interrupt_flag_clear(TIMER0, TIMER_INT_FLAG_UP);
    }
}

Ideas welcome :-)

robcazzaro commented 1 year ago

@RoboDurden yes, happy to help. Please let me know exactly what you'd like me to look into.

But, please, keep in mind that the right way to handle low side current sampling is by using the inserted ADC functionality (injected for STM32), not using a very slow software interrupt timer. That's what the STM32 driver does. We are working with a 48MHz processor, and should avoid doing in software what can be done in hardware

RoboDurden commented 1 year ago

The Timer2 example from the GD32-Arduino community works. And i guess it is better anyway to keep driver code seperated from current_sensor code.

#include <Arduino.h>

#define PIN_LED PB3

uint32_t getTimerClkFrequency(uint32_t instance)
{
    rcu_clock_freq_enum timerclkSrc = 0;
    uint32_t APBx_PSC = 0;
    uint32_t clk_src = 0;
    if (instance != (uint32_t) 0) {
        switch ((uint32_t)instance) {
            case (uint32_t)TIMER0:
            case (uint32_t)TIMER1:
            case (uint32_t)TIMER2:
            case (uint32_t)TIMER5:
            case (uint32_t)TIMER13:
                timerclkSrc = CK_APB1;
                APBx_PSC = (RCU_CFG0 & RCU_CFG0_APB1PSC) >> 8;
                break;
            default:
                break;
        }
    }
    if (0 != (APBx_PSC & 0x04)) {
        clk_src = 2 * rcu_clock_freq_get(timerclkSrc);
    } else {
        clk_src =  rcu_clock_freq_get(timerclkSrc);
    }
    return clk_src;
}

void config_timer(uint32_t timer_periph) {
    nvic_irq_enable(TIMER2_IRQn, 2, 2); // hardcode enable Timer2 interrupt in NVIC
    /* enable clock input for Timer2 peirpheral */
    rcu_periph_clock_enable(RCU_TIMER2);
    /* configure TIMER base function */
    timer_parameter_struct timer_initpara;
    uint16_t every_x_milliseconds = 200;
    timer_initpara.prescaler = getTimerClkFrequency(timer_periph) / 10000 - 1;
    timer_initpara.period = every_x_milliseconds * 10 - 1;
    timer_initpara.repetitioncounter = 0;
    timer_initpara.clockdivision = TIMER_CKDIV_DIV1;
    timer_initpara.counterdirection = TIMER_COUNTER_UP;
    timer_initpara.alignedmode = TIMER_COUNTER_EDGE;
    timer_autoreload_value_config(timer_periph, 0);
    timer_init(timer_periph, &timer_initpara);
    /* enable timer update interrupt */ 
    /* happens when timer is overflowing (period / reload value exceeded) and it is set back to 0 again */
    timer_interrupt_flag_clear(timer_periph, TIMER_INT_FLAG_UP);
    timer_interrupt_enable(timer_periph, TIMER_INT_UP);
    timer_enable(timer_periph);
}

int main(void)
{
    pinMode(PIN_LED, OUTPUT);
    config_timer((uint32_t)TIMER2);
    while (1)
    {
        __WFI(); // wait for interrupt. not needed but debugging is easier :)
    }
}

uint8_t state = 0;
void TIMER2_IRQHandler(void)
{
    // clear interrupt request to enable next run
    if (timer_interrupt_flag_get(TIMER2, TIMER_INT_FLAG_UP) != RESET) {
        timer_interrupt_flag_clear(TIMER2, TIMER_INT_FLAG_UP);
        /* our own reaction to timer update interrupt triggering: invert GPIO pin, blinky blink */
        digitalWrite(PIN_LED, state);
        state ^= 1; // invert for next run
    }
}

void NMI_Handler(void) {}
void HardFault_Handler(void){   while (1);  }
void MemManage_Handler(void){   while (1);  }
void BusFault_Handler(void){   while (1);  }
void UsageFault_Handler(void){   while (1);  }
void SVC_Handler(void){}
void DebugMon_Handler(void){}
void PendSV_Handler(void){}
//void SysTick_Handler(void){}

not using a very slow software interrupt timer.

Don't understand why you two keep on repeating this. The "Gen2 style" is to only trigger the adc from a timer interrupt. And if

// -> pwm of timer0 running with 16kHz -> interrupt every 31,25us
//----------------------------------------------------------------------------
void TIMER0_BRK_UP_TRG_COM_IRQHandler(void)

is correct then

// This function handles DMA_Channel0_IRQHandler interrupt
// Is called, when the ADC scan sequence is finished
// -> ADC is triggered from timer0-update-interrupt -> every 31,25us
//----------------------------------------------------------------------------
void DMA_Channel0_IRQHandler(void)

should also succeed with 2 adc (battery voltage and overall current) at a 16 kHz rate.

And when adc is complete it is also the best time to call motor.loopFOC(); :-)

Calling this function from the main loop only achieved about 5kHz with exceptions of below 1 kHz :-( So i do not need the 16 kHz of the pwm timer0 (if that 16 kHz is correct). With a seperate Timer2 i can trigger the adc at lets say 8 kHz and increased the adc from 2 to 4 (low_side current) :-)

Will continue tomorrow.

RoboDurden commented 1 year ago

Could no longer flash my board so i had to solder a little wire from the NRST mcu pin to the RST header pin. inside one of my ST-Link dongles: https://modwiggler.com/forum/viewtopic.php?p=1999431#p1999431 The RST pin of these cheap clones only connects to the SWIM flash pins used for the STM8 MCUs. I also did unsolder a little smd resistor on the backside to use the RST output pin exclusively for the SWD protocol.

When i copy the working TIMER2 code (see previous post) into my Split_Hoverboard_SimpleFOC project, it does no longer work. When i completely replace the main.cpp and the platformio.ini::[env] i get a compiler error

Compiling .pio\build\xxGD32F130C8\src\main.cpp.o
src\main.cpp: In function 'uint32_t getTimerClkFrequency(uint32_t)':
src\main.cpp:7:39: error: invalid conversion from 'int' to 'rcu_clock_freq_enum' [-fpermissive]
    7 |     rcu_clock_freq_enum timerclkSrc = 0;

Is there some other ini file in our Split_Hoverboard_SimpleFOC project that sets some compiler directives ?

[env:xxGD32F130C8]
debug_tool = stlink
upload_protocol = stlink
framework = arduino
platform = https://github.com/CommunityGD32Cores/platform-gd32.git
platform_packages = framework-arduinogd32@https://github.com/CommunityGD32Cores/ArduinoCore-GD32.git
board = genericGD32F130C8
build_flags = -D __PIO_DONT_SET_CLOCK_SOURCE__
    -D __SYSTEM_CLOCK_48M_PLL_IRC8M_DIV2=48000000
    -D $PIOENV  
lib_deps = 
lib_archive = false
monitor_port = socket://localhost:9090
monitor_filters = send_on_enter
monitor_eol = LF
monitor_echo = yes

Ideas welcome.

RoboDurden commented 1 year ago

Okay :-( The working GD32-Arduino Timer2 example https://github.com/CommunityGD32Cores/gd32-pio-projects/tree/main/gd32-spl-timer has a main.c and not a main.cpp. Therefore it gets compile a C-code. And i can not add simpleFOC to a main.c project because that is a nice c++ library.

But the Timer example no longer works when compiled as c++ (rename to main.cpp):

void config_timer(uint32_t timer_periph) {
    nvic_irq_enable(TIMER2_IRQn, 2, 2); // hardcode enable Timer2 interrupt in NVIC
    // enable clock input for Timer2 peirpheral
    //rcu_periph_clock_enable(RCU_AF);
    rcu_periph_clock_enable(RCU_TIMER2);
    // configure TIMER base function
    timer_parameter_struct timer_initpara;
    uint16_t every_x_milliseconds = 200;
    timer_initpara.prescaler = getTimerClkFrequency(timer_periph) / 10000 - 1;
    timer_initpara.period = every_x_milliseconds * 10 - 1;
    timer_initpara.repetitioncounter = 0;
    timer_initpara.clockdivision = TIMER_CKDIV_DIV1;
    timer_initpara.counterdirection = TIMER_COUNTER_UP;
    timer_initpara.alignedmode = TIMER_COUNTER_EDGE;
    timer_autoreload_value_config(timer_periph, 0);
    timer_init(timer_periph, &timer_initpara);
    // enable timer update interrupt
    // happens when timer is overflowing (period / reload value exceeded) and it is set back to 0 again
    timer_interrupt_flag_clear(timer_periph, TIMER_INT_FLAG_UP);
    timer_interrupt_enable(timer_periph, TIMER_INT_UP);
    timer_enable(timer_periph);
}
...
uint8_t state = 0;
void TIMER2_IRQHandler(void)
{
    // clear interrupt request to enable next run
    if (timer_interrupt_flag_get(TIMER2, TIMER_INT_FLAG_UP) != RESET) {
        timer_interrupt_flag_clear(TIMER2, TIMER_INT_FLAG_UP);
        // our own reaction to timer update interrupt triggering: invert GPIO pin, blinky blink
        digitalWrite(PIN_LED, state);
        state ^= 1; // invert for next run
    }
}

Then the main.cpp code compiles but the led is not blinking. And F5 debug confirms that the interrupt handler never gets called.

@robcazzaro , you might have an idea how to port this c-code example to c++ :-)

My platformio.ini for both, the main.c and main.cpp project:

[env:GD32F130C8]
debug_tool = stlink
upload_protocol = stlink
framework = arduino
platform = https://github.com/CommunityGD32Cores/platform-gd32.git
platform_packages = framework-arduinogd32@https://github.com/CommunityGD32Cores/ArduinoCore-GD32.git
board = genericGD32F130C8
build_flags = -D __PIO_DONT_SET_CLOCK_SOURCE__
    -D __SYSTEM_CLOCK_48M_PLL_IRC8M_DIV2=48000000
    -D $PIOENV  
lib_deps = 
lib_archive = false
monitor_port = socket://localhost:9090
monitor_filters = send_on_enter
monitor_eol = LF
monitor_echo = yes
RoboDurden commented 1 year ago

For sure i strongly dislike this low-level c-style code :-( After searching the net for interrupt handlers in c++ and Arduino or PlatformIO i finally learned:

there is already a nice #include <HardwareTimer.h> that is supported by GD32-Arduino

#include <Arduino.h>
#include <HardwareTimer.h>
#include <SimpleFOC.h>

#define LED PB3
#define LED_GREEN PA15

HardwareTimer t(TIMER2);

unsigned long iCount = 0;
#define WINDOW 16000

void timer_cb() 
{
    digitalWrite(LED, digitalRead(LED) ^ 1);
    iCount++;
    digitalWrite(LED_GREEN, (iCount % WINDOW) < (WINDOW/2) );
}

void setup()
{
    pinMode(LED, OUTPUT);
    pinMode(LED_GREEN, OUTPUT);
    t.setPeriodTime(16000, FORMAT_HZ);
    t.attachInterrupt(&timer_cb);
    t.start();
}

void loop() {}

Of course now i fear that simply adding

    // Start ADC conversion
    adc_software_trigger_enable(ADC_REGULAR_CHANNEL);

to that void timer_cb() will not call

//----------------------------------------------------------------------------
// This function handles DMA_Channel0_IRQHandler interrupt
// Is called, when the ADC scan sequence is finished
// -> ADC is triggered from timer0-update-interrupt -> every 31,25us
//----------------------------------------------------------------------------
void DMA_Channel0_IRQHandler(void)
{
    motor.loopFOC();

    if (dma_interrupt_flag_get(DMA_CH0, DMA_INT_FLAG_FTF))
    {
        dma_interrupt_flag_clear(DMA_CH0, DMA_INT_FLAG_FTF);        
    }
}

because that probably is also stupid c-style code :-(

robcazzaro commented 1 year ago

I'm confused, @RoboDurden... Why are you using the DMA IRQ handler, given that there is no DMA interrupt generated in your code?

Gen2 code used an ADC conversion with DMA transfer, so the DMA IRQ was called at the end of the conversion. But if you are using a timer, there's no DMA IRQ...

RoboDurden commented 1 year ago

Yes, i will port that Gen2 code https://github.com/RoboDurden/Hoverboard-Firmware-Hack-Gen2.x/blob/main/HoverBoardGigaDevice/Src/setup.c#L336 And yes, the DMA IRQ will/should be called at the end of the conversion. But in Gen2 the conversion begin is triggered from the TIMER0 that is primarily used for the bldc pwm. As i could not get the Candas-port to simpleFOC make the TIMER0 call an event handler like Gen2 to trigger/begin the conversion https://github.com/RoboDurden/Hoverboard-Firmware-Hack-Gen2.x/blob/main/HoverBoardGigaDevice/Src/it.c#L126

I will now use a seperate TIMER2 with that nice GD32-Arduino. Does not really matter from where the adc conversion is triggered.

But i fear that the DMA IRQ will not get call in c++ just like the TIMER0 handler did not get called.

RoboDurden commented 1 year ago

of course the DMA IRQ handler gets not called:

#include <Arduino.h>
#include <HardwareTimer.h>
#include <SimpleFOC.h>

#define LED_GREEN PA15
#define LED_ORANGE PA12
#define LED_RED PB3

HardwareTimer t(TIMER2);

unsigned long iCount = 0;
#define TIMER2_HZ 8000

void timer_cb() 
{
    digitalWrite(LED_RED, digitalRead(LED_RED) ^ 1);
    iCount++;
    digitalWrite(LED_ORANGE, (iCount % TIMER2_HZ) < (TIMER2_HZ/4) );

    // Start ADC conversion
    adc_software_trigger_enable(ADC_REGULAR_CHANNEL);
}

// This function handles DMA_Channel0_IRQHandler interrupt
// Is called, when the ADC scan sequence is finished
void DMA_Channel0_IRQHandler(void)
{
    //motor.loopFOC();
    digitalWrite(LED_GREEN, (iCount % TIMER2_HZ) < (TIMER2_HZ/2) );

    if (dma_interrupt_flag_get(DMA_CH0, DMA_INT_FLAG_FTF))
        dma_interrupt_flag_clear(DMA_CH0, DMA_INT_FLAG_FTF);        
}

// ADC defines
#define VBATT_PIN   GPIO_PIN_4
#define VBATT_PORT GPIOA
#define VBATT_CHANNEL ADC_CHANNEL_4
#define CURRENT_DC_PIN  GPIO_PIN_6
#define CURRENT_DC_PORT GPIOA
#define CURRENT_DC_CHANNEL ADC_CHANNEL_6

// DMA (ADC) structs
dma_parameter_struct dma_init_struct_adc;
// ADC buffer struct
typedef struct
{
  uint16_t v_batt;
    uint16_t current_dc;
} adc_buf_t;

adc_buf_t adc_buffer;

//----------------------------------------------------------------------------
// Initializes the ADC
//----------------------------------------------------------------------------
void ADC_init(void)
{
    gpio_mode_set(VBATT_PORT, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, VBATT_PIN);
    gpio_mode_set(CURRENT_DC_PORT, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, CURRENT_DC_PIN);

    // Enable ADC and DMA clock
    rcu_periph_clock_enable(RCU_ADC);
    rcu_periph_clock_enable(RCU_DMA);

  // Configure ADC clock (APB2 clock is DIV1 -> 72MHz, ADC clock is DIV6 -> 12MHz)
    rcu_adc_clock_config(RCU_ADCCK_APB2_DIV6);

    // Interrupt channel 0 enable
    nvic_irq_enable(DMA_Channel0_IRQn, 1, 0);

    // Initialize DMA channel 0 for ADC
    dma_deinit(DMA_CH0);
    dma_init_struct_adc.direction = DMA_PERIPHERAL_TO_MEMORY;
    dma_init_struct_adc.memory_addr = (uint32_t)&adc_buffer;
    dma_init_struct_adc.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
    dma_init_struct_adc.memory_width = DMA_MEMORY_WIDTH_16BIT;
    dma_init_struct_adc.number = 2;
    dma_init_struct_adc.periph_addr = (uint32_t)&ADC_RDATA;
    dma_init_struct_adc.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
    dma_init_struct_adc.periph_width = DMA_PERIPHERAL_WIDTH_16BIT;
    dma_init_struct_adc.priority = DMA_PRIORITY_ULTRA_HIGH;
    dma_init(DMA_CH0, &dma_init_struct_adc);

    // Configure DMA mode
    dma_circulation_enable(DMA_CH0);
    dma_memory_to_memory_disable(DMA_CH0);

    // Enable DMA transfer complete interrupt
    dma_interrupt_enable(DMA_CH0, DMA_CHXCTL_FTFIE);

    // At least clear number of remaining data to be transferred by the DMA 
    dma_transfer_number_config(DMA_CH0, 2);

    // Enable DMA channel 0
    dma_channel_enable(DMA_CH0);

    adc_channel_length_config(ADC_REGULAR_CHANNEL, 2);
    adc_regular_channel_config(0, VBATT_CHANNEL, ADC_SAMPLETIME_13POINT5);
    adc_regular_channel_config(1, CURRENT_DC_CHANNEL, ADC_SAMPLETIME_13POINT5);
    adc_data_alignment_config(ADC_DATAALIGN_RIGHT);

    // Set trigger of ADC
    adc_external_trigger_config(ADC_REGULAR_CHANNEL, ENABLE);
    adc_external_trigger_source_config(ADC_REGULAR_CHANNEL, ADC_EXTTRIG_REGULAR_NONE);

    // Disable the temperature sensor, Vrefint and vbat channel
    adc_tempsensor_vrefint_disable();
    adc_vbat_disable();

    // ADC analog watchdog disable
    adc_watchdog_disable();

    // Enable ADC (must be before calibration)
    adc_enable();

    // Calibrate ADC values
    adc_calibration_enable();

    // Enable DMA request
    adc_dma_mode_enable();

    // Set ADC to scan mode
    adc_special_function_config(ADC_SCAN_MODE, ENABLE);
}

void setup()
{
    t.setPeriodTime(TIMER2_HZ, FORMAT_HZ);
    t.attachInterrupt(&timer_cb);
    t.start();
    pinMode(LED_RED, OUTPUT);
    pinMode(LED_GREEN, OUTPUT);
    pinMode(LED_ORANGE, OUTPUT);
}

void loop() {}

ideas welcome :-/

P.S. there is an GD32-Arduino example that one by one triggers adc conversion and then stupidly wait for the conversion to end. Maybe it would be sufficient to trigger all wanted adc conversion and simply check with the TIMER2-callback when all conversions have finished:

https://github.com/CommunityGD32Cores/gd32-pio-projects/blob/main/gd32-spl-adc-polling-gd32f1x0/src/main.c#L162C21-L162C21

robcazzaro commented 1 year ago

@RoboDurden if I understand what you are doing, you are mixing Arduino code and low level SPL code from the old project. That might result in either the ADC or the DMA not being properly initialized, so either the ADC conversion doesn't happen or the DMA IRQ is not properly set to happen.

You will need to single step thru the code to see if the ADC, DMA and IRQ registers are set the right way. Or at least start by manually calling the ADC conversion and see if it works and transfers the data into the DMA structures. My guess is that you will see that the ADC conversion is not happening, hence no DMA IRQ is generated. If the ADC/DMA works when called from your code, check if the timer is firing as expected

RoboDurden commented 1 year ago

Ah thanks @robcazzaro that's nice, i can already monitor the adc_buffer at dma_init_struct_adc.memory_addr to see if the trigger adc_software_trigger_enable(ADC_REGULAR_CHANNEL); in my TIMER2 callback does indeed kickoff the adc conversion. When that succeeds i can start worrying about why the adc-conversion-finished handler does not get called. But maybe the conversion is always finished by the time the TIMER2 callback gets fired again and than i can call motor.loopFOC() from that TIMER2 handler :-) But depending on how fast the adc will be, the values might that way already be up to 200 microseconds old (TIMER2 with 5 kHz) Will adc_buffer always hold the old values until they are replaced with new ones ? With a 32bit mcu i guess the uint16 will be written in one step. But i see in the Gen2 code that the trigger of a new conversion takes place after adc_buffer.adc_buffer.current_dc etc is read from the bldc updater:

void DMA_Channel0_IRQHandler(void)
{
    CalculateBLDC();

    if (dma_interrupt_flag_get(DMA_CH0, DMA_INT_FLAG_FTF))
        dma_interrupt_flag_clear(DMA_CH0, DMA_INT_FLAG_FTF);        
}

But i guess i will see when i monitor adc_buffer.v_batt and the values go crazy :-)

RoboDurden commented 1 year ago

No, the adc_buffer values do not change:

void setup()
{
    #ifdef DEBUG_STLINK
    SimpleFOCDebug::enable(&rtt);
    #endif
    OUTN("Hello gd32-adc :-)")

    t.setPeriodTime(TIMER2_HZ, FORMAT_HZ);
    t.attachInterrupt(&timer_cb);
    t.start();
    pinMode(LED_RED, OUTPUT);
    pinMode(LED_GREEN, OUTPUT);
    pinMode(LED_ORANGE, OUTPUT);

    adc_buffer.v_batt = adc_buffer.current_dc = 42;
}

void loop() 
{
    OUT2T(adc_buffer.v_batt,adc_buffer.current_dc);
    OUTN(iCount);
    delay(10);
}
42: 42  147663
42: 42  147743
42: 42  147823
42: 42  147903
42: 42  147983
42: 42  148063
42: 42  148143
42: 42  148223

I guess i will make a break for a few days. Beginning a new journey with my 10 km/h solar camper on saturday. ich bin blind

But in two days i will make a stop at my train station for a few days and will continue there.

robcazzaro commented 1 year ago

Yes, that's one of the concerns with a slow processor and all the Arduino framework overhead.

Don't forget that Gen2 on the GD32 was overclocked to 72MHz, and we are running at 48MHz. So you need to make sure that the timer initialization code takes that into account.

If the ADC transfers values via DMA to adc_buffer, your code will always find valid values in that variable. Worst case, the battery ADC and current adc will be from different read cycles, but it makes no real difference since those are not related at all. As a matter of fact, the code is wasting a lot of time converting the battery voltage so frequently, I would suggest checking the battery no more than a few times per second, if that.

Given your last message (no valid ADC values), it looks as if the initialization didn't work as expected

robcazzaro commented 1 year ago

Enjoy your trip @RoboDurden 🌞

RoboDurden commented 1 year ago

@robcazzaro , if you thinks my Gen2 style adc approach with loopFOC called by a TIMER callback might be a way to go, i can upload my code to a new github repo. That is something you could also work on with your blue pills :-)

robcazzaro commented 1 year ago

@RoboDurden I can't promise I can do it in the next couple of days, but if you upload your code somewhere I'll have a look as soon as I have time.

RoboDurden commented 1 year ago

Will then do so when i really take the break :-) from the gd32 user manual: ADC conversion time: 0.5μs for 12-bit resolution (2MS/s), Don't think that we have to worry a lot about also doing adc_buffer.v_batt every 100 μs (10 kHz motor.loopFOC() )

I also read

Start of the conversion can be initiated:
- By hardware triggers with configurable polarity (internal timer events from TIMER0,TIMER1, TIMER2 and TIMER14)

So i might be able to "attach" the adc conversion begin to TIMER2 and only use the TIMER2 callback to run motor.loopFOC();

But yes, if the 4 adc conversion will only take a few microseconds, the values will mostly be "quite old" when the 100 μs TIMER2 callback runs loopFOC.

Don't know if this will affect the bldc closed loop much.

robcazzaro commented 1 year ago

The conversion time depends on the ADC settings, and can be much higher. From the manual, section 10.4.8 Example: CK_ADC = 14MHz and sample time is 1.5 cycles, the total conversion time is “1.5+12.5” CK_ADC cycles, that means 1us.. I haven't looked at your settings, but can be more than 1us. Not sure where you found that reference, but it's not in the official documentation https://www.gigadevice.com.cn/Public/Uploads/uploadfile/files/20230314/GD32F130xxDatasheetRev3.7.pdf and https://www.gigadevice.com.cn/Public/Uploads/uploadfile/files/20230209/GD32F1x0_User_Manual_EN_Rev3.6.pdf

If the ADC is actually using DMA, the conversion time is not taking away processor time, but can result in the current ADC being sampled at the wrong time, depending on the code sampling the current or the battery first

RoboDurden commented 1 year ago

Okay, it is ugly but extern "C" {...} does the job.

I have kept all code in one main.cpp and uploaded the repo to https://github.com/RoboDurden/GD32_SimpleFOC/blob/main/src/main.cpp

With the conversion defines of Gen2 i get this output when cutting off the the voltage:

OUT2T(fVoltage ,fCurrent)   OUTN(iCount)
25.06: -0.20  298607
25.06: 0.00  298687
25.06: 0.00  298767
25.06: 0.20  298847
23.01: 0.00  298927
13.41: 0.00  299007
10.83: -0.20  299087
8.36: -0.40  299167
6.41: 0.00  299247

here the uint16 values:

1042: 1354  231253
1041: 1354  231333
1042: 1354  231413
1028: 1354  231493
999: 1353  231573
975: 1354  231653
948: 1354  231733
923: 1353  231813
898: 1353  231893
870: 1354  231973
839: 1354  232053
801: 1353  232133
763: 1353  232213
727: 1353  232293
686: 1353  232373
649: 1354  232453
619: 1353  232533
569: 1353  232613
537: 1353  232693
503: 1354  232773
473: 1353  232853
440: 1353  232933
413: 1353  233013
385: 1353  233093
356: 1354  233173
326: 1353  233253
274: 1353  233333
270: 1370  233413

There is also ADC_init2() code that i found in the net and which might do continious conversion. It is also working. https://gitee.com/yhalin/gd32-e230/blob/master/code/simple_app/main_adjust_Joystick.c

So of course it now would be nice to measure the microseconds for ADC_init() from timer_cb() to DMA_Channel0_IRQHandler(void) and for ADCInit2() the microseconds between each ADC_CMP_IRQHandler(void) calls.

And of course doing it the c++ style without that ugly extern "C"

But i have to force myself now to stop and enjoy the rest of this day with packing all i need into my little camper. But yes, i will take my test setups with me, at least the 50 km to my train station.

So @robcazzaro maybe you want to take a look at my low level code. Doing the real LowsideTimerCurrentSense (derived from LowsideCurrentSense ) should not take much effort.

RoboDurden commented 1 year ago

Added the microseconds evaluation: https://github.com/RoboDurden/GD32_SimpleFOC/blob/main/src/main.cpp#L48 With the Gen2 style ADC_init() the two adc conversions finish 7-8 microseconds after the Timer2 handler triggered a new conversion. As i plan to call motor.loopFOC only every 125 microseconds (= 8 kHz) this is absolutely fine :-)

RoboDurden commented 1 year ago

Already spent whole sunday to port the working "bulk adc" to a new class LowsideCurrentSenseTimer but am having trouble with lots of statics needed to make the non c++ interrupt code work. 8 kHz Timer is running (orange led blinking) and triggering the bulk adc. Again after about 8 ms, the DMA_Channel0_IRQHandler gets called (green led blinking) :-) But all adc values get written by dma as 65535 :-(

So directly porting the working https://github.com/RoboDurden/GD32_SimpleFOC/blob/main/src/main.cpp into a c++ class was a too big step :-/

Will first have to simply copy the RCU_init(); DMA_init(); ADC_init(); into the main.cpp and get valid adc values from there..

With LowsideCurrentSenseTimer we wil be able to have multiple motors and the option to add additional adc pins:


LowsideCurrentSenseTimer current_sense = LowsideCurrentSenseTimer(BLDC_CUR_Rds, BLDC_CUR_Gain, BLDC_CUR_G_PIN, BLDC_CUR_B_PIN, BLDC_CUR_Y_PIN);
LowsideCurrentSenseTimer current_senseLeft = LowsideCurrentSenseTimer(BLDC_CUR_Rds, BLDC_CUR_Gain, BLDC_CUR_L_G_PIN, BLDC_CUR_L_B_PIN, BLDC_CUR_L_Y_PIN);

setup()
{
  current_sense.AddAdc(VBATT_PIN,VBATT_CONVERT);                // add additional adc to bulk conversion
  current_sense.AddAdc(CURRENT_DC_PIN,CURRENT_DC_CONVERT,1000); // add with offest calculation with 1000 first values
  current_sense.AddCurrentSensor(current_senseLeft);          // add pinA, pinB and pinC to the one bulk conversion

if (current_sense.init(TIMER2,8000))    // user TIMER2 with 8 kHz
  {
    motor.linkCurrentSense(&current_sense);
    motorLeft.linkCurrentSense(&current_senseLeft); // motorLeft will only see current_senseLeft which will fetch its adc from master

code is online here https://github.com/RoboDurden/Split_Hoverboard_SimpleFOC/blob/main/src/main.cpp#L46C1-L46C26 https://github.com/RoboDurden/Arduino-FOC/blob/master/src/current_sense/LowsideCurrentSenseTimer.cpp

ideas welcome :-/

Candas1 commented 1 year ago

You have limited time to sample the phase currents, and you have to do it at the right time. This is why it's good practice to use inserted/injected adc. Now with this bulk of adc channels to sample, your low side mosfets will have to stay ON for a longer time, so you will have to reduce the maximum duty cycle. And I am not sure both motors will sample at the right moment.

That's why I said I can tackle the current sensing myself later.

RoboDurden commented 1 year ago

Ah now i understand why you always onsist on 'inserted' = 'synced' ! Adc of the low-side-currents of course need the low-side mosfets be ON for that time. Therefore the adc has to be in sync. If the ON phase of all three low-side mosfets would always start with the begin of a new TIMER0 cycle, then my bulk-method might still work and i would need the Gen2 code to trigger on TIMER0 to work. Does the low-side pwm always begin with the ON-phase ?

like:

|---_______|---_______|---_______| = 30% pwm ratio lo-side A
|-_________|-_________|-_________| = 10% pwm ratio lo-side B
|-----_____|-----_____|-----_____| = 50% pwm ratio lo-side C

However, over the 50% of the low-side C being on, the current might also differ, because the three hi-side mosfets have different ON-times !

So what kind of low-side currents does the foc alghorithm needs anyway ? An average over the complete cycle ? sorry yes, i should finish reading that long FOC intro article :-/

Using TIMER2 will not work my way. Thanks for the clarification @Candas1 !!

Candas1 commented 1 year ago

Yes check that document I shared in the past, I can share the link again if needed. It's related to Eferu's firmware but it's still relevant.

RoboDurden commented 1 year ago

ha ha yes please post the link again. our threads here are so long that i have diffucultis to find something again.

Candas1 commented 1 year ago

Here it is

RoboDurden commented 1 year ago

Thank @Candas1 you for the link (i meant that general introduction into FOC but this link is better suited for our low-level talk). Now i think that "injected adc" is not about syncing the adc to the pwm but "Values must be read from registers instead of DMA.". And if i would trigger the adc by the TIMER0-callback (as is done in Gen2) AND would trigger that callback to the middle of the pwm cycle (timerBldc_parameter_struct.alignedmode = TIMER_COUNTER_CENTER_DOWN; ?), then i would have the same as the EFeru timing: adc sampling If it is not possible to set a custom counter value for TIMER0 to trigger the Timer0-callback, then i could use an additional TIMER2 to delay the adc-begin: Timer0 -> Timer2 -> ADC

Yes, adding VBATT and CURRENT_DC to the "bulk conversion" would unnessearily delay the end of conversion. But that would only be optional anyway.

What i still do not understand is what good it is to measure the currents when all three low-side mosfet are on and all highside-mofset ar off. Is the foc-alghorithmn only interessted in some inductive currents ? But i do not really want to understand the physics of FOC anyway..

So if i succeed with syncing my adc-begin to the middle (plus some offset?) of TIMER0 (and somehow skip the DMA but read the values from some register to further shorten conversion time), then my code would be okay ?

RoboDurden commented 1 year ago

Am still confused. Now i think that what is centered to the middle of the pwm cycle is hi-side=ON and lo-side=OFF. So the beginning/ending of a cycle (that Gen2 callback is fired https://github.com/RoboDurden/Hoverboard-Firmware-Hack-Gen2.x/blob/main/HoverBoardGigaDevice/Src/it.c#L126 is exatcly the time when all hi-side mosfet are off and all lo-side mosfet are ON. Then i only need to drop my additional TIMER2 code and make the Gen2 TIMER0 callback work with extern "C"{}:-)

Candas1 commented 1 year ago

The advantage of injected adc is that you can sample separately from the regular adc channels, it will just put any regular adc sampling on hold and start the injected adc instead. In the gd32 drivers I already initialized the TIMER_CH_3 of TIMER0 for sampling.

What the gen2.0 firmware is doing with the adc is really wrong, that's not a good example. It's starting an interrupt at Timer update event (middle), starting the adc by software in that interrupt instead of trigger it by the event, and then DMA is triggering another interrupt.

RoboDurden commented 1 year ago

Okay but if you would tell me how to change Timer0 update event (middle) to update event (begin/end) then this awkward Timer0_cb->DMA_ADC->AdcFinished_cb should work. I guess we could live a few micro seconds delay.

Timer0 update callback is initialized here (i guess):

    // Enable TIMER_INT_UP interrupt and set priority
    nvic_irq_enable(TIMER0_BRK_UP_TRG_COM_IRQn, 0, 0);
    timer_interrupt_enable(TIMER_BLDC, TIMER_INT_UP);

But i do not see the register that chooses between middle or begin/end :-/

Candas1 commented 1 year ago

we discussed some of it here

If you are not interested in the physics of FOC or dealing with low level, forget about current sensing.

RoboDurden commented 1 year ago

From the user manual:

Center-aligned counting mode In the center-aligned counting mode, the counter counts up from 0 to the counter-reload value and then counts down to 0 alternatively. The Timer module generates an overflow event when the counter counts to the counter-reload value subtract 1 in the up-counting mode and generates an underflow event when the counter counts to 1 in the down-counting mode. The counting direction bit DIR in the TIMER0_CTL0 register is read-only and indicates the counting direction when in the center-aligned mode. The counting direction is updated by hardware automatically

TIMER0 up down

Now It seems to me that the update event is fired in the middle (overflow) AND the begin/end (underflow) So i would only (somehow) need to start adc conversion when DIR bit indicates an underflow event :-)

RoboDurden commented 1 year ago

As a physicist i love abstractation - and strongly dislike all these Linux believers with their mindsets stuck in the 90s of last centrury who think that you first have to understand the complete set of underlying low levels to advance to a higher level :-(

This project here is about making the c++ simpleFOC library run on a GD32. And if that library wants the adc currents when all lo-side mosfets are on (and all hi-side mosfett are off), then i do proudly not want to understand why, because that belongs to a lower level.

0: physics level :-( 1: c-code GD32 level :-/ 2: simpleFOC c++ level :-)

Candas1 commented 1 year ago

This project here is about making the c++ simpleFOC library run on a GD32. And if that library wants the adc currents when all lo-side mosfets are on (and all hi-side mosfett are off), then i do proudly not want to understand why, because that belongs to a lower level. That's still low level. So you get to pick what level is interesting for you and ask when it's too level for you liking.

RoboDurden commented 1 year ago

Exactly Candas :-) When some issue to too low level (like the flag to only fire the updae event on underflow) to my liking i happly say it here and maybe you or @robcazzaro are happy to help because you low-level experts immediately know the answer. When you don't answer, i might still find the happiness to dig deeper myself.

Do not forget that i only began here because you answered "There is still a lot for work to be done on the 6PWM driver before starting to work on current sensing."

Candas1 commented 1 year ago

I never suggested you should work on the current sensing. Anyway, that's why I said feel free to experiment if you want to learn. But if we have to step in all the time, that's not the most efficient use of our time.

Now I am discussing the extrapolation from the dev branch with the simplefoc team because you didn't want to discuss it with them. You could have handled this much better than me.

I repeat myself but here I try to keep track of what I do and the information I collect.

RoboDurden commented 1 year ago

Thanks for the spreadsheet. I did not disuss my extrapolation because it was not fully working. And for that i think it needs the motor.loopFOC taken out of the main loop. And to get this i started with my current_sensor. The smoothedSensor is close to my linear prediction. He uses a low pass to average over the latest velocities (= time between two hall steps), i sum over the latest 10ms:

  fPulseDiff = aiTimeDiff[iPosUpdateState];
  iSum = 1;
  for(int i=1; i<HISTORY_updateState; i++)
  {
    int iDiff = aiTimeDiff[(i+iPosUpdateState)%HISTORY_updateState];
    if (  (fPulseDiff + iDiff) > 10000) // not over 10 ms for predicting the next getMechanicalAngle()
      break;
    fPulseDiff += iDiff; 
    iSum++;
  }
  fPulseDiffPredict = fPulseDiff / iSum;

We both (i think) then take this average velocity and the micro seconds since last halt step to do a linear prediction.

A low-pass is less sensitive to the latest hall steps as the sum over a time interval ? I prefer my method because i can also test higher polynomial grade interpolation.. Of course a low pass is way faster. But i think i need a timer::motor.loopFOC to continue.

P.S. this seems to work to get the pin/port:

        PinName pinname = DIGITAL_TO_PINNAME(pin);
        uint32_t gd_pin =  gpio_pin[GD_PIN_GET(pinname)];
        uint32_t gd_port = gpio_port[GD_PORT_GET(pinname)];
RoboDurden commented 1 year ago

Okay, 4x adc with TIMER2 working: StmStudio 4x adc working thanks @Candas1 for showing me StmStudio ! ai_AdcBuffer[0] and ai_AdcBuffer[1] (StmStudio can not import arrays ?) are the two low-side mosfet currents and i spin the motor by hand :-) ai_AdcBuffer[2] is VBATT and changes nicely when i change the power supply voltage. ai_AdcBuffer[3] is the overall current_dc but not yet calibrated. Conversion time mostly takes about 14 micro seconds but sometimes up to 50 us: StmStudio iMicorsAdcReady

But of course now i need to move back from TIMER2 to the pwm TIMER0. I dream that this extern"C"{} this time will make the Timer0 Update handler work.

P.S. how to also get the channel from Arduino-Pin:

        PinName pinname = DIGITAL_TO_PINNAME(aiPin[i]);
        uint32_t gd_pin =  gpio_pin[GD_PIN_GET(pinname)];
        uint32_t gd_port = gpio_port[GD_PORT_GET(pinname)];
        uint8_t gd_channel = get_adc_channel(pinname);

I simply wrote analogRead(VBATT_PIN) into main.cpp and did hit F12 to find the c-level and the mapping macros/functions.

Candas1 commented 1 year ago

StmStudio can not import arrays ? When selecting the variables, there is an option to expend the arrays.

P.S. how to also get the channel from Arduino-Pin:

      PinName pinname = DIGITAL_TO_PINNAME(aiPin[i]);
      uint32_t gd_pin =  gpio_pin[GD_PIN_GET(pinname)];
      uint32_t gd_port = gpio_port[GD_PORT_GET(pinname)];
      uint8_t gd_channel = get_adc_channel(pinname);

I simply wrote analogRead(VBATT_PIN) into main.cpp and did hit F12 to find the c-level and the mapping macros/functions.

Thanks. But ADC channel is OK, I am missing a function/macro to find the Timer channels for a pin.

RoboDurden commented 1 year ago

my analog buffer is a dynamic array


.h
uint16_t* LowsideCurrentSenseTimer::ai_AdcBuffer;
.cpp
ai_AdcBuffer = new uint16_t[aiPin.size()];

and only the constant pointer shows up in StmStudio

This gets expanded to 8 values: static uint16_t ai_AdcBufferLog[8]; :-/

i found this with timer.c

    // Brushless Control DC (BLDC) defines
    // Channel G
    #define BLDC_GH_PIN PA10
    #define BLDC_GL_PIN PB15
    // Channel B
    #define BLDC_BH_PIN PA9
    #define BLDC_BL_PIN PB14
    // Channel Y
    #define BLDC_YH_PIN PA8
    #define BLDC_YL_PIN PB13

    pwmDevice_t oPwmDevice = getTimerDeviceFromPinname(DIGITAL_TO_PINNAME(BLDC_GH_PIN));    // -> 2 = TIMER_CH_2
    SIMPLEFOC_DEBUG("Timer_CH ", oPwmDevice.channel);
    oPwmDevice = getTimerDeviceFromPinname(DIGITAL_TO_PINNAME(BLDC_GL_PIN));    // -> 1 = TIMER_CH_1
    SIMPLEFOC_DEBUG("Timer_CH ", oPwmDevice.channel);
    oPwmDevice = getTimerDeviceFromPinname(DIGITAL_TO_PINNAME(BLDC_BH_PIN));    // -> 1 = TIMER_CH_1
    SIMPLEFOC_DEBUG("Timer_CH ", oPwmDevice.channel);
    oPwmDevice = getTimerDeviceFromPinname(DIGITAL_TO_PINNAME(BLDC_BL_PIN));    // -> 0 = TIMER_CH_0
    SIMPLEFOC_DEBUG("Timer_CH ", oPwmDevice.channel);
    oPwmDevice = getTimerDeviceFromPinname(DIGITAL_TO_PINNAME(BLDC_YH_PIN));    // -> 0 = TIMER_CH_0
    SIMPLEFOC_DEBUG("Timer_CH ", oPwmDevice.channel);
    oPwmDevice = getTimerDeviceFromPinname(DIGITAL_TO_PINNAME(BLDC_YL_PIN));    // -> 0 = TIMER_CH_0
    SIMPLEFOC_DEBUG("Timer_CH ", oPwmDevice.channel);

But the channels seem to be wrongly shifted by 1 :-/

RoboDurden commented 1 year ago

@Candas1, with analogWrite(BLDC_GH_PIN,100); and F12 i found this in arduino/pwm.cpp

void analogWrite(pin_size_t ulPin, int ulValue)
{
...
  set_pwm_value_with_base_period(ulPin, analogOut_period_us, value);

->

void set_pwm_value_with_base_period(pin_size_t ulPin, uint32_t base_period_us, uint32_t value)
{
...
    PWM pwm(ulPin);

->
PWM::PWM(uint32_t pin)
{
    PinName instance = DIGITAL_TO_PINNAME(pin);
..
    this->pwmDevice   = getTimerDeviceFromPinname(instance);

So the functions seem to be correct and my defines_2.0.h definitions wrong ?

Candas1 commented 1 year ago

I will check that getTimerDeviceFromPinname, but the GD_PIN_CHANNEL_GET macro it uses is also used in get_adc_channel. I might reach out to the arduino-gd32 team for clarification. Thank you.

RoboDurden commented 1 year ago

Yes, but in get_adc_channel with the line before it is

  uint32_t function = pinmap_function(pinname, PinMap_ADC);
  uint32_t channel = GD_PIN_CHANNEL_GET(function);

whereas in getTimerDeviceFromPinname it is

  pinfunction = pinmap_function(instance, PinMap_PWM);
  pwmDevice.channel = GD_PIN_CHANNEL_GET(pinfunction);
Candas1 commented 1 year ago

Thanks, now I understand how it works. I am waiting for possible fixes in arduino-gd32

I started to work on the current sensing last evening.

This was missing in your splitboard code.

RoboDurden commented 1 year ago

Good to hear from you Candas :-)

Yes, the current_sense.linkDriver(&driver); was missing in my splitboard main.cpp. And yes: > Simplefoc is very well documented but this kind of things happens, and can generate unnecessary discussions in the forum. I am the copy+paste guy who never reads documentations ;-) Again the difference to the linux believers.. i have this expectation that code should be intuitive, speaking for itself and NOT need lengthy documentations..

As i have never reached the point where my current_sensor might be ready for testing with simpleFOC, i have never tested my current_sense.XY lines ;-)

I have nearly finished my mppt project and would like to return to this repo here.

Would be nice if you would also update this Split_Hoverboard_SimpleFOC and not only the Arduino-FOC (and the arduino-foc-drivers ) so i can see how you implement the SmoothedSensor.

Greetings from rainy Germany - nature loves rain :-)

Candas1 commented 1 year ago

As I told you I have a dev branch of this repository. It's up to date.