Programming the Lepton from start to finish

Does it maybe become more noticeable in some situations, like when turning very slowly?

Update on the Lepton testing: I’ve hooked up a motor, and tested different SPI sensors.

I could not make it work well with the SC60228 so far, although I did get the sensor working with the dev branch code (which has some bug-fixes compared to the release version) and by changing SPI Mode. Not sure what the problem is, TBH.

I then tested it with the MA330, and it seems to be working quite well. Tuning the PID without commander is a pain though. With the settings I have right now on an eMax GB4008 (66KV) turns well enough, draws hardly any power in velocity mode, and get it up to 75rad/s at 15V, that’s with about 3.5kHz loop speed…

More tomorrow.

2 Likes

Do you think Deku’s interpolator might help with loop speed? Sorry I haven’t gotten anything done recently… tomorrow I can experiment further to try to solve the baffling problem with the shaking stuff. My first stop will be a different sensor and magnet positioning approach, I bought an AS5048B. Or maybe I will try adjusting the distance of the magnet from the sensor… Or experiment to see if I can ascertain the cause of the variation between the pole pair check in the commander sketch and the pole pair check sketch… Probably switching out the sensor and magnet and magnet holder is the fastest way to get answers.

Well no wonder it didn’t do anything, that code was total nonsense :stuck_out_tongue: Hopefully this one is not so bad:

class SmoothingSensor : public Sensor
{
public:
  SmoothingSensor(Sensor *s, const FOCMotor *m):wrappedSensor(s),motor(m){}

  float getVelocity() { return wrappedSensor->getVelocity(); }
  int needsSearch() { return wrappedSensor->needsSearch(); }

  float getMechanicalAngle() {
    return enable_smoothing == false ? wrappedSensor->getMechanicalAngle() : _normalizeAngle(
      wrappedSensor->getMechanicalAngle() + motor->shaft_velocity * (_micros() - wrappedSensor->angle_prev_ts) / 1000000.0);
  }

  float getAngle() {
    return enable_smoothing == false ? wrappedSensor->getAngle() :
      wrappedSensor->getAngle() + motor->shaft_velocity * (_micros() - wrappedSensor->angle_prev_ts) / 1000000.0;
  }
  
  double getPreciseAngle() {
    return enable_smoothing == false ? wrappedSensor->getPreciseAngle() :
      wrappedSensor->getPreciseAngle() + motor->shaft_velocity * (_micros() - wrappedSensor->angle_prev_ts) / 1000000.0;
  }

  int32_t getFullRotations() {
    float angle = getAngle();
    return (angle - _normalizeAngle(angle)) / _2PI;
  }
  
  void update() {
    if(sensor_cnt++ < sensor_downsample) return;
    sensor_cnt = 0;
    wrappedSensor->update();
  }

  bool enable_smoothing = true;
  unsigned int sensor_downsample = 0; // parameter defining the ratio of downsampling for sensor update
  unsigned int sensor_cnt = 0; // counting variable for downsampling

protected:
  float getSensorAngle() { return wrappedSensor->getSensorAngle(); }
  void init() { wrappedSensor->init(); }
  
  Sensor *wrappedSensor;
  const FOCMotor *motor;
};

First of all, I had the parentheses in the wrong place in the getAngle calculation.
Second, the delta time was in microseconds and needed to be divided by 1000000.
Third, loopFOC uses electricalAngle, which uses sensor->getMechanicalAngle and thus was getting the un-smoothed value.

Since getAngle is ultimately only used in angle mode and I was testing in velocity mode, it really wasn’t doing anything at all.

It does seem to work now. It’s able to achieve about 25% higher speed, 150rad/s versus 120rad/s without smoothing. 2208 motor rewound from 13T delta 1450kv to 11T wye so theoretically 990kv. Voltage limit is set to 1, so speed should be 990*2pi/60=103rad/s. 120 without smoothing implies 1147kv, 150 with smoothing implies 1433kv. When tuning voltage-based torque control without smoothing, I ended up on 1400kv giving the best behavior. I need to try measuring kv using the method of spinning it with a drill and measuring the AC voltage on the terminals and see how that compares.

It seems to need different PID tuning with smoothing turned on. This time with smoothing disabled I ended up on P0.1, I1.0, D0, and angle P20. That seems to give good behavior in velocity and angle mode. But with smoothing enabled, angle mode was a little choppy. P0.05, I0.1, D0, angle P5 seems to work well.

There is an audible difference between smoothing and not. Without smoothing, I can hear a sort of chirpy tone when the motor is spinning, one chirp for each hall state change. With smoothing, that goes away for the most part but I still hear it intermittently. And I can feel it in my hand holding the motor as well, slight skips in the smooth motion. Much less after the PID re-tuning, but still there. Without smoothing, the motion is consistent but always has that slight vibration of torque ripple due to hall sensor commutation.

EDIT: Measured back EMF with drill, 412mV versus 286mV for a different one that still has the original 1450kv winding. That means 1007kv, so pretty close to the calculated value. And since I have voltage_power_supply set to 7.4 but my battery is actually charged to 8.1V, that means I’m driving it at 1.095V, which should give 115.5rad/s. So the un-smoothed hall sensor commutation is just about spot on, and smoothing must be projecting the angle out ahead of where it should be and doing some field weakening.

2 Likes

@dekutree64 , that’s awesome - can we add it to the drivers library? There’s already been interest in it as you know…

@Anthony_Douglas I’ve actually made board files for the Arduino IDE for the Lepton now.

image

This is compiling for me now.

The problem is, unlike with PlatformIO where I can share a project containing everything needed for a new board to github, and you can just download and use that project, for ArduinoIDE this stuff happens in the platform files.

So I’m actually unsure how to get it to you. Short of sending STM32duino a pull-request, them merging it, and you waiting for the next platform release, it seems that everything else is going to be some kind of kludge. :frowning:
If anyone has any suggestions I’d love to hear them. I’ll also ask the stm32duino people if there is a method…

Certainly. But do include a note that it has had minimal testing. And you might change SmoothingSensor::getFullRotations() to just call wrappedSensor->getFullRotations() like I had it before. Technically getFullRotations()*_2PI+getMechanicalAngle() should give the same value as getAngle(), so I had to calculate it by the inverse of that incase the smoothing offset crosses the wraparound point. But I doubt anyone is actually using it in a way that it matters, and as it is I think it may be off by 1 sometimes due to the float to int conversion truncating rather than rounding.

And to update on the field weakening effect mentioned in my previous post, I think it’s specific to hall sensors. Each hall state change jumps 60 electrical degrees instantaneously, but the smoothed value will have gradually advanced through those degrees during the same time, meaning that on average it’s 30 electrical degrees ahead of where it should be.

EDIT: Also, SmoothingSensor won’t work with HallSensor at all as is. HallSensor needs to be edited to use angle_prev_ts instead of pulse_timestamp. Give me a bit more time before you integrate it. I’ll see if I can come up with an elegant way to eliminate the field weakening effect…

EDIT2: I remembered we live in the future and the standard library has rounding functions now. So this should give fully correct results:

  int32_t getFullRotations() {
    float angle = getAngle();
    return lroundf((angle - _normalizeAngle(angle)) / _2PI);
  }

As for the other issue, one potential approach would be to add a phase advance setting in FOCMotor:

float FOCMotor::electricalAngle(){
  // if no sensor linked return previous value ( for open loop )
  if(!sensor) return electrical_angle;
  return _normalizeAngle( (float)(sensor_direction * pole_pairs) * sensor->getMechanicalAngle() +
    phase_advance * _sign(shaft_velocity) - zero_electric_angle );
}

That will give user control of field weakening with any kind of sensor, as well as the ability to correct this particular problem. It’s fun to play with. 0.5 (~30 degrees) gives around 145rad/s with un-smoothed halls, so it looks like my theory was correct. 0.8 (~45 degrees) almost makes it to 160 rad/s :slight_smile:

Ok, I think I’ve gone about as far as I’m going to with this thing. I think angle mode is better off without it, but velocity mode is better with it. Maybe adding second order approximation (estimate the acceleration from velocity history) would get angle mode working better too.

I made a new thread to avoid monopolizing this one any further, and so it’s easier for people to find in the future. See the updated code there: SmoothingSensor: Eperimental sensor angle extrapoltion

Hey,

I have pushed Arduino Board files for the Lepton:

If you follow the install instructions of this repository (isn’t hard) then you will have the Lepton available as a board in ArduinoIDE, and things like Serial, I2C and SPI should just work.

If anyone decides to try it out, please let me know how it goes.

It took me a bit longer than anticipated because Arduino IDE is a pain. But now its working I think I can add more boards fairly quickly.

We’ll add more boards as we go along, I guess it only makes sense once they have a certain popularity.

2 Likes

I’ll give it a try within a few days, hopefully, I am still using the b-G431b-esc1 board because it has enough memory for my experimenting and stuff, but maybe I can at least use the leptons I had made. If they work ok I might roll with them for a bit but I don’t want to get more made because I want to use whatever everyone else is using, and I think the lepton’s memory is too small for it to catch on, however it’s great start and I feel like if you are going to put the effort in to make the files I should contribute by at least testing them, which takes much less time and expertise ;)…

edit:
I actually got inspired and gave it a quick try. The first issue is that the folder for the boards must be different for windows installs, and you must be using Linux or something. The folder for windows appears to be something in the region of: C:\Users\anthony\AppData\Local\Arduino15\packages

replace anthony with your own username.

However I don’t know for sure that is the right folder, it may be a subfolder or something. When I unzip to that location and start the ide, in the tools> board menu it now has an entry for simplefoc-main-stm32 bah blah or something. fairly long name that could be more clear…
Then within that there is a simplefoc board, which is perhaps the shield, and then there is one with a very long name that doesn’t display correctly which is probably the lepton? From looking at the directory structure of the stuff that was unzipped, I’m guessing so.

however, in the windows arduino, you have to select the board from the drop down in the main window, too. When I try to do that, the board with the long name is not there.

If I select the Simplefoc board, which does show up in that list, nothing works :(. I checked that the upload by SWD is enabled etc.

I think most of these problems stem from the differences between the linux arduino ide and the windows one.

I can keep trying more later, but am pretty baffled and it’s getting late.

edit: looks like my test file had an error in it, it seems to compile and upload, and Serial seems to work if you select the SimpleFOC board on the second in-window menu :slight_smile: I don’t know if this is the right board, or if it is just a coincidence that it works and thus if other features will work or what, but it is some progress :). I just uploaded a file that prints to Serial to see if Serial worked, I haven’t tried any of the other stuff yet, but will later :).

Lepton should be 64kb, not 32 as listed in that board file. This one: STM32G031G8U6 STMicroelectronics | C432211 - LCSC Electronics

Looks like I’ll need to update my IDE and STM32 library before I can test it… I’m still on IDE v1.8.

What all was involved in making it? I never was able to figure out what I was supposed to do. Are the files in variants/SIMPLEFOC_LEPTONG031 edited from the ones in packages\STMicroelectronics\hardware\stm32\2.3.0\variants\STM32G0xx\G031G(4-6-8)U_G041G(6-8)U, or created some other way? And is there a template for boards.txt, or do you just start with the monster packages\STMicroelectronics\hardware\stm32\2.3.0\boards.txt and strip it down to one definition, and edit from there?

Read this https://docs.arduino.cc/software/ide-v1/tutorials/PortableIDE
I find it much nicer to have the packages and libraries all in with the IDE itself. For example mine is C:\Arduino\portable\packages

No, that’s the application’s data folder. You can put it in there somewhere too, probably, but it’s supposed to go in your user Sketchbook folder, in the hardware subfolder. By default, the Sketchbook folders are located here:

image

Hmmm… Arduino IDE builds this name from the folder name “simplefoc_arduino_boards” and the architecture name “stm32”.
I’ll add a note to the instructions to rename the cloned folder to something shorter.

The shields don’t have on-board MCUs so they won’t be part of the board files.

Hey that’s great!

could you send a screenshot of what your menu you looks like?

You should have “SimpleFOC Boards” as the Board name, and then there is a Submenu (“Board Part Number”) which has the Lepton as the only choice ATM:

image

image

I’ve now changed that 32kB in the menu item name to be 64kB, thanks Deku! It was just in the label, the board definition used 64kB.

It was such a headache because Arduino IDE caches stuff internally and you have to restart it 1000 times (or at least, I don’t know how to re-initialize it).
But yeah, you copy a lot of stuff from the generic variant and adapt it. And the board.txt follows the same format as the main framework’s so you can copy things and adapt from there too…

1 Like

There was definitely no \hardware folder, I checked thoroughly. They changed a lot of stuff in the latest update for arduino apparently. Will get those screenshots later yeah, I’m on the wrong computer now. Actually I have arduino on this computer too, an older version, and I checked and there is no hardware file there either C:\Users\User\Documents\Arduino . Searched, put the folders in alphabetical order and searched manually, definitely not there, not hidden or anything.

Fair enough, if the hardware folder is not there, you can just create it. I’ve updated the docs to mention that :slight_smile:

Thanks for being part of the “test subjects” for this…

ok cool. BTW if anyone else wants a lepton let me know, me and Runger are the only ones that actually have any at this point so I feel kind of obligated…

here is a screenshot, probably it’s because of the wacky folder structure, I will try correcting it

Yeah, if you shorten the folder name to just “simplefoc” the menu will look better.

As for the “arduino-select-board” menu item, no idea what is up with this, it seems to be something the IDE puts there automatically… I have it too, and could not really figure it out.

It turns out there is a problem with the lepton’s waveform generation, even in open loop. There appears to be a thump about once per revolution. The waveform flakes out, I confirmed it in a couple different ways. I thought it was some kind of mechanical defect in my fan at first, that’s why I didn’t realize what was going on.

It appears to be worse when I compile code on my desktop. I reset the libraries, and it still is. I noticed my desktop gives the following error when compiling and uploading on arduino, after following the board install proceedure:
Warning: Board simplefoc:stm32:build doesn’t define a ‘build.board’ preference. Auto-set to: STM32_BUILD

In orange letters. I think maybe some peripheral is configured slightly differently and this has something to do with the thumping noise.

The G431 board doesn’t do it as far as I can tell. I hypothesize some calculation occurs when things wrap around and this causes the thump. Either I have to try to get in there and fix the problem with the code or I have to use the G431 board and can’t use the Lepton. I will have a look at the code but… This is a real downturn for me because I really don’t want to have to go through designing my own G431 based board.

The thump occurs even when I restrain the fan from actually moving or put the voltage down so low it can’t move on it’s own. So it’s definitely an interruption in the waveform.

edit: ok, looking at the code, I think it might be when the shaft_angle = _normalizeAngle(shaft_angle + target_velocity*Ts); happens on line 677 of BLDCmotor.cpp. Normalize calls fmod, floating point modulo.

The noise takes a while to build up when I start rotation, I think this may be because the division takes longer when the angle is larger? I think shaft_angle accumulates, rather than wrapping around.

Thus, perhaps the floating point hardware is not working properly on the Lepton? Man, I haz no clue how to solve such a problem :(. If only I can get open loop mode working at least.

Oh geeze it’s an M-0 cortex, right? they don’t even have floating point hardware? https://ww1.microchip.com/downloads/en/DeviceDoc/90003178A.pdf

Yeah the G431 thing has floating point hardware https://www.google.com/url?sa=t&rct=j&q=&esrc=s&source=web&cd=&cad=rja&uact=8&ved=2ahUKEwii1v2Zg-n9AhUcmYkEHY5LBA4QFnoECBEQAQ&url=https%3A%2F%2Fwww.st.com%2Fen%2Fmicrocontrollers-microprocessors%2Fstm32g431cb.html&usg=AOvVaw1IG0vpnrQS1R11KanU9eqJ

Ah shit.

Update: well I don’t see how I could make the code in the library work any better, which is no surprise. It doesn’t look like there is much stuff that could take time. There is just a handful of floating point modulo things and I don’t see anything that could explain the increase over time, shaft angle doesn’t increase in perpetuity in openloop mode apparently, it does appear as though it would wrap around and the cycle just begin again. it happens just as well with trapezoidal drive, so it’s not the stuff in setphasevoltage or whatever. I follow the flow of the program and don’t see how it could flake out or stall like that.

Edit: ok, I realized the G431 board also does it, it’s just not as loud. Oh shit. Ok so not a floating point issue. Just a bunch of code that takes too long once per revolution… I really don’t see anything.

edit: I made a last ditch effort, and it actually worked. I figured something else is messing with shaft_angle at some point, and just replaced it with a static variable that stays inside the velocityopenloop function.

it now reads:

// Function (iterative) generating open loop movement for target velocity
// - target_velocity - rad/s
// it uses voltage_limit variable
float BLDCMotor::velocityOpenloop(float target_velocity){
  // get current timestamp
  static float other_shaft_angle = 0;
  unsigned long now_us = _micros();
  // calculate the sample time from last call
  float Ts = (now_us - open_loop_timestamp) * 1e-6f;
  // quick fix for strange cases (micros overflow + timestamp not defined)
  if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;

  // calculate the necessary angle to achieve target velocity
  other_shaft_angle = _normalizeAngle(other_shaft_angle + target_velocity*Ts);
  // for display purposes
  shaft_velocity = target_velocity;

  // use voltage limit or current limit
  float Uq = voltage_limit;
  if(_isset(phase_resistance)){
    Uq = _constrain(current_limit*phase_resistance + fabs(voltage_bemf),-voltage_limit, voltage_limit);
    // recalculate the current  
    current.q = (Uq - fabs(voltage_bemf))/phase_resistance;
  }
  // set the maximal allowed voltage (voltage_limit) with the necessary angle
  setPhaseVoltage(Uq,  0, _electricalAngle(other_shaft_angle, pole_pairs));

  // save timestamp for next call
  open_loop_timestamp = now_us;

  return Uq;
}

Man, what a roller coaster. So stressful. Progress is possible, it just always takes so long. Only open source makes this kind of rectification of issues possible.

Probably the above modification broke all kinds of stuff, idk.

Strange. The only thing that modifies shaft_angle during normal operation is the call to shaftAngle() in BLDCMotor::move (line 339). And that only modifies it if there is a sensor linked. And the call is skipped in open loop mode. Is something writing off the end of an array somewhere? Memory corruption bugs are hard to track down.

Ok so as mentioned I got the G431 board working better, but I just tried the lepton just now. It’s still borked. I think it might sound a bit different but… I don’t know how it could make such a difference with the G431 board and not the lepton. Maybe it does have something to do with floating point.

edit: shit. Now it’s back with the g431 board. It was fine. I tested it for a solid ten minutes to be sure.

Did you try to run the CORDIC on the G431 like we just configured?

I’m just curious to how that would run?

I really think you should use the MT6835 over the I2C based sensor. Maybe that will solve the noise thing…