Gooser: a 4-in-1 Lepton derivative

The boards have arrived! But the capacitors and connectors from LCSC may not be here for another week, so I can’t do any testing yet.

Nonetheless I have been preemptively writing the firmware. The most amusing problem I’ve discovered is that I should have called the motors M0-M3 instead of M1-M4, since the code is naturally zero-based. But I think it’s too much hassle to change at this point, since I’d want to rename all hall sensor and current sensor nets to match.

I found one minor hardware problem. I assumed there would only be one 100nF 0402 capacitor on the JLC basic parts list and used the first one I saw, but it turns it was only rated for 16V. Only the input snubber is exposed to high voltage, so that’s no problem to swap out on my boards while I’m soldering the ones on the back, and I’ve switched them all to the 50V version in EasyEDA.

The ADC configuration was fun. It’s much easier if you read the reference manual (rm0440 for this chip) to see how the hardware works rather than trying to understand it from the library interface. On Lepton I got so mad at the hideously cluttered LL and HAL libraries that I just wrote my own register #defines, but actually the official #defines for direct register access are reasonably well done so I’m using them this time. The DMA section of the manual is not entirely clear on how to set up for auto-triggering by ADC, so hopefully I did it right.

The general approach is to start the sampling for the next motor just before updating the current motor, so the next motor’s update will have recently-measured data ready to go without any waiting for the ADC. The ADC data is read by DMA into a circular array and then sorted out by using the pin numbers in the InlineCurrentSense and LinearHall classes as indices into that array.

/*
Current sense pins, phase A,B
M1 PB14 PB12 adc1 ch 5 11
M2 PF1 PA4   adc2 ch 10 17
M3 PB11 PB15 adc2 ch 14 15
M4 PA0 PF0   adc1 ch 1 10

Encoder pins
M1 PC4 PB2 adc2 ch 5 12
M2 PA2 PA3 adc1 ch 3 4
M3 PB1 PB0 adc1 ch 12 15
M4 PA6 PA7 adc2 ch 3 4
*/
LinearHall sensor[4] = {
  // Pin numbers are actually are indices into adcData[] (see ReadLinearHalls and ADC sequence config)
  LinearHall(3, 1, 6),
  LinearHall(4, 6, 7),
  LinearHall(10, 8, 7),
  LinearHall(13, 15, 7)
};
InlineCurrentSense currentSense[4] = {
  // Pin numbers are actually indices into adcData[] (see _readADCVoltageInline and ADC sequence config)
  InlineCurrentSense(15.0f/3.3f, 1.0f, 0, 2), // M1 and M2 have 15 amp sensors
  InlineCurrentSense(15.0f/3.3f, 1.0f, 5, 7),
  InlineCurrentSense(31.0f/3.3f, 1.0f, 9, 11), // M3 and M4 have 31 amp sensors
  InlineCurrentSense(31.0f/3.3f, 1.0f, 12, 14)
};

volatile uint16_t adcData[16];

void ReadLinearHalls(int hallA, int hallB, int *a, int *b) {
  *a = adcData[hallA];
  *b = adcData[hallB];
}

float _readADCVoltageInline(const int pin, const void*) {
  return adcData[pin] * (3.3f/16384.0f);
}

void setup() {
  RCC->AHB1ENR |= RCC_AHB1ENR_DMAMUX1EN | RCC_AHB1ENR_DMA1EN;
  RCC->AHB2ENR |= RCC_AHB2ENR_ADC12EN;
  RCC->CCIPR |= RCC_CCIPR_ADC12SEL_0; // ADC use PLL clock
  ADC1->CR = ADC2->CR = ADC_CR_ADVREGEN; // Enable voltage regulator
  delayMicroseconds(20); // Voltage regulator startup time from STM32G431 datasheet

  // Configure ADC to read one motor's halls and current sense per trigger event
  ADC12_COMMON->CCR = 6 | ADC_CCR_MDMA_1 | ADC_CCR_DMACFG; // Dual mode regular simultaneous, enable DMA (2 bytes per sample, circular)
  ADC1->CR = ADC2->CR = ADC_CR_ADEN | ADC_CR_ADVREGEN;
  ADC1->CFGR = ADC_CFGR_DISCEN | (ADC_CFGR_DISCNUM_0); // Each ADC reads two values per trigger
  ADC1->CFGR2 = ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR_1; // 4x oversample, giving 0-16384 range
  #define ADCSQ(idx, ch) ((ch) << ((idx)*6)) // More concise than the ADC_SQRx_SQy #defines
  // Note: SQR1 low bits specify the number of conversions
  // Note: ADC1 and ADC2 can't convert the same channel number at the same time
  ADC1->SQR1 = 8 | ADCSQ(1,5) | ADCSQ(2,11) | ADCSQ(3,1) | ADCSQ(4,10); // M1,M4 current
  ADC1->SQR2 = ADCSQ(0,3) | ADCSQ(1,4) | ADCSQ(2,15) | ADCSQ(3,12); // M2,M3 hall
  ADC2->SQR1 = 8 | ADCSQ(1,11) | ADCSQ(2,5) | ADCSQ(3,3) | ADCSQ(4,4); // M1,M4 hall
  ADC2->SQR2 = ADCSQ(0,10) | ADCSQ(1,17) | ADCSQ(2,14) | ADCSQ(3,15); // M2,M3 current
  DMA1_Channel1->CCR = DMA_CCR_CIRC | DMA_CCR_MINC | DMA_CCR_PSIZE_1 | DMA_CCR_MSIZE_1;
  DMA1_Channel1->CNDTR = sizeof(adcData)/4;
  DMA1_Channel1->CPAR = (uint32_t)&ADC12_COMMON->CDR;
  DMA1_Channel1->CMAR = (uint32_t)&adcData;
  DMAMUX1->CCR = 5; // ADC1 (reference manual RM0440, page 420, table 91)
  ADC1->CR = ADC_CR_ADSTART;
...
}

void loop() {
  for (int i = 0; i < 4; i++) {
    while(!(ADC1->ISR & ADC2->ISR & ADC_ISR_ADRDY)){} // Make sure this motor's hall and current sense values are ready
    ADC1->CR = ADC_CR_ADSTART; // Start ADC for next motor
    motor[i].loopFOC();
    motor[i].move();
  }
}

Although I’ll need to use a different configuration during calibration since I won’t be able to keep requesting conversions during that. I think just setting ADC1->CFGR = ADC_CFGR_CONT will do it. That should loop through the whole sequence as quickly as possible until told to stop.

2 Likes

Hi,
would it be OK to use only three motors, or will your ADC sampling be hardcoded?
I still hope I could run two motors on one shaft, but that’s probably too difficult. (four motors but three sensors, NAH )
(calling motor.move can only be done for one motor at a time for now?)

Of course you can use fewer than 4 motors. As-is it will waste a few microseconds sampling the pins for the unused motors, but unless you want to use those pins as digital I/O then there’s no real need to change the ADC configuration.

Although come to think of it, one of my “stretch goals” was to make SPI available using the hall pins of two motors. I forgot about it and only SPI1 MISO/MOSI are available on M4. SPI3 MISO/SCK are available on the UART pins, but no complete sets anywhere. Not a problem for me, but sad that it limits other potential uses for the board.

Not sure what you mean by this? The main loop is calling move on all 4 motors.

For your dual-motor idea, I think you’d initialize both drivers but leave the second BLDCMotor unused. Then call driver->setPwm(Ua, Ub, Uc); on the second driver using the voltages from the active motor. Or if the two motors aren’t perfectly synchronized, then you could update the first one like normal, call linkDriver with the second driver, call setPhaseVoltage again but with an offset applied to the electrical angle, and then link back to the first driver.

1 Like

That’s my concern: each motor has it’s own line
motor1.move(target1)
motor2.move(target1) (same target for dual motor axis)
…then the next motor.
There is always a small delay between two hard-coupled motors.

I doubt the delay would be a problem when the motors are only mechanically connected. Most of the time you’ll be advancing the stator field in the direction the motor is moving, so if one stator is lagging a few electrical degrees behind for a few microseconds between the setPwm calls, it will just be contributing less torque, but not fighting against the other. I don’t think you’d want to run angle/velocity PID on them separately or they really could fight eachother, so you will need to customize the main loop for this application.

Connecting a single motor to two drivers would be much more difficult. You’d have to get the timers synchronized within ~100ns or there would be times where the two drivers have opposite mosfets on and short out.

1 Like

Looks good, so you plan to drive all motors, are you expecting 4 pwm inputs coming to the mcu!!. I have a use-case where i intend to receive 4 pwm inputs and drive 4 bldc motors.
I was thinking of using STSPIN32G4 + DRV8300 to drive 2 bldc motors and then another set of STSPIN32G4+ DRV8300 to drive another set of motors.
Looking at your Design it seems G4 is capable of driving all 4 motors in 1 go.
BTW from firmware point of view for a single motor pwm input + bmef monotoring + VBAT_sense is what i would be monitoring.

I considered STSPIN32G4+DRV8300 as well, but gave up pretty early in the PCB layout process. It was looking like the per-motor board size would be significantly larger than Gooser. It would have significantly higher voltage rating to make up for it, but I don’t need it.

I have made some more progress. No spinning yet, but all appears to be well so far.

Soldering the capacitors on the back took a couple hours. I used a toothpick to apply paste, tweezers to pick up the tiny things, and a needle to nudge them precisely into place.



Then place them on whatever scraps of aluminum I had lying around, and cook them until the solder turns shiny. I should have gotten it better centered because the aluminum hanging off the side of the burner seemed to be wicking heat away.

I’d say I got a touch too much solder on the small capacitors and a touch too little on the large ones, but good result overall.

Then add the programming connector, some temporary battery/motor/encoder wires (and a jumper wire to the 3V regulator input, which is fine when only running one motor’s worth of hall sensors), and a couple 820uF capacitors. None on M1 and M2 because I need clear access to all the encoder solder pads there. This board will be running two 2208 motors and two tiny 1404 motors, so 2146uF total is probably enough.


I made a terrible mistake, getting solder on one of the holes for the board-to-board connector along the edge :slight_smile: That will be a pain to get opened back up so I can solder the pins. I filled all the other holes intentionally since I’ll be soldering wires flat to them.

Software-wise, so far I only have it communicating over UART. I had to program the boot bits, but did not need the BOOT0 touch pad (which is good since I didn’t have room for it on the buck converter version). Correct configuration is nSWBOOT=0, nBOOT0=1, to boot from main flash memory.

It crashes if more than two drivers are initialized. I think it’s a limitation of SimpleFOC’s timer pin configuration code. I’ll have to go digging tomorrow to find out how to bypass that and set them up directly.

EDIT: It’s a heisenbug. It crashes somewhere in the recursive function findBestTimerCombination, but if I try to track down the exact location of the crash by peppering the code with Serial.print calls with delays after them to make sure the text gets to the monitor, all 4 drivers initialize just fine.

I don’t see any reason why it shouldn’t work. SIMPLEFOC_STM32_MAX_PINTIMERSUSED is 12, which is how many I need. And according to the printout, it never gets more than a few levels deep on the recursion, so no stack overflow.

EDIT2: At long last, I’ve found it!

int scoreCombination(int numPins, PinMap* pinTimers[]) {
  // check already used - TODO move this to outer loop also...
  for (int i=0; i<numTimerPinsUsed; i++) {
    if (pinTimers[i]->peripheral == timerPinsUsed[i]->peripheral
        && STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(timerPinsUsed[i]->function))
      return -2; // bad combination - timer channel already used
  }
  ...

pinTimers[i] reads off the end of the array. It only has 3 entries for 3PWM, whereas i goes up to 11 with 4 motors. Off to github to make a report…

1 Like

I quite like your hightech reflow plate setup.

I’ll have to try that to see if I can swap the FETs on one of my dead qvadran boards.

I set this aside for a few days to work on other projects after dealing with that frustrating bug, and now immediately ran into another one. Open loop modes are not working. I’m not sure if it’s a problem with the timer configuration or what, but for some reason the drivers aren’t outputting correct voltage. Calling driver->setPwm and measuring the motor wire pads relative to ground, the measured voltage does change in proportion to the command, but on a sort of exponential curve rather than linear. It ramps up very slowly until reaching 0.2V around 98% duty, 0.4V at 99%, 1V at 99.2%, and then jumps to 7V at 99.3%, and no further change to 100%. The battery is 7.4V nominal, but charged to 7.7V at the moment, so the maximum output is still lower than it should be.

Any ideas? I’m not sure how to go about debugging this. I’m using Generic G431CBUx in Arduino IDE. F_CPU reports 170MHz, so I think the CPU clock is configured correctly. The program is stripped down to the minimum to be sure nothing else is going on:

#include <SimpleFOC.h>

BLDCDriver3PWM driver[4] = {
  BLDCDriver3PWM(PA8, PA9, PA10),
  BLDCDriver3PWM(PA5, PA1, PB10),
  BLDCDriver3PWM(PB4, PB5, PB7),
  BLDCDriver3PWM(PB6, PB8, PB9)
};

void setup() {
  Serial.setRx(PC11);
  Serial.setTx(PC10);
  Serial.begin(115200);
  Serial.println(F_CPU);

  for (int i = 0; i < 4; i++) {
    driver[i].voltage_power_supply = 7.4;
    driver[i].pwm_frequency = 25000;
    driver[i].init();
  }
}

void loop() {
  static float v = 0;
  driver[0].setPwm(v, 0, 0);
  if (Serial.read() == 'V') {
    v = Serial.parseFloat(); Serial.print("Set voltage "); Serial.println(v);
  }
}

You’re measuring the phase outputs with no motor connected, right?
With the oscilloscope?

How about the PWM signals going into the driver, are they correct?

No oscilloscope, just regular multimeter. And no motor connected. I don’t know about the PWM signals going into the driver. I’ll try configuring the timer directly via hardware registers so I know for sure that it’s set up right and see if there’s any difference.

I’d take a peek with the oscilloscope first. If the PWM is generated then it’s likely to be a hardware driver issue. Maybe its protections don’t like it when no load is attached?

If the PWM is also not correct then it’s likely a software error.

Ok, I used an ESP32 with OLED display to probe the PWM pins, and it looks like the duty is correct, but frequency is 50KHz instead of 25. This is the ESP32 code:

#include <Arduino.h>
#include <Wire.h>
#include <U8g2lib.h>

U8G2_SSD1306_128X64_NONAME_F_SW_I2C u8g2(U8G2_R0,22,21,U8X8_PIN_NONE);

void setup() {
  u8g2.begin();
  pinMode(27, INPUT);
}

void loop() {
  while(digitalRead(27));
  long startTime = micros();
  int index = 0;
  char value[128];
  while(index < 128)
    if (micros() > startTime + index * (2000000.0f / 25000.0f / 128.0f))
      value[index++] = digitalRead(27);
  
  u8g2.clearBuffer();
  for (index = 0; index < 128; index++)
    u8g2.drawPixel(index, 32 + value[index] * 4);
  u8g2.sendBuffer();
}

It waits for the start of a PWM cycle, records two cycles worth of data, and then prints to the screen. But it was actually showing 4 cycles. I tried setting driver.pwm_frequency = 12500; and then it shows two cycles. The multimeter still shows the same sort of voltages on the motor pads so I don’t think this is the ultimate issue, but is another mystery to be solved.

I have previously tried it in open loop velocity/angle modes with a motor attached and got no movement and similar multimeter measurements, so I don’t think it’s a driver protection issue, unless I’m misunderstanding the datasheet and have it configured for 6PWM and it’s trying to prevent switching both mosfets on at the same time. I have the mode pin connected to GVDD as specified here:


And e.g. TIM1_CH1 is connected to both INHA and INLA.

I double checked all the other pins and they are wired up properly. And all drivers give similar measurements, so if it is a routing error, it’s one that I made consistently.

EDIT: Maybe this driver will not operate without gate resistors? The very similar FD6288Q used on Lepton doesn’t seem to care, but maybe this one is able to detect it. I hope not, because I don’t have room for resistors or for the diodes that FD6288Q needs.

The way I read this Datasheet that can’t work :frowning:

The MODE pin controls the polarity of the output, but the input is always active high.

So if you control both FETs of a half bridge from the same pin, the result is always Hi-Z - both FETs off.

For what you want you need a 3-PWM driver…

I wish I’d noticed this earlier but I haven’t used the drv8300 myself yet…

Hmm, I don’t quite follow… you mean if the polarity is inverted, it will somehow produce a negative voltage on the output when input is high? I read it to mean inverting the phase, but the output is still either equal to GND or GVDD voltage. There’s a diagram on page 15:

Hmmmm… ok, you’re using the DRV8300DRGE with 24 pins, like shown in the schematic?

Then the mode pin controls only the output polarity:

And on these device types the input is always active high (also on page 15):

So the timing diagram you show with an nINL input only applies to the 20 pin packages 8300DI and 8300NI:

At least that’s how I read the datasheet, but I admit its quite unclear.

I think it just means the 20-pin packages have the mode hardwired, whereas 24-pin has the mode pin to select inverting or non.

The only question is the meaning of the word “polarity”. I don’t see how it could generate a negative voltage, and the text in your image from page 15 mentions phase, so I think it is the correct behavior for 3pwm. Input high on both pins will switch the high side mosfet on and low side off. Input low on both pins will switch high side mosfet off and low side on. No way to switch both off at the same time for hi-z/freewheeling, but I never needed that capability on Lepton anyway.

In digital circuits the polarity of the signal is whether it is active high, or active low.

In a way, it is similar to the phase, in the sense that a the same signal, when negated, now has the opposite polarity and can be considered to be “out of phase” (because it is the same signal, but opposite).
But phase also refers to the shift (delay) between two signals, and is therefore related to the phase angle in three phase systems, etc… so I find it clearer to talk about the “polarity” when discussing the switching states (on off) of a half bridge.

So in particular for gate drivers, the input polarity determines whether the input is “active high” (input high state means FET is logically switched ON by driver) or “active low” (input low state means FET is logically switched ON by driver).

On the output side, you have the output polarity. This is independent from the input polarity. It determines whether the ON state for the FET is achieved by a high level gate drive output (VCC or VBST) or low level gate drive output (GND). Because depending on whether you are switching N-FETs or P-FETs the ON-state can be achieved with opposite gate drive polarity…

Note there are no negative voltages involved here.

So the drivers often specify whether the outputs are “in phase” with the inputs (meaning they have the same polarity) or “out of phase” with the inputs, meaning opposite polarity on the output from the input.

Its all a bit complicated so often a truth table helps:

image

The orange highlighted states are the only ones you’re using. It results in the gate drive switching on the low side, or disconnected (Hi-Z).

I’m still not seeing where you got that truth table. The datasheet says nothing about the GHx/GLx pins having a Hi-Z state. They are either ON or OFF. Hi-Z only describes the output of the half bridge, i.e. the motor wire solder pad, if both mosfets are switched off at the same time. So it should look like this:
TruthTable

However there is one more bit of ambiguity: when is the cross conduction prevention enforced?

At the top it says this driver is for N-FETs only, so I would expect cross-conduction to be when both GHx and GLx are ON (the lines I marked “bad” in the truth table). However on page 14 it says it turns off both outputs if both inputs are logic HIGH at the same time.


That would make sense if the inverted polarity mode was for driving one N-FET and one P-FET, but for N-FETs I don’t see how inverted mode could ever do anything useful in that case. And the diagram I posted before shows GHx being ON when both inputs are HIGH, so I still think inverted mode is intended for 3pwm.

Ok, you have convinced me. So the two states you are using should be working the way you want.

That brings us back to the question why they are not, despite receiving what looks like correct PWM signals?

How about the mode pin? You have it tied to GVDD in the schematics which also looks correct.

Is it perhaps a problem that in the configuration you have the inputs have both pull-up and pull-down on them?

Or the problem lies somewhere else entirely…