Git Product home page Git Product logo

Comments (88)

robcazzaro avatar robcazzaro commented on July 25, 2024 2

@RoboDurden understood, and appreciate your help. The reason why I'm so focused on the low level timer, is because that initialization code is fundamental to everything else on top of it. SimpleFOC relies on a smooth PWM to be able to use the FOC algorithm properly. Especially at higher speeds or higher torque, proper control of the PWM with proper dead times is also critical to keep the MOSFETs cool and in good shape. And the motor running quietly. SimpleFOC has a lot of settings to ensure smooth running, smooth accelerations, etc, but it all relies on the PWM underneath. So I keep annoying everyone with it 😉

At this point we are looking really solid, and I'm happy. I'll work to improve the code for proper pin initialization to be more generic and to derive the dead time from the initialization settings (it's hardcoded in a constant now), but none of it is critical now for the rest of the project. So, please disregard my ramblings and keep working on the rest of the code. And if you run into any low level problem, open an issue and send it my way

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024 1

No forget it, I think it happens when you change the duty cycle. This doesn't happen in your case.
I don't think it will solve what you have seen.

But still worth checking.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024 1

I made some progress, not as much as I wanted.

There are 3 problems with the timer as is:

  • Phase G and B are reversed. @Candas1: I haven't looked at where these are swapped, since it's not as critical for now, but maybe you can spot the problem
  • The timer output is negated compared to the STM32 output for the same values. This is a big issue, probably need to enable the positive/negative edge of the timer, haven't looked into this yet
  • There is a recurring glitch which disappears when the processor is halted in debug mode. Which means that the glitches are generated by the GD32 Arduino code, given that in halt mode the timer keeps working. I'll open a bug in the GD32 project

I captured more scope images using the values 0, 5, 9 out of a max of 10V, i.e. 0%, 50%, 90%. The names of the files are processor-phase-percent and I have B, G and Y in order for both

First, the STM32
STM32-B-0
STM32-G-50
STM32-Y-90

Now GD32 in same order. Note that the GPIO outputs are high when low for the STM32, and vice versa. So 90% is actually 10%, 0 is actually wrong, both signals are high which should not happen. 50% looks identical, but it's reversed as well. This will obviously cause problem to the FOC motor control, since the voltages are wrong. The phase G and B being swapped is not as critical for motor control, as long as the motor connections are ok

GD32-B-0
GD32-G-50
GD32-Y-90

the code I used in this for both projects

#include <Arduino.h>
#include <Config.h>
#include <Defines.h>
#include <SimpleFOC.h>

// BLDCMotor motor = BLDCMotor(15);
BLDCDriver6PWM driver = BLDCDriver6PWM(BLDC_BH_PIN, BLDC_BL_PIN, BLDC_GH_PIN, BLDC_GL_PIN, BLDC_YH_PIN, BLDC_YL_PIN);

void setup()
{

  // power supply voltage [V]
  driver.voltage_power_supply = 10;
  // Max DC voltage allowed - default voltage_power_supply
  driver.voltage_limit = 10;
  driver.init();
  driver.enable();
  delay(1000);
}

void loop()
{
  // phase B        G         Y
  // pins  A9-B14   A10-B15   A8-B13
  driver.setPwm(0, 5, 9);
}

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024 1

I almost figured out the glitch. It happens when a new PWM value is written to the timer registers (new PWM value, or in the case of my sample code simply re-writes the existing value). The sample code is setting PWM values as quickly as the loop time, which is why I see so many glitches with the loop containing only a single pwm command.

Probably in the STM32 there is a register setting to seamlessly update the register values without glitching the timer, and it's not set for GD32. I'll see if I can find it

EDIT: by commenting out the following 2 lines, the glitch disappears

void _setSinglePhaseState(PhaseState state, uint32_t timer_periph, uint16_t channel1,uint16_t channel2) {
  _UNUSED(channel2);
  switch (state) {
    case PhaseState::PHASE_OFF:
      timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_DISABLE);
      timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_DISABLE);
      break;
    default:
      //timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_ENABLE);
      //timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_ENABLE);
      break;
  }
}

As for the timer polarity, it's a problem with register CHCTL0, which is set to 0x7070 but must be 0x6868 like in the STM32. It can be fixed by changing the lines following this to the below

  timer_channel_output_shadow_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, TIMER_OC_SHADOW_ENABLE);
  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);

  // Set output channel PWM type to PWM0
  timer_channel_output_mode_config(TIMER_BLDC, TIMER_BLDC_CHANNEL_G, TIMER_OC_MODE_PWM0);
  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);

With these 2 fixes, the only remaining problem is understanding why a PWM value of 0 results in both outputs being 0. I'm too tired to figure that out tonight :)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024 1

It's 6am here, I can take over the shift 😜
Thanks a lot for the hard work.
I am going to work now, I have answers to some of your questions, I will reply when I am back on the computer.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024 1

Just came across this, it can be useful.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024 1

I'm trying to get a signal on the scope using either the original firmware, or another firmware not using SimpleFOC, to check the polarity of the signal driving the MOSFET gates. Usually the signal used must be complementary (i.e. when the high side is high, the low side is low, and vice versa, but the hoverboard seems to use the same polarity for high and low side... I want to be sure that's the case)

So the idea would be to connect the scope probes to a pair of complementary GD32 pins, set the scope in single shot mode, and capture the signal. Even if the PWM keeps changing when the motor runs, the single shot will freeze a portion of the signal that is representative enough.

@Candas1, I will take on those 3 work items while you frolic on vacation 😁. I had already planned to look at those

And, yes, I agree, no value doing the software PWM. We might want to look at the other hardware PWMs just to have am ore complete GD32 solution, but would not work for the hoverboards, so low priority

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024 1

@Candas1 I do actually have the real hardware, a Layout 2.0 board with a C8. I just didn't want to burn the only board I have while messing around with low level timer code (and, given all the tests I did, I would have killed it almost for sure). I have a hard time finding other boards that I can work on (the other I have uses a weird MM32 processor which is almost impossible to support. Just buying random hoverboards gets expensive, unless you can find non-working ones (usually just a dead battery)

I can now use the actual board, but I will still prefer the Bluepill for any low level development: it's so much easier to probe pins on the Bluepill than trying to hold a probe on a tiny pad in the real board, not to mention that having nothing else connected I can verify waveforms and timing without other components influencing it. For example, the dead time timing is easier to measure on the Bluepill.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

IMG_20230619_102519.jpg

This is what I get when running your code.

My power supply was in cc mode because of the high duty cycle.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Your waveforms are smoothed due to the presence of load on the GPIO pins. But you can clearly see the same spikes I was seeing in the CH2, and those will kill the MOSFETs over time

I'll look at the initialization code and see what's going on. The same code on STM32 produces absolutely clean signals. That could explain the noisy motor control you and @RoboDurden are seeing

BTW: you might want to use something like https://www.eevblog.com/forum/testgear/rigol-screen-capture-vcl-windows-application/ it works either via USB or LAN, and it's lightweight and fast

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

But are you sure the spikes are not due to the cc mode?
I am not sure if the voltage was high enough to drive the mosfets.

With the code from my repository I don't think I have the spikes.

I didn't know about that capture program, thanks

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

One idea, I have never used the splitboard firmware so I assumed it was working well, but I saw something weird in the code but I haven't had time to investigate.
If I am not wrong on stm32 there is a shadow register were you save the new duty cycle, and it is applied only at the end of the period, on timer update.

I am wondering if this code is the problem.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

My plan is to run the STM32 code, dump the register content, run the GD32 code dump as well, and compare the two. As much as the HAL is different from the SPL, the underlying registers are the same, so the values in the end must be the same

Just haven't had time to do it yet :) please continue to work on the rest of the code, and I promise I'll get this working

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Hmm it could really be that, stm32duino enables it, but it was disabled in the splitboard firmware.
We can enable it and try again.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

The European shift tales over 😂

As you saw, I solved the glitch and reversed values. What is missing and critical is the wrong values for 0 pwm (and possibly 100%, I haven't checked). Then the swapped G and B phases, which I'm almost sure are simply a channel swap

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

I see you already enabled the shadow register as mentioned here, this is best practice that was missing in the original firmware. Are you sure this hasn't solved some of the glitches ?

About the PWM being inverted, that's also coming from the original firmware, and EFeru's firmware has the same. This is usually done to center the low side ON time for ADC sampling, see (1) on the picture:
image
I need to check how simpleFOC deals with that. There should be 2 update events per cycle, maybe they are using the second one, see (2) on the picture.

Regarding this:

void _setSinglePhaseState(PhaseState state, uint32_t timer_periph, uint16_t channel1,uint16_t channel2) {
  _UNUSED(channel2);
  switch (state) {
    case PhaseState::PHASE_OFF:
      timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_DISABLE);
      timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_DISABLE);
      break;
    default:
      //timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_ENABLE);
      //timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_ENABLE);
      break;
  }
}

SimpleFOC also seems to turn the phase OFF, that's probably why you see both high side and low side being low. It's called HIGH IMPEDANCE.
The STM32 code is pausing or resuming the channel, it could be the SPL I used is not doing exactly the same thing.

I also have some splitboards with STM32F103 chips, so I could try comparing how the firmware behaves on those boards.

If later you need the counter to stop during debug, I added this but it's commented. This is how STM describes it :
image

I also noticed the old firmware was using this. I am not sure we want that. This will enable the timer output after each PWM cycle if it's disabled. We need to check if disabling the driver works as expected.
This is how STM is using it for motor control:
image

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Well, my goal was to get the GD32 SimpleFOC driver work the same as the STM32. If we want SimpleFOC to work without surprises, we need to follow the same conventions and have the PWM timer work the same (phase voltage and all).

The 2 lines I commented out here https://github.com/Candas1/Arduino-FOC/blob/7cff1faa6acc47b04dabed47e230265bfb99a875/src/drivers/hardware_specific/gd32/gd32_mcu.cpp#L158 cause the glitch. The STM32 code for that function is much more complex and does a lot more, but I'm not sure that it writes to the same register as the GD32. I haven't fully followed that code yet and it's possible that we need more than just commenting out two lines. The "high impedance" phase_off code is still needed, but not yet called for now. That is definitely needed.

The inverted output must be changed. Otherwise SimpleFOC sends, say, a 10V out of 12V on a phase, but the GD32 driver will send ~2V instead.... not good :)

And we still have a problem with 0V and possibly Vmax, not sure yet. I'll work on that today

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Yes I agree, I commented the same in the other thread.
I tried changing PWM1 to PWM0, it just makes the motor spin in the other direction.
I imagine that switching the 2 phases and changing from PWM1 to PWM0 will just make it run in the same direction again.

Touching any of this code, the motor stops spinning, I need to find how to make it work without the glitch.

void _setSinglePhaseState(PhaseState state, uint32_t timer_periph, uint16_t channel1,uint16_t channel2) {
  _UNUSED(channel2);
  switch (state) {
    case PhaseState::PHASE_OFF:
      timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_DISABLE);
      timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_DISABLE);
      break;
    default:
      //timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_ENABLE);
      //timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_ENABLE);
      break;
  }
}

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

When you are saying G and B phases are reversed, are you talking about the BLDCDriver6PWM function call ?

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

When you are saying G and B phases are reversed, are you talking about the BLDCDriver6PWM function call ?

Yes. If I call the below

  // phase B        G         Y
  // pins  A9-B14   A10-B15   A8-B13
  driver.setPwm(0, 5, 9);

I get the wrong 0% on pins A10/B15, 50% on A9/B14 and 90% on A8/B13. On the STM32 with the same definitions, I get as expected 0% on pins A9/B14, 50% on A10/B15 and 90% on A8/B13.

The pins assigned to timer channels must have a problem. Incidentally, the current code has the pin names in the function parameters, but the code uses the macros defined in the settings instead

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Yes I agree, I commented the same in the other thread. I tried changing PWM1 to PWM0, it just makes the motor spin in the other direction. I imagine that switching the 2 phases and changing from PWM1 to PWM0 will just make it run in the same direction again.

Touching any of this code, the motor stops spinning, I need to find how to make it work without the glitch.
[...]

I was afraid of this, thanks for checking. The simplest workaround is to check if the timer is already enabled and only call the function to enable it if not enabled. Unlike the PWM call I use for test, the motor control very likely turns off a phase in certain parts of the rotation, and with the current code commented out, the timer is never re-enabled. I will do it today, pretty trivial to check if the timer is already enabled or not

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

ok I got what you mean, you think enabling over and over again generates the glitch. Makes sense.
If needed I could also save the channel state in the params struct, sometimes calling those registers over and over again also takes time.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

I wouldn't worry about that. On an STM32 or GD32, checking a register takes as many assembly instruction as checking a variable value. All registers are memory mapped and accessible with no delays :)

If you look at the STM32 code, that function is almost a hundred lines of code calling other function. On the GD32, it's going to be just a simple register read, binary and and a check, which is going to be super fast

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

I tried a lot of things but still it didn't improve.
As a workaround, using SinePWM or SVPWM instead of Trapezoidal, the High Impedance state is not used, and the channel is not enabled/disabled. So commenting the code in the function has no impact. And it is much more silent.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

@Candas1 , @robcazzaro , you make me happy and i fear that i can contribute little to that low level library confsusion.
So only take my words as inspiration and do not waste time to explain things to me that are obvious to you !
I have simply deleted all files to let Github-Desktop re-clone his repo here.

I do not understand how the 6 gate driver pins are mapped to the pwm interrupts!

BLDCDriver6PWM driver = BLDCDriver6PWM( BLDC_BH_PIN,BLDC_BL_PIN, BLDC_GH_PIN,BLDC_GL_PIN, BLDC_YH_PIN,BLDC_YL_PIN );
only stores the 6 pins to the public (why not private?) element variables

  	int pwmA_h,pwmA_l; //!< phase A pwm pin number
  	int pwmB_h,pwmB_l; //!< phase B pwm pin number
  	int pwmC_h,pwmC_l; //!< phase C pwm pin number

BLDCDriver6PWM::init() sets them to OUTPUT and the only use of these 6 params are in the following _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l);

But when i look at the GD32 implementation of that function, the 6 params are never used at all:

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){
In the stm32_mcu.cpp they are stored to

int pins[6] = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l };
Searching those public element variables like pwmA_h with strg+shift+F over the entire projects do also not show any references.

So i wonder how our gd32_mcu.cpp is able to drive the 6 mosfet pins at all ?

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

For the moment the gd32 driver is using fixed pins, it's not using the parameters from this function.
Because anyway the only timer that can be used is timer0, and anyway all the channels are available for fixed pins only.
So only pinmode() is set in BLDCDriver6PWM.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

So the swapping of BLDCDriver6PWM( BLDC_BH_PIN,BLDC_BL_PIN, BLDC_GH_PIN,BLDC_GL_PIN, BLDC_YH_PIN,BLDC_YL_PIN ); of course had not effect :-(

But then i want to mention (like @robcazzaro ?) that HallSensor(HALL_A_PIN, HALL_B_PIN, HALL_C_PIN, 15); seems to init with Green,Blue,Yellow according to the color of the hall cables, but the driver is instantiated with blue,green,yellow.

Maybe i could beautify your "for the moment" code with the Arduino-Core helper functions that retrieve the port and pin from single values BLDC_BH_PIN, etc. :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

I would rather have something that works and then beautify it.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

I'll take over now for the Seattle shift :)

@RoboDurden to add to what @Candas1 says, the SimpleFOC is written for generic boards and a variety of processors. It tries to use every possible pin combination, and there is a lot of code devoted to ensure that the timer/pin combination is the right one. There are STM32 processors with multiple usable timers and pins, unlike in our case. Granted, if we wanted the GD32 code to be truly generic, we would need to use the pins passed in the call, but for now we are focusing on getting it at least usable, then make it more generic.

The reason why almost all the pins in the SimpleFOC code are global, is that the Arduino pin naming convention is crazy and some pins have multiple possible uses. In a case with the STM32G431, I needed to use a pin for the encoder (which uses a timer in encoder mode), and that pin was PB7. But I needed to use the PB_7_ALT1 version to properly set the pin in the timer. The Arduino code has no provision to identify which of the multiple functions a pin can use. So the workaround was to instantiate the encoder with PB7, then set encoder._pinB to PB_7_ALT1 (https://community.simplefoc.com/t/encoder-skips-pulses/2884/38)

It's very hard to write generic code that works on every possible processor family and processors inside a family. The SimpleFOC team did a pretty amazing job, hacks and all

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

For now channels (not pins), can be swapped here.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

This code is taken from gd32/pinmap.c void pin_function(PinName pin, int function) , compilies successfully but i understand that for now you prefer hard coded port/pins and to not care for the higher abstraction levels:

  uint32_t port   = GD_PORT_GET(pinA_h);
  uint32_t gpio = gpio_clock_enable(port);
  uint32_t gd_pin = 1 << GD_PIN_GET(pinA_h);

  gpio_mode_set(gpio, GPIO_MODE_AF, GPIO_PUPD_NONE, gd_pin);
  //gpio_mode_set(TIMER_BLDC_GH_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, TIMER_BLDC_GH_PIN);

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

We need much more than that to get it to work that way.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

One example

This gives you the timer channel for a pin, it doesn't exist in arduino-GD32.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Dear Candas, don't waste your prescious time to argue with a born loser. uint32_t getTimerChannel(PinName pin) is neither used in stm32_mcu.cpp nor in BLDCDriver6PWM.cpp so i guess it is okay to hard code the timer channel.
But when the constructor asks for the 6 pins, it will only cause "swapping" problems when not making use of them - in the long run.
Have a nice 14 day trip. Holiday or your job ?

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Holidays. I will still be brainstorming from there as I cannot take this topic out of my mind.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

"working jobs we hate so we can buy shit we don't need" - Tyler Durden, Fight Club.
Be happy to not have "bought" yourself holidays in order to free your mind from a job you hate.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

I still think this is more readable and less error prone:

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_paramter_struct;	
  timer_break_parameter_struct timerBldc_break_parameter_struct;
  timer_oc_parameter_struct timerBldc_oc_parameter_struct;

  int aiPin[6] = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l };
  uint32_t aiGdPort[6];
  uint32_t aiGdPin[6];
  for (int i=0; i<6; i++)
  {
    aiGdPort[i] = gpio_clock_enable(GD_PORT_GET(aiPin[i]));
    aiGdPin[i] = 1 << GD_PIN_GET(aiPin[i]);
  }

  // Init PWM output Pins (Configure as alternate functions, push-pull, no pullup)
  for (int i=0; i<6; i++)
  {
    gpio_mode_set          (aiGdPort[i], GPIO_MODE_AF, GPIO_PUPD_NONE,    aiGdPin[i]);
    gpio_output_options_set(aiGdPort[i], GPIO_OTYPE_PP, GPIO_OSPEED_2MHZ, aiGdPin[i]);
    gpio_af_set            (aiGdPort[i], GPIO_AF_2,                       aiGdPin[i]);
  }    

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

  // Initial deinitialize of the timer
  timer_deinit(TIMER_BLDC);
  //dbg_periph_enable(DBG_TIMER0_HOLD); // Hold counter of timer 0 during debug
 
  // Set up the basic parameter struct for the timer
  timerBldc_paramter_struct.counterdirection  = TIMER_COUNTER_UP;
  timerBldc_paramter_struct.prescaler 		    = 0;
  timerBldc_paramter_struct.alignedmode 	    = TIMER_COUNTER_CENTER_DOWN;
  timerBldc_paramter_struct.period			      = SystemCoreClock / pwm_frequency;
  timerBldc_paramter_struct.clockdivision 	  = TIMER_CKDIV_DIV1;
  timerBldc_paramter_struct.repetitioncounter = 0;
  timer_auto_reload_shadow_disable(TIMER_BLDC);

  // Initialize timer with basic parameter struct
  timer_init(TIMER_BLDC, &timerBldc_paramter_struct);

  // Set up the output channel parameter struct
  timerBldc_oc_parameter_struct.ocpolarity 		= TIMER_OC_POLARITY_HIGH;
  timerBldc_oc_parameter_struct.ocnpolarity 	= TIMER_OCN_POLARITY_LOW;
  timerBldc_oc_parameter_struct.ocidlestate 	= TIMER_OC_IDLE_STATE_LOW;
  timerBldc_oc_parameter_struct.ocnidlestate 	= TIMER_OCN_IDLE_STATE_HIGH;

  // Set up the break parameter struct
  timerBldc_break_parameter_struct.runoffstate      = TIMER_ROS_STATE_ENABLE;
  timerBldc_break_parameter_struct.ideloffstate     = TIMER_IOS_STATE_DISABLE;
  timerBldc_break_parameter_struct.protectmode	    = TIMER_CCHP_PROT_OFF;
  timerBldc_break_parameter_struct.deadtime 	      = DEAD_TIME; // 0~255
  timerBldc_break_parameter_struct.breakstate	      = TIMER_BREAK_DISABLE;
  timerBldc_break_parameter_struct.breakpolarity	  = TIMER_BREAK_POLARITY_LOW;
  timerBldc_break_parameter_struct.outputautostate 	= TIMER_OUTAUTO_ENABLE;

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

  // Disable until all channels are set for PWM output
  timer_disable(TIMER_BLDC);

  uint16_t aiChannel[3] = {TIMER_BLDC_CHANNEL_G,TIMER_BLDC_CHANNEL_B,TIMER_BLDC_CHANNEL_Y};

  for (int i=0; i<3; i++)
  {
    timer_channel_output_fast_config(TIMER_BLDC, aiChannel[i], TIMER_OC_FAST_DISABLE);      // Deactivate output channel fastmode
    timer_channel_output_shadow_config(TIMER_BLDC, aiChannel[i], TIMER_OC_SHADOW_DISABLE);  // Deactivate output channel shadow function
    timer_channel_output_mode_config(TIMER_BLDC, aiChannel[i], TIMER_OC_MODE_PWM1);         // Set output channel PWM type to PWM1
    timer_channel_output_pulse_value_config(TIMER_BLDC, aiChannel[i], 0);    // Initialize pulse length with value 0 (pulse duty factor = zero)
    timer_channel_output_config(TIMER_BLDC, aiChannel[i], &timerBldc_oc_parameter_struct);  // Configure with the output channel parameter struct
    timer_channel_output_state_config(TIMER_BLDC, aiChannel[i], TIMER_CCX_ENABLE);          // Enable for PWM output
    timer_channel_complementary_output_state_config(TIMER_BLDC, aiChannel[i], TIMER_CCXN_ENABLE); // Enable complemenary channel for PWM output
  }

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

  // 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 = { aiChannel[0], aiChannel[0], aiChannel[1], aiChannel[1], aiChannel[2], aiChannel[2] },
    .pwm_frequency  = pwm_frequency,
    .range          = SystemCoreClock/pwm_frequency,
    .dead_zone      = dead_zone,
    .interface_type = _HARDWARE_6PWM
  };

  return params; // success
}

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

We can always improve the code.
This is mostly a copy paste of the timer setup from your splitboard repository into the simpleFOC driver code.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Ok, here's the working code (no glitch, can turn phases off). I needed to add a function _isChannelEnabled() before _setSinglePhaseState()

Just replace _setSinglePhaseState with the snippet below

uint32_t _isChannelEnabled(uint32_t timer_periph, uint16_t channel)
{
  switch (channel)
  {
  /* configure TIMER_CH_0 */
  case TIMER_CH_0:
    return (TIMER_CHCTL2(timer_periph) & (uint32_t)TIMER_CHCTL2_CH0EN);
    break;
  /* configure TIMER_CH_1 */
  case TIMER_CH_1:
    return (TIMER_CHCTL2(timer_periph) & (uint32_t)TIMER_CHCTL2_CH1EN);
    break;
  /* configure TIMER_CH_2 */
  case TIMER_CH_2:
    return (TIMER_CHCTL2(timer_periph) & (uint32_t)TIMER_CHCTL2_CH2EN);
    break;
  /* configure TIMER_CH_3 */
  case TIMER_CH_3:
    return (TIMER_CHCTL2(timer_periph) & (uint32_t)TIMER_CHCTL2_CH3EN);
    break;
  default:
    return 0xFFFF;    // should never get here. Added to avoid compile warning
    break;
  }
}


void _setSinglePhaseState(PhaseState state, uint32_t timer_periph, uint16_t channel1, uint16_t channel2)
{
  _UNUSED(channel2);
  switch (state) {
    case PhaseState::PHASE_OFF:
      timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_DISABLE);
      timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_DISABLE);
      break;
    default:
      if (_isChannelEnabled(timer_periph, channel1) == 0) // enable timer channel only if disabled to avoid glitches
      {
        timer_channel_output_state_config(timer_periph,channel1,TIMER_CCX_ENABLE);
        timer_channel_complementary_output_state_config(timer_periph,channel1,TIMER_CCXN_ENABLE);
      }
      break;
  }
}

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Thanks a lot.

I included it in the driver. I think I still see glitches from my side, but maybe we are not talking about the same glitch.
I also used your function but for when phase has to be disabled, and some small other changes.

It's published, you can try to update arduino-FOC from your side.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

As a reminder, we have 2 remaining problems, one minor, one major

The minor one is the swapped G and B phases, which @Candas1 has a workaround for

The major is that 0 and 100% are still wrong. In the STM32, when the value is 0, a9 low, b14 high. when 100% a8 high, b13 low

in the GD32 at 0 a10 high, b15 low, 100% a8 high, b13 high

I see also weirdness when using values like 98%, I'm investigating further

EDIT: I found the problem, please don't use this code yet

And I forgot: @Candas1, enjoy your vacation!

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Tell me, I am still awake 😂

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

The complementary input is inverted, but at this point I don't know if it's because I messed something up with the many code changes. I need to download your code and start fresh. But I also need to take a break for another task, so it won't be for a couple of hours at least. Go to sleep 😉

To be clear: for me right now, all the complementary outputs are wrong. Once I solve this, the 0 and 100 are solved, too. But I need to start from clean, I touched too many things

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

OK no worries. I will still have some time tomorrow.
Platformio is a bit confusing me. The code was working, I published. Then I ran the update command but the wheel started cogging. I changed the zero angle offset again and it spins as least but it's a bit noisy. I definitely need to improve the calibration.

But SinePWM and SpaceVectorPWM are really smooth.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Ok, I think I have solved everything (minus the phase swap)

There were a couple of issues here.

The OC and OCN polarity should both be high, and the OC and OCN idle states must be low. It's counterintuitive, but they want to know if the active state of the complementary output is high when it should be high (which is what we want). One would think they want to know the phase of the complementary output (which is the opposite of the normal output), but that would be wrong 😉

Also, these calls use the full timerBldc_oc_parameter_struct content. When debugging, the structure could be initialized to values != 0, and when that happens, the register settings are completely messed up. It's safer to initialize it fully, including settings we change later.

So I changed the two definitions for N polarity and added the outputstate and outputnstate to be on the safe side

  // Set up the output channel parameter struct
  timerBldc_oc_parameter_struct.outputstate   = TIMER_CCX_DISABLE;
  timerBldc_oc_parameter_struct.outputnstate  = TIMER_CCXN_DISABLE;
  timerBldc_oc_parameter_struct.ocpolarity    = TIMER_OC_POLARITY_HIGH;
  timerBldc_oc_parameter_struct.ocnpolarity 	= TIMER_OCN_POLARITY_HIGH;
  timerBldc_oc_parameter_struct.ocidlestate 	= TIMER_OC_IDLE_STATE_LOW;
  timerBldc_oc_parameter_struct.ocnidlestate 	= TIMER_OCN_IDLE_STATE_LOW;

With those changes the PWM works as expected, all polarity are correct, including 0 and 100%

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

@Candas, I noticed a bug in your code here

The function _isChannelEnabled does not return a boolean, but the register value in the channel position (so 1, 16, 256 and 4096 depending on the channel). I did it to speed up the execution, there's no point shifting bits just to get a 0 or 1 result, all that matters is 0 or not zero

If you prefer to have an if statement, use

if (_isChannelEnabled(timer_periph, channel1) != 0) // disable timer channel only if enabled to avoid glitches

(I didn't put one because it was not needed: there's no glitch disabling an already disabled channel, unlike enabling it... but yours is safer, as long as you use != 0)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

good morning from Germany :-)
@robcazzaro , your last comment is 4 hours ago and gd32_mcu.cpp changed 6 hours ago. But i do not see what you want to be changed. There is already if (_isChannelEnabled(timer_periph, channel1) != 0)

I tested with that latest code and motor indeed spins as smoothly as "my" gen2.x firmware with

  // choose FOC modulation (optional)
  //motor.foc_modulation = FOCModulationType::Trapezoid_150;
  //motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
  motor.foc_modulation = FOCModulationType::SinePWM;

SpaceVectorPWM also works nicely and i do not see or hear a difference to SinePWM
Both modulations draw about the same current of 160 mA at 26 Volt just like the gen2.x binary.

Here my one-liner for testing backward/forward (5 seconds to go from zero to +-max):

  float fSpeed = 5.0 * (ABS(	(float)((millis()/50+100) % 400) - 200) - 100)/100;
  //fSpeed = 5;
  motor.move(fSpeed);

A target of 5 generates about the same speed as speed = -320; with TEST_SPEED of my gen2.x code.

The motor.foc_modulation = FOCModulationType::Trapezoid_150; is very loud for a target (speed?) of 2,
gets more silent for 3 but at 5, the motor blocks and i fearfully quickly override the binary to esacpe a blocked motor.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Thanks a lot @robcazzaro , I did the changes. But platformio really behaves in a weird way. It's not always using the driver code I changed locally.
When I published and refreshed, the polarity changes triggered shorts, so I reverted back.

While searching I notice this motor control code, it's using functions to init the structure properly, I did to be on the safer side.

I also remove the channel enabling code from the driver init, so we use driver.enable() for that.
@RoboDurden , I added your one liner but with a smaller speed.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

I think having several environments for different boards was creating a mess.
I still had the C6 related dependencies although I had removed the board for platformio.ini.
I deleted those folders manually and simplified the platformio.ini.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Lastly I switched to sinePWM, trapezoidal is really too noisy.
The target goes from -5 to 5. Higher is possible if you increase the voltage limit.

I tried removing the pin initialization code here to see if the code here is good enough, but it didn't work anymore. The arduino-gd32 code probably has to be checked.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Thanks a lot @robcazzaro , I did the changes. But platformio really behaves in a weird way. It's not always using the driver code I changed locally. When I published and refreshed, the polarity changes triggered shorts, so I reverted back.

Now that I see "the polarity changes triggered shorts" I finally started realizing that the MOSFET circuit in the hoverboard might be different from the usual SimpleFOC drivers.

For reference, this is the waveforms I was trying to achieve for a PWM of 30%, with CH1 being the positive signal and CH2 the complementary one

GD32-30

But according to your note, that seems to cause shorts. Can one of you please send me the working waveform for 30% PWM (or any non 0 or 100% PWM), using the same CH1 CH2 assignments? I want to make sure I can check the signals properly going forward.

I'll also look at the pin initialization code and add a function or macro to properly calculate the dead time (which, incidentally, I verified and a value of 60 is indeed 1250 ns)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

With working waveform you mean the full candas code not with my one Liner but a static target of something like 2.0 ?

I am not sure if we will see some nice static pwm for a rotating motor ?

I only have a 1 channel pocket dso.
I would like to probe phase a to phase b without the motor connected. Then I expect a positive voltage and a negative voltage depending on hall inputs and rotation direction..

For two dso channels of one timer channel with it's hiside and low side gate outputs I fear you must wait for candas to return from holidays.

I am still looking for a 2 channel pocket dso on AliExpress for $50 :-/

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

To my understanding, the 40+14V gate driver voltage of the high-side mosfets is "somehow" generated by a charge pumpe driven by the pwm of the low-side mosfets. So without a motor connected, i may not see a lot when probing phase A to phase B.
You can look at the schematics pdf of the gen1 board, found on the EFeru FOC repo. The gen2.0 boards without half-bridge driver chips seem to use the same analog circuit with 3 transistors for each mosfet.
But you are probing the GD32 output pins don't you ? On your bluepill maybe without pull-down resistors..

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Sorry I checked on the scope but forgot to record it.
I was basically getting the same signal twice.

Now I am out but I will check tomorrow if I have time. I fly only on Friday.

I haven't swapped the phases because the motor was smooth in sinepwm, svpwm, and in simplefoc you have either to swap the pins or change this.

I guess next on the to-do list could be:

  • derive the phases from the pins in the call to BLDCDriver6PWM so people could swap the phases if needed, this could probably be used
  • use the deadtime parameter from simplefoc
  • check how the pins are set in BLDCDriver6PWM

I am not sure working on software6pwm would be really useful for now

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

The target goes from -5 to 5. Higher is possible if you increase the voltage limit.

5.0 is way more slowly than the 1000 of the gen2.x firmware which i think is 100% pwm.
What should be the values to test max speed ?

Unfortunately, my one liner needs an offset because the setup() function takes so long that the motor no longer start from zero:

unsigned long iLoopStart = 0;
void setup()
{
  ......
  iLoopStart = millis();
}

void loop()
{
  float fSpeed = 5.0 * (ABS(	(float)(((millis()-iLoopStart)/50 + 100) % 400) - 200) - 100)/100;

Not very intuitive

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Don't think that my 1-channel scans are helpful:

gd32 yellow hi side and lo side mcu outputs: https://youtu.be/0w15tCuFyrE
yellow hi-lo pa8-pb13

gd32 phase difference blue yellow with 10x probe: https://youtu.be/uHkZAgpiEuQ
blue-yellow phase difference 10x probe

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Thanks @RoboDurden, this is good. So that means that, indeed, the complementary signal is high when the output is high, which is the opposite of what I was trying to achieve (based on the standard STM32 for SimpleFOC). 🤦‍♂️. Apologies about that, but I'm glad we solved it

Just to be clear: was this with the SimpleFOC version, or your old firmware? Would be good to see what your old firmware did. Also, where did you capture the phase difference on the board?

I tried with the original firmware, but unless everything is connected, it doesn't work, just beeps. And I can't reassemble everything, I don't have all the pieces anymore, so I won't be able to test. But if your motor is turning, and the board not burning, we must be on the right path 😁

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

I looked at the STM32 hoverboard schematic and the EFeru code, and indeed I was wrong on the polarity. The high phase goes thru an extra inverter transistor, so the outputs must be both high or low to properly drive the bridge, apologies for wasting your time on this.

Here's the STM32 timer init code from EFeru's repository

  sConfigOC.OCMode       = TIM_OCMODE_PWM1;
  sConfigOC.Pulse        = 0;
  sConfigOC.OCPolarity   = TIM_OCPOLARITY_HIGH;
  sConfigOC.OCNPolarity  = TIM_OCNPOLARITY_LOW;
  sConfigOC.OCFastMode   = TIM_OCFAST_DISABLE;
  sConfigOC.OCIdleState  = TIM_OCIDLESTATE_RESET;
  sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET;

Both the OC and OCN polarity and idle state must be set opposite of what I did (and like it's in the code now)

@Candas1 I noticed that there is still a bug in the PWM ON/OFF code.

That line must be "!=0" not "!=1"
if (_isChannelEnabled(timer_periph, channel1) != 0) // disable timer channel only if enabled to avoid glitches

It does work anyway, given that the function never returns 1 😁 so the code is the same as without the if statement. And turning off the same phase multiple times has no negative side effect. But, to save execution time when a phase stays disabled, having "!=0" would be better.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

@robcazzaro i do not understand a lot about these low level timer functions. That is mainly a talk between you and candas.

Yes i will make the same dso test tomorrow with my gen2.x firmware. These two test up here have been made with this Candas1/Split_Hoverboard_SimpleFOC here.

The second test was putting gnd of the dso to the outlet of yellow phase, the probe of the dso was held to the middle phase cable. The motor was still connected and spinning +-5.0

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

Don't worry guys, we are all learning, and that's why we need to use power supplies.
@robcazzaro You are spending a lot of effort with this project and will not benefit if you don't have the real hardware. Let's do something about that

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

so here the dso comparison between the simpleFOC firmware and the gen2.x binary: https://youtu.be/T1nndQ1UpqM

The gen2.x firmware does a rect wave when not spinning the motor, which i think is needed for layouts without dedicated gate driver chips because the rectangle wave form for the low-side mosfet drives a charge pump to generate the 40+14V to drive the hi-side mosfets. But i may be wrong about that.
The simpleFOC code at least seem to have some 10% duty spikes when not spinning the motor and that could be enough to generate the 54V. But i may be wrong about this also.
Quite hot here in Germany and i have had little and bad sleep the last three days. Will return to my trainsation today.

gd32 gen2 x yellow hi-side
gd32 gen2 x yellow lo-side

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Thanks for the additional screenshots

Methinks that both the gen2 firmware and SimpleFOC send power to the motor to keep it in place, powered, and prevent movement when speed is 0.

Only when freewheeling the motor phases are all off. When the motor is static, I'm sure that SimpleFOC keeps the phases energized to prevent movement when speed is 0.

The reason why the gen2 has a square wave when not moving, is probably because they apply a much stronger force to hold them motor, while with the settings we have now, SimpelFOC only applies a weak current to hold the motor. So gen2 uses roughly half the voltage for each phase, while SimpleFOC uses probably10-15% of the voltage. Changing the torque settings in SimpleFOC would increase that PWM value, and get to a square wave, too

Easy to verify: try moving the wheel by hand when powered on and not rotating, and you should feel a string resistance to movement, stronger in gen2 than SimpleFOC

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Easy to verify: try moving the wheel by hand when powered on and not rotating, and you should feel a string resistance to movement, stronger in gen2 than SimpleFOC

No, not really. With SimpleFOC, the current only rises from 30 mA (@ 26V, setting the 6 gate ouputs back to INPUT to free the motor) to 70ma with motor.move(0.0);
The motor can still be moved quite freely.
Same for the gen2 firmware. To my experience, all hoverboard firmwares do not apply a constant torque on the wheels when only driven in pwm-mode. There is no closed loop to keep a certain speed or torque or position.

And for sure the not changing 50% duty square wave on hiside and loside of the gen2 with speed = 0 must cancel each other out, otherwise some uncontroled current would flow.

22:03 here in Germany now and i only have a 3W led lamp here in my solar powered train station. Too dark to probe the gate pins now.
I think the simpleFOC generates a 10% duty pwm on hi and low at motor.move(0.0); that also cancel each other out. And that 10% duty pwm might be sufficient to drive the charge pump.

Maybe you can fully understand how that C1 capacitor is driven to generate the 14+40V:

hoverboard mosfet half bridge

When the lo-side mosfet is closed (conducting), C1 is charged, when it is open, its voltage adds to the middle point of that half bridge (= source of hi-side mosfet) and the gate of the hi-side can be driven by that voltage.
But a pwm has to be applied to the lo-side mosfet at all time, i think.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

Got it, thanks for the additional info!

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

SimpleFOC has a very good documentation, this can help understand how it works.

Sorry guys I couldn't check anything and I leave soon.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

@Candas1 , @robcazzaro , is the gd32_mcu.cpp now already good enough that i could begin with master-slave uart communication and i2c control that would replace my Gen2.x repo ?
Or do we first want to continue with lo-side current sensing and full FOC ?

I would be happy to delete my Split_Hoverboard_SimpleFOC original and this one here from Candas becomes the lead.
Then i could fork it to add master-slave via pull request while you two guys still work on the completion of the simpleFOC port.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

In my opinion, it's good enough to be used, and should already be as good as the motor control in gen2 firmware?
What do you think @robcazzaro ?

I haven't tried debugging after the recent changes, I would still not do it without a power supply.
We will still improve the GD32 code, but it shouldn't improve the pwm signal itself.

Now we need to make a better use of simplefoc.
Next release of simplefoc will also bring some improvements.
The current sensing for foc shouldn't be too complicated but not all the boards have that.

We could create a list of tasks, agree on the priorities, align on the dependencies not to impact each other. Like a real project 😂

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

I started to list some ideas here.

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Just for the record, here the pwm for target 0 at the yellow lo-side gates for Gen2.x and this SimpleFOC repo here:
gen2 0 yellow_low Gen2 x motor move(0) gen2 0 yellow_low simpleFOC motor move(0)
I guess the lower duty cycle of the simpleFOC library does not make a difference for the charge pump :-)

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

It could be this is happening because I kept the voltage_limit low to play it safe for the tests. limits.png

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

If we do not set the voltage limit, it will be equal to the power supply voltage, so the duty cycle should be 50% with target 0 as the modulation is centered
https://github.com/Candas1/Arduino-FOC/blob/d9051562df093e10b6e30943e254dd5d758df1bd/src/drivers/BLDCDriver6PWM.cpp#L61

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Indeed yes :-)

  driver.voltage_power_supply = 26;
  driver.voltage_limit = 26;

produces the same 50% duty square rect at target speed 0 :-)
Will this then test max speed ?

float fSpeed = 26.0 * (ABS( (float)(((millis()-iLoopStart)/50 + 100) % 400) - 200) - 100)/100;

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

I think so

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

But the max speed is already reached at about 12.0. Setting it higher will only make the motor spin longer at the max of 12.0. So either that is the max or there is a clamp somewhere in the library.
Max current is then slightly above 0.5A so i increased it to 1.0 A CC.

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

That's weird. And the max duty cycle is 100%, do you know the max speed you reach in rpm?

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

for that i would need to get the uart debug output working so i can log the rpm.
The Gen2.x at speed 1000 definitely spins faster an the current is still below 500mA (about 480 mA).
The simpleFOC code draws more current (about 550 mA) and spins more slowly :-/

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

You could try simplefocdebug and monitoring that I added recently

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

In my opinion, it's good enough to be used, and should already be as good as the motor control in gen2 firmware? What do you think @robcazzaro ?

Yes, the initialization code is robust and safe to use, I'll add the few missing things (as per your spreadsheet) soon, but none makes a real difference for now

We could create a list of tasks, agree on the priorities, align on the dependencies not to impact each other. Like a real project 😂

Yes, good idea. Please feel free to assign any low level tasks to me as a default. I'm much more useful working at that level, and you both are much more knowledgeable about the motors and their control

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Here another dso test that compares the voltage differences of Gen2.x vs SimpleFOC between pahse blue and yellow at max speed: https://youtu.be/DFzkf_X7WHU

The dso output should reflect the current flowing through the blue-yellow windings and be proportional to the speed ?!
But i do not really see a difference between Gen2.x and SimpleFOC:
gd32 simpleFOC vs Gen2 x - max speed

Both binaries produce these double pulses also at max speed. I guess that is okay because we have a vector addition of the three sets of coils, and even at max speed, one set must vary its current to achive a rotating vector.
The red horizontal lines is a voltage difference of zero = no current flowing.
I notice that the possible (i guess) max current of 90+% duty and 10% no current is never reached but that the 10% off must induce a sligtly opposite current that i guess cancle out some of the 90% current :-(

But this is only 1/3 of the motor coils, so the 90% duty cycle overlaps with green-blue and green-yellow anyway.
And again, i do not see a difference to the simpleFOC ouput.
But motor is definitely spinning more slowly.

When i click on Custom->Update_SimpleFOC that succeeds.
But Custom->Update_gd32 fails , because of my twowire.cpp changes from my other GD32_I2C_Slave project :-/
Don't know how to fetch the latested Arduino-GD32-Core :-(

Processing GD32F130C8 (framework: arduino; platform: https://github.com/CommunityGD32Cores/platform-gd32.git; board: genericGD32F130C8)
------------------------------------------------------------------------------------------------------------------------------------------------------------Verbose mode can be enabled via `-v, --verbose` option
CONFIGURATION: https://docs.platformio.org/page/boards/gd32/genericGD32F130C8.html
PLATFORM: GD GD32 (1.0.0+sha.3424e66) > GD32F130C8 (8k RAM, 64k Flash)
HARDWARE: GD32F130C8T6 48MHz, 8KB RAM, 64KB Flash
DEBUG: Current (stlink) External (blackmagic, cmsis-dap, jlink, sipeed-rv-debugger, stlink)
PACKAGES:
 - framework-arduinogd32 @ 4.20000.210603+sha.d0cf857
 - toolchain-gccarmnoneeabi @ 1.90201.191206 (9.2.1)
LDF: Library Dependency Finder -> https://bit.ly/configure-pio-ldf
LDF Modes: Finder ~ chain, Compatibility ~ soft
Library Manager: Installing Arduino-FOC @ 2.3.0+sha.d905156
Warning! Could not find the package with 'Arduino-FOC @ 2.3.0+sha.d905156' requirements for your system 'windows_amd64'
Found 14 compatible libraries
Scanning dependencies...
Dependency Graph
|-- RTT Stream @ 1.4.0
|-- Simple FOC @ 2.3.0+sha.d905156
Building in release mode
pio pkg update -g -p gd32
Platform Manager: [email protected]+sha.3424e66 is already up-to-date
Tool Manager: Updating framework-arduinogd32 @ 4.20000.210603+sha.d0cf857
git version 2.39.2.windows.1
error: Your local changes to the following files would be overwritten by merge:
        libraries/Wire/src/Wire.cpp
Updating d0cf857..dfa7ccb
        libraries/Wire/src/utility/twi.cpp
Please commit your changes or stash them before you merge.
Aborting
Error: VCS: Could not process command ['git', 'pull', '--recurse-submodules']
*** [Update gd32] Error 1
================================================================ [FAILED] Took 5.94 seconds ================================================================
 *  The terminal process "C:\Users\PAN CF-LX6\.platformio\penv\Scripts\platformio.exe 'run', '--target', 'Update gd32', '--environment', 'GD32F130C8'" terminated with exit code: 1. 
 *  Terminal will be reused by tasks, press any key to close it. 

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

@RoboDurden to update only the GD32 Arduino framework To update, use a PlatformIO core CLI and execute

pio pkg update -g -p gd32

Also, please note this part in your error message

Updating d0cf857..dfa7ccb
        libraries/Wire/src/utility/twi.cpp
Please commit your changes or stash them before you merge.
Aborting```

If you have made changes to some of the libraries, you can't update them unless you either check-in your changes or discard those changes (Platformio/VSCode allow you to discard the changes with a right click menu)

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

thanks. How do i stash on the cli ?

PS C:\GitHub\Candas1\Split_Hoverboard_SimpleFOC> pio pkg update -g -p gd32
Platform Manager: [email protected]+sha.3424e66 is already up-to-date
Tool Manager: Updating framework-arduinogd32 @ 4.20000.210603+sha.d0cf857
git version 2.39.2.windows.1
error: Your local changes to the following files would be overwritten by merge:
        libraries/Wire/src/Wire.cpp
        libraries/Wire/src/utility/twi.cpp
Please commit your changes or stash them before you merge.
Aborting
Updating d0cf857..dfa7ccb
Error: VCS: Could not process command ['git', 'pull', '--recurs

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

No idea, sorry. In cases like these I simply copy the files to a temp location on my disk, discard them and update. If needed, I manually merge the files by copying the relevant lines in the IDE. Not very elegant, I admit 😁

I never took the time to learn how GIT commands work from Platformio. But it's all here https://docs.platformio.org/en/stable/integration/ci/github-actions.html

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

Thanks @robcazzaro , after removing C:\Users\PAN CF-LX6\.platformio\packages\framework-arduinogd32\libraries\Wire the update succeeded :-)

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

@RoboDurden if you want to discard changes, you can do so from the UI, too, much easier than chasing the right files on disk.

image

If you right click on the file name itself, it also offers more options (like discard changes)

From that UI it's easy to see what needs to be changed to unblock the updates, and decide what to do

from split_hoverboard_simplefoc.

RoboDurden avatar RoboDurden commented on July 25, 2024

the poor motor behavior of the SimpleFOC binary is still the same :-/
Maybe someone of you discovers a difference in the dso ouputs shown in my latest video.
Good night for today from a rainy and stormy Germany :-)

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

In the past, I had problems with SimpleFOC due to the limited speed of the encoder readings. The Arduino interrupt handling code has a lot of overhead, made worse by the various processor layers. If the code handling the hall sensors is not fast enough, speed is limited by that. And we are using a 48MHz processor, pretty slow all considered.

I don't have time today, though. Over the weekend, I'll look at ways to speed up the interrupt handler and see if that improves anything.

from split_hoverboard_simplefoc.

robcazzaro avatar robcazzaro commented on July 25, 2024

BTW: we should open a new issue every time we discover a problem like this one. Otherwise things become hard to follow. The motor performance is not a timer issue 😉

from split_hoverboard_simplefoc.

Candas1 avatar Candas1 commented on July 25, 2024

In the past, I had problems with SimpleFOC due to the limited speed of the encoder readings. The Arduino interrupt handling code has a lot of overhead, made worse by the various processor layers.

There is some improvement in the next release simplefoc/Arduino-FOC#270

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.