Git Product home page Git Product logo

Comments (160)

Candas1 avatar Candas1 commented on August 28, 2024 2

I get one sinusoidale phase current for one pin, but the other one is not reacting, just noise.
Need to check if it's the right pin, if it's not defective, or if I did something wrong.

Finally I had some time to work on it today.
Actually the problem was my board, with another board I can sample the 2 phase currents.
image

The driverAlign fails for some reason, I need to investigate why.
But if I skip it I can run in FOC current mode.
https://www.youtube.com/shorts/dns41fACYqU

Need to experiment more and check if there is anything to tweak.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024 2

Found another schematic from another repository for our board, it's still missing the phase current sensing but it has more details.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024 2

Some updates.
All works well on the last 2 boards I tried. I will fix the other ones later.
I experimented with the Foc current/torque mode, the way it works is counterintuitive but it was the same with Eferu.
I need to try it with load.

I had bought this a few month ago but it's really overkill.... I thought I could use it as a load.
image

I bought this recently for 8e, should be good enough for now:
image
It's just a metal disc spinning between magnets, I could probably adapt the same principle to a hoverboard wheel directly.

I experimented with pwm deadtime compensation, it makes the phase current waveform much more sinusoidal, and the motor stutter less at slow speed. It's highly experimental.
I really like this new tool, it's not fully stable but better than stm studio already.

I will publish my recent code. I haven't touched the drivers recently.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024 1

Ok the reason why driveralign was failing is because it can only swap 2 phase currents, not identify each phase current.
With the following pinout driveralign doesn't fail anymore.

#define BLDC_CUR_G_PIN PB1	
#define BLDC_CUR_B_PIN PB0
#define BLDC_CUR_Y_PIN _NC  // simpleFOC can handle 2 or 3 current sense pins

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024 1

I just published my code for current sensing.
I added a parameter that lets you run an interrupt with a basic filtering of the phase current as I was experimenting.

This and this might need some tweaking to behave well at high duty cycle.
I kept the default current PI parameters for now, it seemed to be ok.

SFOC doesn't seem to limit the current, it's not a problem during the tests without load, but it might be during a real drive.
My gd32 implementation is using the overcurrent trigger pin that might kick in.

Now I need to check if analogread still works and doesn't break the current sensing, with the battery voltage for example.
The SFOC team told me it's not working for them with STM32.

No news from the Arduino-gd32 about some fixes I need to close the PWM driver init.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 loopFOC out 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" :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-)

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

@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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-(

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

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...

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

@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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

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

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

Enjoy your trip @RoboDurden 🌞

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

@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 :-)

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

@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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on August 28, 2024

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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 !!

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Here it is

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 ?

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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"{} :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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."

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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)];

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

@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 ?

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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);

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

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 :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

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

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Okay now i see that you indeed have dev branches for all three github repos. Sorry, Github is not intutive for me ;-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

No worries.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I have got the update event running at the right. (the small peaks are interferences)
I also get value from inserted adc, but values are weird.
DS1Z_QuickPrint1

But those 2 singles commands mess it up and introduce delays for the interrupt.

// user communication
command.run();
if (oOnOff.Get()) oKeepOn.Set(false);

DS1Z_QuickPrint2

But I used the interrupt only to check when the Update event is trigger by turning an output ON and OFF.
I couldn't get the Channel 3 to work yet, need to find why it's not working.
Once I have confirmed it's working I will remove the interrupt.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Yes i think i also observed strange behavior with the SELF_HOLD_PIN / BUTTON_PIN as i could not reproduce the normal hoverboard behavior to turn off the board. Do not understand this.

To my understanding, the update event can trigger on overflow (in the middle) and underflow (beginning/ending).
I think the beginning/ending is the time when the adc should take place as the gate-high-states are centered to the middle and you said that measurenments should take place when the low-side mosfets are conduction = hi=off & lo=on

As i wanted to call an update handler to trigger adc, i think i can check if it was an underflow and only then start adc.
But you want to trigger adc directly i think. But i fear, the GD32 can not be configured to only fire the update event on underlow. Only overflow or overflow+underflow.
Then i guess you indeed need the channel3.
But with the channel3 you could also start the adc a few microseconds before the beginning/ending :-)

P.S. i had the idea to first do the time critical adc of gate currents
then reconfigure the adc

	adc_channel_length_config(ADC_REGULAR_CHANNEL, aiPin.size());
	//adc_channel_length_config(ADC_REGULAR_CHANNEL, 1);

	int iSize = aiPin.size();
	for (int i=0; i<iSize; i++)
	{
		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);
	
		gpio_mode_set(gd_port, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, gd_pin);
		adc_regular_channel_config(i, gd_channel , ADC_SAMPLETIME_13POINT5);
	}

do the voltage and current_dc when we have all the time in the world
and finally reconfigure adc back to the two time critical gate currencies.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

This is what inserted adc is for.
It runs critical sampling with highest priority, while regular adc samples non critical stuff another time.
No need to reconfigure.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

So you can configure this "inserted adc" only once at the beginning and the update/channel3 event directly triggers putting normal adc on hold and "insert" its adc
and wait the few us to finish to read the values or only these inserted adc conversion gets written via dma ?
Everything without a handler function to be called ?
Only (please) when these time critical adc have been finished to i can put a motor.loopFOC() in that final callback :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Yes regular adc is put on hold.
We need to check how analog read is implemented. I think Arduino-FOC-drivers has a voltage reading 'driver' that uses it.

No 16khz is too fast for loopfoc.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

If you give me a callback when this inserted adc has finished, i can call loopFOC only every second call :-)

I overwrite the analog read function in my LowsideCurrentSenseTimer class

#define _ADC_VOLTAGE 3.3f
#define _ADC_RESOLUTION 4096.0f

float LowsideCurrentSenseTimer::ReadAdcVoltage(const int pin)
{
	if (_isset(pin))
		return ai_AdcBuffer[aiAdcMap[pin]] * _ADC_VOLTAGE / _ADC_RESOLUTION;
	return 0;
}

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Got ch3 to work so I can define where I want to sample. It works without any interrupt.
I get one sinusoidale phase current for one pin, but the other one is not reacting, just noise.
Need to check if it's the right pin, if it's not defective, or if I did something wrong.

But I have guests from tomorrow to sunday so might be hard to find time to progress.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

@Candas1 , i downloaded via zip file your Split_Hoverboard_SimpleFOC-dev but i get compiler error

src\main.cpp:239:5: error: 'GPIO_BOP' was not declared in this scope; did you mean 'GPIOB'?
I also do not understand the syntax of

  GPIO_BOP(GPIOB) = (uint32_t)GPIO_PIN_6; 
    motor.loopFOC();
    GPIO_BC(GPIOB) = (uint32_t)GPIO_PIN_6;

Are GPIO_BOP and GPIO_BC macro definitions ?

Also a lot warnings like

src\main.cpp:207:30: warning: ISO C++ forbids converting a string constant to 'char*' [-Wwrite-strings]
  207 |   command.add('T', doTarget, "target voltage");

Am i missing something ?

P.S. with command.add('T', doTarget, "target voltage"); i will be able to set the target speed to 10.2 Volt by entering T10.2 via the RTTStream serial communication ?

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

@Candas1 , if i remove (comment) these strange GPIO_BOP macro lines and set target by

target = 1 * (motor.voltage_limit) * (ABS((float)(((millis()-iLoopStart)/10 + 250) % 1000) - 500) - 250)/250;
The motor is not able to start spinning but only makes a heavy push every 2 seconds and the leds start blinking, i guess, the setup procedure. So board rebooting.

That is because i have replaced the on/off button with a switch and this happens when i keep the switch on.
Only after i put the switch off than after the next "push", the motor begins to spin nicely backwards and forwards.

If i only put that switch quickly on and off like pushing a button, then after setup, the motor will also make this heavy "push" and then begins to rotate nicely.

This "push" will make the motor spin for about 720° degrees :-(

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Also, the if (current_sense.init()) is still not active and i do not see a gd32 hardware file in https://github.com/Candas1/Arduino-FOC/tree/dev-gd32/src/current_sense/hardware_specific to "catch" the channel3 interrupt. Nor a new LowsideCurrentSensor class to implement your inserted adc - which of course i am eager to see :-)

ideas welcome.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

So i continued with my own LowsideCurrentSenseTimer and successfully switched to the TIMER0 update handler

GD32F130C8\Simple FOC\src\drivers\hardware_specific\gd32\gd32_mcu.cpp needs

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

Unfortunately the event handler is already defined and used in the GD32-Arduino-core::timer.c :

/* some devices have this. */
void TIMER0_BRK_UP_TRG_COM_IRQHandler(void)
{
    timerinterrupthandle(TIMER0);
}

So i kept my HardwareTimer in my class but set it to TIMER0

	pTimer = new HardwareTimer(instanceTimer);
	pTimer->attachInterrupt(&timer_cb);

Downside is that the current_sense.init(TIMER0,..) MUST be called before driver.init() because the constructor of HardwareTimer already initializes the TIMER0: timerHandle.init(timerDevice, &timerPeriod);
But when the _configure6PWM() reconfigures the TIMER0, it works.

That way the update handler in timer.c forwards to my

void LowsideCurrentSenseTimer::timer_cb() 
{
	//digitalWrite(LED_RED, digitalRead(LED_RED) ^ 1);
	LowsideCurrentSenseTimer::iCount++;

	digitalWrite(LED_ORANGE, (LowsideCurrentSenseTimer::iCount % LowsideCurrentSenseTimer::iTimerHz) < (LowsideCurrentSenseTimer::iTimerHz/4) );

	// Start ADC conversion
	adc_software_trigger_enable(ADC_REGULAR_CHANNEL);
	LowsideCurrentSenseTimer::iMicrosTimerCb = getCurrentMicros();
}

It is called at 16 kHz, so i guess i have only the overflow event which is in the middle of the pwm cycle ?
And not the begin/end that we want for adc sampling ?
In the user manual i now read that overflow and underlow are always enabled or disabled:


GD32F1x0 User Manual
9.1.4. TIMER0 registers
Control register 0 (TIMERx_CTL0)
bit 2: UPS Update source
This bit is used to select the update event sources by software.
0: Any of the following events generate an update interrupt or DMA request:
– The UPG bit is set
– The counter generates an overflow or underflow event
– The slave mode controller generates an update event.
1: Only counter overflow/underflow generates an update interrupt or DMA request

Will try

void LowsideCurrentSenseTimer::timer_cb() 
{
	LowsideCurrentSenseTimer::iCountTimer0 = timer_counter_read(TIMER0);

and monitor with StmStudio..

Of course, using Channel3 instead of Update-Event will be better.

Ideas welcome :-)

update: the timer0 counter is unrelated to an overflow or underflow :-/
stmstudio iCountTimer0
The range from 0 to 1500 is exactly timerBldc_parameter_struct.period = SystemCoreClock / pwm_frequency;

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Those macros are just the low level way to turn outputs on or off. I used this to measure duration from my oscilloscope.
This code is compiling fine for me. I have the warnings but it's not important.
Yes you can set up to T-15 or T15 but I usually increasing step by step otherwise it's too violent.
E0 or E0 to disable or enable the smoothing.

I haven't uploaded the current sensing as it's still work in progress.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Hi Candas :-)
As you can read i would be happy if you share your (complete) code that "Got ch3 to work".

P.S. after removing some OUT(..) log output now my callback runs at 32 kHz. So two events called per period. But of course no use when the callback time is unrelated to the actual over/underflow :-/

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

But the timer0_update_handler is called exactly every 31 us:

	void TIMER0_BRK_UP_TRG_COM_IRQHandler(void)
	{

		if (SET == timer_interrupt_flag_get(TIMER_BLDC,TIMER_INT_FLAG_UP))
		{
			uint32_t iNow = getCurrentMicros();
			LowsideCurrentSenseTimer::iMicrosAdcReady = iNow - LowsideCurrentSenseTimer::iMicrosTimerCb;
				LowsideCurrentSenseTimer::iMicrosTimerCb = iNow;
			LowsideCurrentSenseTimer::iCountTimer0 = timer_counter_read(TIMER0);

Which reflects the 32 kHz (overflow + underflow) of the 16 kHz pwm.
But if the handler gets called exactly in sync, then the timer counter should always be the same (with some offset maybe). Yet i get

31: 80
31: 74
31: 1420
31: 79
31: 1475
31: 210
31: 430
31: 79 

(these log values are 100.000 microseconds appart.)

timer_counter_read(TIMER0); might be wrong but it resolves to TIMER_CNT(timer_periph) which leads to
#define TIMER_CNT(timerx) REG32((timerx) + 0x00000024U) /*!< TIMER counter register */
and the user manual confirms:
This bit-filed indicates the current counter value. Writing to this bit-filed can change the value of the counter

I do not understand this.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

As the log output via RTT is only every 100000 micro seconds i have stored the last 10 calls

LowsideCurrentSenseTimer::aiMillis[LowsideCurrentSenseTimer::iPosMillis] = timer_counter_read(TIMER0);
LowsideCurrentSenseTimer::iPosMillis = (LowsideCurrentSenseTimer::iPosMillis +1) % 10;

and that looks more like two different events within the 16 kHz period:

1413    1413    87      87      87      87      1412    1412    1412
87      87      1412    1412    1412    1412    88      88      88
87      87      1412    1412    1412    1412    1412    88      88
87      87      87      1412    1412    1412    1412    1412    88
87      87      87      1412    1412    1412    1412    88      88
1413    1413    87      87      87      87      1412    1412    1412
87      87      1412    1412    1412    1412    88      88      88
87      87      1412    1412    1412    1412    1412    88      88
87      87      87      1412    1412    1412    1412    88      88
87      87      87      1413    1413    1413    1413    88      88
1413    1413    87      87      87      87      1412    1412    1412

The range of the counter is 1500: timerBldc_parameter_struct.period = SystemCoreClock / pwm_frequency;

But still i do not understand why 87 and 1412, and why they do not toggle like 87 1412 87 1412 87

maybe you @robcazzaro have an idea :-)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

okay, i had to add thread safety:

      int iPos = LowsideCurrentSenseTimer::iPosMillis;
      LowsideCurrentSenseTimer::iPosMillis = -1;  // thread safty
      for (int i=9; i>0; i--)
        OUTT(LowsideCurrentSenseTimer::aiMillis[(iPos + i) % 10])
      LowsideCurrentSenseTimer::iPosMillis = iPos;  // thread safty

and

	void TIMER0_BRK_UP_TRG_COM_IRQHandler(void)
	{
		if (SET == timer_interrupt_flag_get(TIMER_BLDC,TIMER_INT_FLAG_UP))
		{
				uint32_t iCounter = timer_counter_read(TIMER0);
			if (LowsideCurrentSenseTimer::iPosMillis >= 0)	// thread safety
			{
				uint32_t iNow = getCurrentMicros();
				LowsideCurrentSenseTimer::iMicrosAdcReady = iNow - LowsideCurrentSenseTimer::iMicrosTimerCb;
					LowsideCurrentSenseTimer::iMicrosTimerCb = iNow;
				LowsideCurrentSenseTimer::aiMillis[LowsideCurrentSenseTimer::iPosMillis] = iCounter;
				LowsideCurrentSenseTimer::iPosMillis = (LowsideCurrentSenseTimer::iPosMillis +1) % 10;
				//LowsideCurrentSenseTimer::iCountTimer0 = timer_counter_read(TIMER0);
				//LowsideCurrentSenseTimer::iCountTimer0 = timer_channel_capture_value_register_read(TIMER0,TIMER_CH_3);
			}

			//digitalWrite(LED_RED, digitalRead(LED_RED) ^ 1);
			LowsideCurrentSenseTimer::iCount++;
			digitalWrite(LED_ORANGE, (LowsideCurrentSenseTimer::iCount % LowsideCurrentSenseTimer::iTimerHz) < (LowsideCurrentSenseTimer::iTimerHz/4) );

			// Start ADC conversion only once in a peridod
			if (iCounter < 500)
				adc_software_trigger_enable(ADC_REGULAR_CHANNEL);

			timer_interrupt_flag_clear(TIMER_BLDC,TIMER_INT_FLAG_UP);
		}
	}

to get the nice two update events per pwm period:

46      1454    46      1454    46      1454    46      1454    45
46      1454    47      1454    45      1454    46      1454    46
45      1454    46      1454    46      1454    46      1454    46
46      1454    46      1454    46      1454    46      1454    46
46      1454    46      1454    46      1454    46      1454    46

Now i of course would like to understand how 46 and 1454 correspond to overflow and underflow.
But as 1464 + 46 = 1500 = period, it seems that the interrupt handler has a 46 microseconds delay :-/

So i need the channel3 interrupt :-)

https://github.com/RoboDurden/Arduino-FOC/blob/master/src/current_sense/LowsideCurrentSenseTimer.cpp#L247
https://github.com/RoboDurden/Split_Hoverboard_SimpleFOC/blob/main/src/main.cpp#L327

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

You don't understand.
It will happen with any interrupt.
If another interrupt with higher or equal preemption is running, your interrupt will wait.
That's why I haven't used interrupts.

The benefit of ch3 is that your trigger the event at a specific timer counter.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Yes i understand that YOU do not need a timer interrupt handler.
But as you do not share your progress, i have to progress from what i can do so far - and that is triggering adc from a timer0-interrupt handler :-)

i am a born loser !

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I did all this now. This is waste of time.
Anyway....

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Yes you already said that you all did this already. But i do not see your code online.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I will share it when it fully works.
You don't believe me? 🤣

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Of course i believe you.
The problem is that i do not want to wait :-)
It is my time that i am wasting.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Your feedback about the smoothing would be welcome if you are bored.
How is it comparing to EFeru's sinusoidal in terms of speed and consumption for example.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Okay, i will do that tomorrow :-)
But i had this nasty "push" before the motor starts spinning, so i continued with my repo to wait for your comment on this.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I don't have anything like this.
The target is 0 at startup.
I feed the sensor direction and zero angle so the calibration is skipped.
Those are not parameters of initFOC function anymore in the dev branch of simplefoc.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Yes and my sine one-liner also starts with 0.
Okay, will inverstigate myself tomorrow.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Hi, some update.
The gain was set as 50 but I don't think it's correct. Anyone knowledgeable about opamps ?
This is for dual boards but maybe it's the same, so 2.5.
Eferu was wrongly using the same gain of 11 for both phase current and dc current.

Also, I just remembered that with Eferu's firmware the current readings were inverted, so if it's the same I need negative gains for the phases.

When this is correct I need to tweak the current PID parameters.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

You could connect a battery with a resistor to one phase cable to have 10 A when the lower MOSFET is ON. With no inductivity the pwm current should be equal to a multimeter measurement.
Then simply calculate the opamp gain from your adc readings.

The opamp gain depends on a little SMD resistor in the feedback line from its output back to it's input, I think.

As I read in your first link, you can also connect the minus pole of the battery to a phase cable and positive pole to hoverboard minus. Then the -10A should give an adc reading below the offset which should be 1.x volt.
Something like 0.5V lower.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Some of this is actually supposed to be done in the function driveralign, It should power each phase separately and detect if pins are swapped or gains are inverted, I need to check why it fails.

That's one of the features I started to implement on Eferu but then I saw it's already available with SFOC.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

from my defines_2-0.h:

// BLDC low-side current sense pins (R_ds)
#define BLDC_CUR_Rds 0.008	// R_ds of the low side n-Chnannel mosfets
#define BLDC_CUR_Gain 50.0	// gain of the op-amp to amplify voltage_drain-source
#define BLDC_CUR_G_PIN _NC	// simpleFOC can handle 2 or 3 current sense pins
#define BLDC_CUR_B_PIN PB1
#define BLDC_CUR_Y_PIN PB0

Forgot where i got these numbers from :-/
Maybe i searched the net for what mosfets are found on the boards and did lookup the R_ds_on in a datasheet.
Yes, the gain of 50 seems to be to high.
With an offset at the middle of the 0 - 3.2 Volt adc range, that leaves 1.6 Volt to measure from 0 to +-35 A.

So 1.6V / (0.008 Ohm * 35 A) = 5.71 and a BLDC_CUR_Gain of 5.0 should fit better.

But attaching an externally defined 10A to a phase cable and simply measure the adc output should be the easiest way to verifiy the offset and gain.

I will be continuing my journey with my 10 km/h solar micro camper tomorrow, and will not have a test setup with me the next 2-3 weeks. So if you want me to test something, than i can do this only today.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

According to https://en.wikipedia.org/wiki/Operational_amplifier :: Closed-loop-amplifier
closed loop amplifier
the gain is 1 + Rf / Rg.
With the hoverboard_schematics.pdf
the gain for current_DC (shunt resistor) is 1 + 10/1 = 11
opamp current_dc
The gain for phase currents should be 1 + 2.2/1 = 3.3 (at least for defines_1-0.h :
opamp phase_current
PH_AMP_VN is the source of the mosfet (which connects to the current_dc-shunt_resistor and PH_AMP_VP is the Drain of the mosfet which connects to one of the three phase cables.
opamp phase_current pins

update:
The phase current offset voltage is generated by the 220k : 40k voltage divider and should only be 40/260 * 3.3V = 0.5 Volt.
So no -35A. But -10A with a gain of 3.3 would be 3.3 * 0.008 * -10 = -0.264. 0.5 + -0.264 = +0.236 V :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I checked, I think layout 2.0 is same as 1.0:
image

This is the op amp.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

A bit strange that BLDC_CUR_B_PIN is not PB1 because the mapping green blue yellow to A B C like SFOC is using of course could be reversed.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

Somes updates.
On thursday I tweaked the gains and the PID parameters, it was running quite well.
When I went back at it on saturday it was not working anymore.
My power supply was going to CC mode and the mosfets were getting hot.
I thought it was because of my changes and wasted a lot of time.

But it turned out the offsets were different and I had to tweak it to a different value each time for phase A.
I need to investigate what is happening there.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

offset_ia etc. are not stored in some eeprom and are not even set to zero in the constructor.
So when you uncomment the offset calculation and reset the board, the old values might still be in the ram. But when you turn off and on you get random numbers.
I am not sure that floats always get initialized to zero.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I don't think it's a bug with SFOC, even if I force my own offset values after the calibration, I still need to tweak the values again.
I believe the gains can change with temperature as we use mosfet RDSON instead of real shunt resistors, but the offsets should n't change.

Need to check if the adc readings are stable during the offset calibration. This used to be a problem even with Eferu in the past when I was playing with AT32 boards.

Those offsets are really important and should be done when the wheels are not moving.
I believe this was also the reason why some boards would burn at start up with FOC torque mode.
If your 0 is wrong you will apply a lot more current than expected, and your overcurrent protection won't pick it up.

Imagine if the board happens to reset while driving, and the offset calibration starts, this can go horribly wrong.
It seems VESC is saving the offsets to eeprom instead of running it at each startup, we might have to do that as well.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

Great that you take this problem so seriously. board resets do happen with my little solar camper !!!
The offset should be the middle of 3.2 V and defined by the 220k : 20k+20k voltage divider.
The hot mosfet R_ds_on would only change the scaling around this offset. So not such a big problem ?
If the 20k+20k resistors are close to the 220k on the board, they should heat equally and the offset would not change.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

For offset calibration to happen, the pwms have to be set to 0,0,0 to turn all low side mosfets ON.
Maybe this is generating a small movement and a delay between driver initialization and offset calibration can help.

I really want to get this right so I will take the time to investigate more.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

I used another board and now the offsets are stable.

It's the 3rd board, 3 different behaviors.
I need to figure out later what is wrong with those 2 boards.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

You could measure the input of the opamp to verify that the 40:220 voltage divider is stable. Then the adc in the gd32 must be the problem.

During offset calibration all high side MOSFET must be off and the low side MOSFETs on I guess.
Maybe the code does not work.
Or some MOSFETs are bad and have some leakage ? Then unplugging the motor phase cable might show a decrease in overall power consumption.

I still have this annoying problem with my gen1 board driving my solar camper but generating some heavy noise either over the battery cables or the UART bus and my i2c OLED collapses and the ads1115 i2c adc module sends wrong readings.

But something like that should affect all your adc inputs.

Maybe these boards had a heavy over current and the adc channel of that MOSFET is broken - a bit :-/

Just some ideas

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on August 28, 2024

After the offset calibration, Current is visible on one phase current even in voltage mode at zero target, which I think should not happen as the pwm duty cycle is 50% for all the phases so no current should flow. So it could be some leakage, need to check that phase with the oscilloscope.

I think the code is ok as it works fine with the last board, but I will try to find the root cause, more people will face this for sure in the future.

We could compile all those checks in a test firmware.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

The 2.0 layouts have analog gate drivers. Maybe check the gate voltages of the two corresponding MOSFET. If there is a leakage bit the MOSFET still okay, the gate voltage might not be pulled actively down to zero..

Greetings from my little Forrest
bis zu 60 cm im steilen Hang

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on August 28, 2024

I will be back home in about a week.

I think I would like to write a little pin auto detect firmware to help beginners add the many different layouts..
Could it be possible that the six MOSFET outputs are always the same because of only timer0 having this extended pwm feature ?

With that nice stlink serial interface it should be easy to test the hall pins and led pins.
Only the onoff button and the hold pin are a bit tricky.

Any chance your SFOC firmware will stay below 32k ? Layout 2.6 again seems to be a x6 MCU :-/

from split_hoverboard_simplefoc.

Related Issues (10)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.