Candas1 / Split_Hoverboard_SimpleFOC

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

please join and help us :-) #1

Open RoboDurden opened 1 year ago

RoboDurden commented 1 year ago

Hi @Candas1 , @robcazzaro i guess the candas fork should now be the place of activity and indeed the old https://github.com/RoboDurden/Hoverboard-Firmware-Hack-Gen2.x/issues/11 needs seconds to load on my mobile data plan.

@RoboDurden Do you know if the emergency stop is really connected on this layout? If yes it will act as an overcurrent trigger and stop the pwm output. It would only be a matter of enabling This with the right polarity and would be safer.

[EDIT] And probably setting PB12 properly

I can probe PB12 with a dso to see if it offers analog or digital input. But according to your spreadsheet https://docs.google.com/spreadsheets/d/15msbDAIMxC2rIkq8Au8vf82ub1qEaS67Lc1cFb86Jpc/edit#gid=0 "sed on some of the boards as overcurrent trigger when the dc current is high enough to turn a transistor ON. Should disable PW" i need to find that transistor and see if i can verify an analog input there while putting a hand on the motor with my gen2.x firmware running.

But according to the 2.0 schemtaics, PB12 is functional: current measure pb12 gen2 0

With the mosfet only driven by the shunt voltage, it should open slowely and indeed produce some analog value on PB12 when some strong current reaches the the gate threshold.

This sketch is already using 91% of the flash, the GD32F130C6T6 have really little memory. I wasn't able to add the serial commander for example, it was exceeding the size.

I checked the photos of the various layouts. Only 2.1 and 2.5 have a C6 mcu. The others have a C8 with doubled flash and ram = 64 kB flash and 8 kB ram. (2.2 has K8 which only has less pins)

So to get all features running i think for now it is okay to compile with the C8 enviroment :-)

Candas1 commented 1 year ago

Hi @Candas1 , @robcazzaro i guess the candas fork should now be the place of activity and indeed the old RoboDurden/Hoverboard-Firmware-Hack-Gen2.x#11 needs seconds to load on my mobile data plan.

@RoboDurden Do you know if the emergency stop is really connected on this layout? If yes it will act as an overcurrent trigger and stop the pwm output. It would only be a matter of enabling This with the right polarity and would be safer. [EDIT] And probably setting PB12 properly

I can probe PB12 with a dso to see if it offers analog or digital input. But according to your spreadsheet https://docs.google.com/spreadsheets/d/15msbDAIMxC2rIkq8Au8vf82ub1qEaS67Lc1cFb86Jpc/edit#gid=0 "sed on some of the boards as overcurrent trigger when the dc current is high enough to turn a transistor ON. Should disable PW" i need to find that transistor and see if i can verify an analog input there while putting a hand on the motor with my gen2.x firmware running.

But according to the 2.0 schemtaics, PB12 is functional: current measure pb12 gen2 0

With the mosfet only driven by the shunt voltage, it should open slowely and indeed produce some analog value on PB12 when some strong current reaches the the gate threshold.

This sketch is already using 91% of the flash, the GD32F130C6T6 have really little memory. I wasn't able to add the serial commander for example, it was exceeding the size.

I checked the photos of the various layouts. Only 2.1 and 2.5 have a C6 mcu. The others have a C8 with doubled flash and ram = 64 kB flash and 8 kB ram. (2.2 has K8 which only has less pins)

So to get all features running i think for now it is okay to compile with the C8 enviroment :-)

OK I could try to set it up and we could test by pulling this pin high. Base on your screenshot it would be useful only in case of short circuit/very high current, but it's still useful.

Candas1 commented 1 year ago

To do: Note the zero_electric_angle after sensor alignment, and feed it with initFOC to skip the alignment

I think the sensor.update in the loop is redundant, it's already in the loopFOC

RoboDurden commented 1 year ago

Still tidying up. I have removed the i2c beginning (that you got when forking my repo) and uploaded the final i2c test code here: https://github.com/RoboDurden/GD32_I2C_Slave

Things like zero_electric_angle after sensor alignment are totally new to me as i only debugged the HallSensor. Will need some time to safely get your nice repo running.

With the simple motor mode i guess position control would be nice to have next. Then adding I2CCommander would already allow to use multiple gen2 boards to build a robot arm. Something the gen1 firmwares are not made for. And FOC efficiency would not be that important for using the bldc as a servo motor.

@Candas1 , maybe try not to quote a full response to keep this issue as short as possible. It will grow vastly anyway :-)

Candas1 commented 1 year ago

To be honest, I didn't mean to fork your repository and take over. I wanted to save time building up on what you already did. My changes could also be pulled to your repository and you could continue from there.

RoboDurden commented 1 year ago

It is an honor for me that you did fork my code witht the little CIO class and my debug macros. I guess more low level gd32 specific code has to be debuged and updated so it might be best when the work continues here.

RoboDurden commented 1 year ago

Unfortunately, my first gen2.0 burned with your code :-/

That can happen :-)

Maybe i should have enabled this emergency stop first ? I stepped through the entire setup (F5, F11, F10) to see your code. When everything looked okay at the end of setup() i hit F5 to let the loop lose. Then the motor made one step forward and one step backward and smoke started to come from somewhere on the board.

Now both mosfet of the green phase have a short over all three pins. and the low-side mosfet of the middle phase blue has a short from sorce to drain but gate still isolated.

Now i need to unsolder the mosfet and find replacements. With these analog gate drivers i can only test the low-side without a new mosfet built in because the high-side needs to low-side and the bldc connected to generate the +14V gate voltage for the high side.

I guess the driver class should have a protected mode that ensures that no low-side and high-side open at the same time ? I fear that happened for the left green phase. The burn of the middle low-side then i fear must have happend because the bldc phases were connected.

Maybe some kind of dry run would be nice were the 6 gate driver pins are mapped to something like the 5 leds ?

I did compile and run the C8 enviroment. But in the past it made no differece for the board to upload a c6 or c8 binary.

As i mentioned, i am embarking on a 1-2 week journey tomorrow, so i guess i will not proceed a lot today but start packing. Maybe i can replace the mosfet today or find some to do it on the journey. Bit I still have a second board on my test setup :-)

Candas1 commented 1 year ago

That's exactly what I want to prevent. Have you tried the code initially without debugging ? Debugging with motor control can be dangerous, there are flags that can stop the timers when you halt the MCU.

Candas1 commented 1 year ago

Deadtime prevents both sides from opening at the same time. But It happened to me that I burned a board while debugging, I am wondering if this is what killed your board.

In Eferu's firmware I had experimented with something like that , it helped me while debugging but I am not sure if it's meant to prevent issues. I will check with Rob if he has experience about that

RoboDurden commented 1 year ago

Yes i was unsure if first debugging was a good idea. But then i decided that sooner or later i would want to debug anyway. If have unsoldered the two mosfest from the green phases. The other two phases seem to be okay. The short cut from low-side blue must have been because of the motor connected. Even if i do not find replacement mosfets (don't know if i have them here in my train station), i will try to flash the gen2.x binary, it should at least show some sloppy turning with two phases. Than even without replacements, the board could be used to kill the next phase mosfets :-)

RoboDurden commented 1 year ago

I have not yet looked into the driver code. But it would be good if it had a save mode where it simply checks that no mosfet is turned on when the opposite low/high side is still on. Does the driver class blindly sets gates to high without checking that ?

Candas1 commented 1 year ago

It's not working like that. You set a pwm duty cycle, complementary channels and deadtime, the MCU handles the rest. It will never turn both ON at the same time.

I made sure this code runs with conservative values and is not triggering CC mode of my power supply.

RoboDurden commented 1 year ago

I tested the board without the 2 mosfet of phase green but then both mosfet of blue burned. Don't know if your firmware was still active. i think i am done for today. At this stage i would not want to simply test my second board. We should find some test setup where the 5 leds and tx from uart1 are used as the 6 gate driver pins.. And then some idea how to test with a single channel dso if there is an overlap of some gate outputs.

Is it possible to add a debug interrupt that logs digital reads the gate output while the pwm interrupt is doing its work ?

RoboDurden commented 1 year ago

An yes, i should have used the little 3A constant courrent power supply i have here in my train station: https://www.aliexpress.com/item/4000549476335.html I forgot you warned me to use a battery :-)

Candas1 commented 1 year ago

Yes that's the reason why. But I am disappointed now, I will check what could be wrong. Sorry about this.

RoboDurden commented 1 year ago

I think I already found another 2.0, but the led headers are a different. The chip layout seems to be identical: Gen2 01

robcazzaro commented 1 year ago

@RoboDurden when building the code in Candas repository, by mistake I used the wrong SimpleFOC and ended up using the STM32-specific code for SimpleFOC (GD32 elsewhere). Platformio takes some time to upload the libraries referenced by Platformio.ini and if you start compiling too quickly after downloading it, it might pick up the wrong library and use the STM32 code for SimpleFOC

A way to test which code is used, is to put a breakpoint in the file gd32_mcu.cpp.c, in the _configure6PWM() function and see if it gets called. Or adding a debug print in that function

The MOSFET pins are driven directly by the timer outputs and if the timer is properly programmed, it should never set both high at the same time. Unless there is a stray piece of code that redefines the GPIO pins along the way.

As soon as my boards arrive, I can safely test this as well, using a logic analyzer to ensure that the complementary pins are never high at the same time

RoboDurden commented 1 year ago

As i did step into all new setup functions i did see the new gd32_mcu.cpp.c code from Candas1 :-)

My one board is done. after unsoldering the next pair, i can power the board with that simple CC power supply and the 5V and 3.3V cascade is working. But the MCU does not respond to the ST-Link anymore. So the the mcu on board seems to be broken.

But i have tested the second board with my gen2.x firmware and my Split_Hoverboard_SimpleFOC from which you did fork. So i am ready to burn the next board. But that should happen after we have gotten some idea of why my first board was killed and find some save_mode without the true gates being driven - i suggest.

I am used to blow up things :-)

robcazzaro commented 1 year ago

The safest way to understand what happened is to use a Bluepill with a GD32, attach a logic analyzer to the 6 outputs and set a trigger that triggers if the complementary outputs are both high. Then let it run in all conditions. If there is a stray GPIO code, it will catch it.

With a logic analyzer or scope, it's also possible to see if the deadtime is too small for the MOSFETs used. With an insufficient deadtime (and a battery capable of hundreds of amps), it's possible to overheat MOSFETs. Which is also why having a power supply with current limiter is a good idea, as we have just been reminded :)

If the timer is properly programmed, the MOSFETs are "protected in hardware", so to speak, and no bug can cause issues. Alas, the way the code works, it's not possible to set a timer to work without actual outputs from GPIOs, so I can't see a way to test the code and prevent the GPIOs connected to the MOSFETs to be driven...

RoboDurden commented 1 year ago

My single board test setup with 25V max 3A constant current driven by one of my 7s E-Bike batteries: PXL_20230615_181512688_copy_2016x1512

Candas1 commented 1 year ago

I added here some calculations, that can be useful.

The current deadtime in the gd32 driver(60 clock cycles) is actually same as what simpleFOC is using by default (2% of the PWM cycle). 1250ns is plenty. Eferu's deadtime is only 750ns.

In the past I had managed to blow all the mosfets of a splitboard in one go, I had set a target value in debug mode, the value was too high and there was no ramp.

But in this repository the target is really low. Still I need to add a ramp/filter.

robcazzaro commented 1 year ago

@Candas1 looking at the code, the deadtime set function is commented out. That's the one we discussed over email, using the STM32 macros to set the non-linear value in the register

So it looks as if at the moment there is no deadtime in the timer, which would explain the problems.... I think I sent you the snippet of code to replicate that STM32 function (but could not test it yet)

Candas1 commented 1 year ago

No no it's there but it's a macro. We need a formula later to use the parameter from simplefoc.

robcazzaro commented 1 year ago

Oh, I see... you are using 60, which as you say it's 1250 ns. Would be worth double checking with an oscilloscope (I can do it, as soon as I have my boards)

The math is pretty complicated, given that it depends on the clock divider (0, 256 or 512), the CPU clock, and the register has a non-linear effect on the actual deadtime. I did send you the STM macro with all the needed definitions to make it work, let me find it and copy it here

#define TIM_CR1_CKD_Pos           (8U)
#define TIM_CR1_CKD_0             (0x1UL << TIM_CR1_CKD_Pos)                   /*!< 0x00000100 */
#define TIM_CR1_CKD_1             (0x2UL << TIM_CR1_CKD_Pos)                   /*!< 0x00000200 */

#define LL_TIM_CLOCKDIVISION_DIV1              0x00000000U          /*!< tDTS=tCK_INT */
#define LL_TIM_CLOCKDIVISION_DIV2              TIM_CR1_CKD_0        /*!< tDTS=2*tCK_INT */
#define LL_TIM_CLOCKDIVISION_DIV4              TIM_CR1_CKD_1        /*!< tDTS=4*tCK_INT */

#define TIM_CALC_DTS(__TIMCLK__, __CKD__)                                                        \
  (((__CKD__) == LL_TIM_CLOCKDIVISION_DIV1) ? ((uint64_t)1000000000000U/(__TIMCLK__))         : \
   ((__CKD__) == LL_TIM_CLOCKDIVISION_DIV2) ? ((uint64_t)1000000000000U/((__TIMCLK__) >> 1U)) : \
   ((uint64_t)1000000000000U/((__TIMCLK__) >> 2U)))

/* Mask used to set the TDG[x:0] of the DTG bits of the TIMx_BDTR register */
#define DT_DELAY_1 ((uint8_t)0x7F)
#define DT_DELAY_2 ((uint8_t)0x3F)
#define DT_DELAY_3 ((uint8_t)0x1F)
#define DT_DELAY_4 ((uint8_t)0x1F)

/* Mask used to set the DTG[7:5] bits of the DTG bits of the TIMx_BDTR register */
#define DT_RANGE_1 ((uint8_t)0x00)
#define DT_RANGE_2 ((uint8_t)0x80)
#define DT_RANGE_3 ((uint8_t)0xC0)
#define DT_RANGE_4 ((uint8_t)0xE0)

/**
  * @brief  HELPER macro calculating DTG[0:7] in the TIMx_BDTR register to achieve the requested dead time duration.
  * @note ex: @ref __LL_TIM_CALC_DEADTIME (80000000, @ref LL_TIM_GetClockDivision (), 120);
  * @param  __TIMCLK__ timer input clock frequency (in Hz)
  * @param  __CKD__ This parameter can be one of the following values:
  *         @arg @ref LL_TIM_CLOCKDIVISION_DIV1
  *         @arg @ref LL_TIM_CLOCKDIVISION_DIV2
  *         @arg @ref LL_TIM_CLOCKDIVISION_DIV4
  * @param  __DT__ deadtime duration (in ns)
  * @retval DTG[0:7]
  */
#define __LL_TIM_CALC_DEADTIME(__TIMCLK__, __CKD__, __DT__)  \
  ( (((uint64_t)((__DT__)*1000U)) < ((DT_DELAY_1+1U) * TIM_CALC_DTS((__TIMCLK__), (__CKD__))))    ?  \
    (uint8_t)(((uint64_t)((__DT__)*1000U) / TIM_CALC_DTS((__TIMCLK__), (__CKD__)))  & DT_DELAY_1) :      \
    (((uint64_t)((__DT__)*1000U)) < ((64U + (DT_DELAY_2+1U)) * 2U * TIM_CALC_DTS((__TIMCLK__), (__CKD__))))  ?  \
    (uint8_t)(DT_RANGE_2 | ((uint8_t)((uint8_t)((((uint64_t)((__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__),   \
                                                 (__CKD__))) >> 1U) - (uint8_t) 64) & DT_DELAY_2)) :\
    (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_3+1U)) * 8U * TIM_CALC_DTS((__TIMCLK__), (__CKD__))))  ?  \
    (uint8_t)(DT_RANGE_3 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__),  \
                                                 (__CKD__))) >> 3U) - (uint8_t) 32) & DT_DELAY_3)) :\
    (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_4+1U)) * 16U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ?  \
    (uint8_t)(DT_RANGE_4 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__),  \
                                                 (__CKD__))) >> 4U) - (uint8_t) 32) & DT_DELAY_4)) :\
    0U)
    uint32_t dead_time_ns = (float)(1e9f/PWM_freq)*dead_zone;
    uint32_t clock_div = TIMER_CTL0(TIMER_BLDC) & TIMER_CTL0_CKDIV ;    // should return 0, 256 or 512
    uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, clock_div, dead_time_ns);

And, yes, it's rather horrible :) I didn't take the time to unravel all those macros, just found a way to make them work. Incidentally, can't use it as is in the future due to the STM IP, but for now it's probably ok

EDIT: as a memo to myself to fix this, here is the relevant portion from the GD32 manual

image

Candas1 commented 1 year ago

Yes this is definitely in the todo list, the current value was just to get it to work, and it should be correct. For someone to be able to set a different "dead_zone" using the simpleFOC library, we need to use the dead_zone parameter and convert it to the value the hardware needs.

Max from Arduino-gd32 was asking here if there are expectable functions missing. I feel like this function is missing in the GD32 SPL, not the arduino layer, but we can still mention about that.

marianomd commented 1 year ago

Hi guys, regarding size optimization, I really encourage you to use bloaty. It's an outstanding tool.

Candas1 commented 1 year ago

Hi,

I tried debugging today, and even if I don't add any breakpoint and just run the code, my power supply definitely goes to CC mode. This is not happening when just flashing the firmware.

RoboDurden commented 1 year ago

Great news :-) Then I think I can try the second board without debug. my little step down LCD converter can only deliver 3A max and i will start with 1A max at 26V. I should kill the second board anyway to make place for the next split board combo :-)

Candas1 commented 1 year ago

I did small changes to this repo and to the arduino-foc one. You should pull it just in case as well.

robcazzaro commented 1 year ago

Just a quick update: I received my Aliexpress order and managed to successfully do a brain transplant: I now have a working GD32F130C8 Bluepill. I have just checked that STLink can see and program it., not tried any actual code yet.

RoboDurden commented 1 year ago

motor still stuttering and spinning very poorly after a few seconds: https://youtu.be/2OGnwagtY-U

It is the same stuttering that made my boad 1 burn after a stutter right followed by a stutter left !

@Candas1 , i did not fork your fork but cloned it with my Windows Github Desktop. I did remove the old I2C beginnings for which i by now have create a new repo. But when doing so i answered the prompt that i want to contribute to your repo. How can i make a pull request without forking your repo ?

But you can quickly remove the i2c stuff in main.cpp yourself anyway :-)

After that video i tried all three combinations of

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

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

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

But no change in motor behavior. So it seems to be a timing issue ?

It is very convenient to have my Gen2.x firmware opened with Keil so i can simply hit F8 to very quickly stop the stuttering and reflash the 2.0_master_test binary (which does nothing when the onoff button is permanently switched on). Also good to confirm that the hardware is still okay.

Now i wonder why your motor is not stuttering. But does it also run as smootly as the normal block commutation of the gen2.x firmware ?

Greetings from Germany. @robcazzaro is in the California time zone. what is your time zone Candas ? And is Candas your first name ??

Candas1 commented 1 year ago

That's not stuttering, that's the sensor alignment. If we feed initFOC with the values given by the sensor alignment, it won't happen anymore at startup.

My motor runs the same, I need to play around with the different modes.

Pull requests work only if you fork the repo.

I am from France, I am leaving close to Germany and Switzerland actually.

[EDIT] I also removed the I2C code now

RoboDurden commented 1 year ago

Maybe i or you should post my video to the simpleFOC community and someone with BLDCDriver6PWM will quickly identify the poor spinning ? But if you have some ideas to test, i will happy wait for your next changes. Good night and good luck :-)

RoboDurden commented 1 year ago

in setup() you can also remove old uart2 test code:

  int iRX0old = PA10;
  int iTX0old = PA9;

  int iRX0new = PB7;
  int iTX0new = PB6;

  int iPinRX0 = RX0;
  int iPinTX0 = TX0;

You can also search and delete the two lines with oPB6

And the two uart return to sender stuff:

  #ifdef SERIALDEBUGXX
    if (SERIALDEBUG.available()) 
    {
      while (SERIALDEBUG.available() )
      {
        SERIALDEBUG.write(SERIALDEBUG.read());
      }
    }
  #endif

and


  #ifdef SERIALDEBUG
    if (SERIALDEBUG.available()) 
    {
      while (SERIALDEBUG.available() )
      {
        SERIALDEBUG.write(SERIALDEBUG.read());
      }
      SERIALDEBUG.println();
    }
  #endif

:-)

Candas1 commented 1 year ago

Maybe i or you should post my video to the simpleFOC community and someone with BLDCDriver6PWM will quickly identify the poor spinning ? But if you have some ideas to test, i will happy wait for your next changes. Good night and good luck :-) I shared my video here already, I think it works exactly the same in your case.

I need to experiment more. I suggested some improvements here, that would make sure the phases and halls are mapped correctly, but I would need time to implement this.

robcazzaro commented 1 year ago

Unless I did something seriously wrong, I would recommend to stop using this code on a board connected to a power supply and with MOSFETs attached.

I just opened https://github.com/Candas1/Split_Hoverboard_SimpleFOC/issues/4 as a work item for myself. I'm done for the day today, will work on this tomorrow.

In order to test the PWM code, I used the PWM6 standalone driver example (below).

CH1 is connected to the H output, CH2 to the L output.

On the pins outputting 0, I see this. i.e. both MOSFETs ON at the same time (minus some spikes every ~38usec)

PWM0

On the pins outputting 1 and 3 respectively, I see

PWM1 PWM3

As you can see, the same spikes every ~38usec, which cause the MOSFETs to conduct at the same time (every now and then). Also, the pin assignment seems wrong (G and B are inverted, so what should have been the 0 output was on the B pins instead, PA9 and PB14)

With the STM32 Bluepill and the same code, everything is as expected (0, 1 and 3 in order)

STM32_0 STM32_1 STM32_3

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

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 = 3.3;
  // Max DC voltage allowed - default voltage_power_supply
  driver.voltage_limit = 3.3;
  driver.init();
  driver.enable();
  delay(1000);
}

void loop()
{
// phase B      G       Y
// pins  9-14   10-15   8-13
  driver.setPwm(1, 0, 3);
}
RoboDurden commented 1 year ago

Thank you @robcazzaro very much. I first try to understand the stm32 outputs:

setPwm

The upper image are hi-side (yellow) and lo-side (blue) mosfets conected to phase B, middle image hi and lo connected to phase G and lower image hi and lo to Y(ellow) ?

Then in about the first 30% of the full cycle i see a "negative" current flowing from phase G to B through the coils inside the motor (hi-side of B is on and lo-side of G is on). Followed by 60% of the period a current from Y to G (hi-side of Y is on and lo-side of G is on) and also the first 90% a current from Y to B (hi-side of Y is on and lo-side of B is on).

But how does that correlate to driver.setPwm(1, 0, 3); ?

These three float values could also be negative, resulting in "opposite" current flow ?

As i have not read the simpleFOC code, for me it is still a black box :-/

Candas1 commented 1 year ago

IMG_20230619_092020.jpg

That's what I see on the high side and low side of one phase. [EDIT] With the repository code

Candas1 commented 1 year ago

I think this is what @robcazzaro used. So setting the pwm for each phase.

RoboDurden commented 1 year ago

@candas1 , your photo is with the simple `driver.setPwm(1, 0, 3); test code ? The blue pill does not yet have hall inputs to test the more complex code of this repo here.

RoboDurden commented 1 year ago
 // power supply voltage [V]
  driver.voltage_power_supply = 12;
  // Max DC voltage allowed - default voltage_power_supply
  driver.voltage_limit = 12;
  // daad_zone [0,1] - default 0.02 - 2%
  driver.dead_zone = 0.05;

  // driver init
  driver.init();

  // enable driver
  driver.enable();

  _delay(1000);
}

void loop() {
    // setting pwm
    // phase A: 3V, phase B: 6V, phase C: 5V
    driver.setPwm(3,6,5);

So 3.0/12.0 = 25% duty cycle on phase A, 6/12 = 50% on the middle phase cable And 5/12 on the C = yellow cable ? All aligned to the 20khz ?? I do not understand how these 3 floats can drive the bldc..

Candas1 commented 1 year ago

This was to show that it's not happening with the repository code. I shared my results with Rob's code here

Candas1 commented 1 year ago

So 3.0/12.0 = 25% duty cycle on phase A, 6/12 = 50% on the middle phase cable And 5/12 on the C = yellow cable ? All aligned to the 20khz ?? I do not understand how these 3 floats can drive the bldc..

You provide a voltage for each phase, that simpleFOC translates to a duty cycle between 0 and 1. (voltage / supply_voltage) The duty cycle is converted to a timer pulse by the driver. ( duty cycle * range ) High side/low side is handled by the MCU using the frequency and deadtime.

RoboDurden commented 1 year ago

Thanks Candas, now I understand :-) When the voltages are set to be 1,2,6 with 12V max, then all three phases are set to high the first 1/12 of the duty cycle and no current flows. Then phase A is pull down and currents start to flow from phase b and c to a. After another 1/12*1/20000 second, phase b is also pulled to gnd. Therefore current from b to a had been 1/12 which is proportional to the voltages 1 and 2 set in setPwm :-) Phase c continues for another 4/12 and 4 is exactly the voltage difference between 2 and 6 :-) And current from C to A has flown for 5/12 of the duty cycle.which is exactly 6-1 .

Candas1 commented 1 year ago

Yes, you're setting a pwm duty cycle/voltage, but the important one is the line to line voltage, that's when the current flows.

If you are interested, I like this intro. We are not using SVWPM yet, only trapezoidal for now, but this will be relevant later.

Candas1 commented 1 year ago

The sensor alignment is weird, the motor would sometimes spin smoothly, sometimes poorly. I checked the zero_electrical_angle and direction in debug/monitoring and picked the values when it seemed to be smooth, and used it when initializing FOC. It's available with my last changes. I also tried trapezoidal 150 instead of 120 but I don't hear any difference.

robcazzaro commented 1 year ago

Just a quick update here that I solved most of the timer/PWM issues and things should work better https://github.com/Candas1/Split_Hoverboard_SimpleFOC/issues/4#issuecomment-1597999614. But a PWM value of 0 (i.e. a phase temporarily at 0V) still results in a wrong output, so it's still unsafe

Candas1 commented 1 year ago

@robcazzaro, I shared my comments and will check this evening what can be improved. I am leaving on Friday for 2 weeks and I still have to pack, so I will focus on those improvements this evening and will share an updated version. Some of this issues where already there on the original firmware, but I agree we should be as close as possible to the STM32 behavior not to have bugs with simpleFOC later.

When I come back I will be able to experiment with those boards that are using a STM32F103: image I added the layout on the spreadsheet based on this firmware. The pins for phases and halls are the same. This will help compare between GD32 and STM32 boards behavior, and find differences on the arduino or simpleFOC driver implementation.

RoboDurden commented 1 year ago

@Candas1 i do not really understand why you have removed the C6 enviroment as it should still fit in the 32 kB flash:

RAM:   [=====     ]  52.7% (used 4316 bytes from 8192 bytes)
Flash: [====      ]  44.4% (used 29116 bytes from 65536 bytes)

A usable Split_Hoverboard_SimpleFOC seems to be in reach and as we have the pin definitions of one C6 and one K6 board, i would like to do my best to support them.

The X6 mcu only has 4 general timers(16-bit) instead of 5. Is that the problem ??

P.S. If you have a grilfriend with you on holidays, you should put this simpleFOC project on halt for the next two weeks !

robcazzaro commented 1 year ago

@RoboDurden, Platformio is weird and having a dual C8 C6 setup makes everything harder now. Once we have the C8 working, making a C6 version is going to be super-easy. No point in having extra complexity now