Encoder skips pulses

I’m controlling a brushless motor with an arduino nano and a custom motor driver board. I’m using the 6PWM driver and a 600ppm encoder. I am running the motor in closed loop position control and setting the target angle to 5 rad, waiting a few seconds, then setting the target angle to -5 rad.

After a few cycles the motor draws far more current when spinning in one direction and eventually slows down and stops.
I hooked up another arduino to the encoder lines and noticed that the position of the target angles slowly drifted. I believe this is caused by the driver missing encoder pulses and the motor phase becoming missaligned with the driver phase.

I am using software interrupts as the 6PWM driver uses one of the hardware interrupt pins.

Is there anything I can do to debug/fix this?

Welcome to SimpleFOC, @varun_dixit !

You might be able to optimize it, but I’m doubtful…

Software interrupts are a bit problematic to begin with, and the Nano is a slow 8bit MCU…

If you switch to a faster 32 bit MCU my guess is it will work much better (and you probably won’t need software interrupts in the first place)

Thanks for the welcome and quick response!

I have since switched to a raspberry pi pico from your advice. The encoder inputs are now on a hardware interrupt pin.

The problem has gotten better after the switch, however I still notice that the at higher speeds, the motor slows down and draws more current before stopping completely. I am now certain that the issue is the driver missing encoder pulses.

I toggle a pin in one of the encoder pin’s interrupt function and monitiored its switching vs the encoder pin. After a while of running the motor, I noticed that the interrupt function, while usually only delayed ~10us from the encoder pin, can be delayed by over 100us after the encoder pin changes. I have also noticed it missing encoder pulses of 120us completely.

Is there anything that could be blocking the interrupt function from being called? This issue seems strange to me.

Hi,

Yes, interrupts execute one at a time and when they happen at the same time, one goes first and the other gets delayed. If it gets delayed so much that the next interrupt of the same type happens, then it can be skipped entirely, I believe. I’d have to dig into the details of the Pico Datasheet to say for sure, as MCU types can differ in the way they handle interrupts.
But for sure it is possible to overload any MCU with interrupts and cause them to become unreliable.

On the other hand the Pico is a fairly fast MCU, so I have to say I am surprised you can overload it with encoder interrupts. Perhaps it is due to some other interrupt routine, for example involved in SPI, Serial comms or similar?

I think the problem may be related to the way the Encoder class is implemented: the current implementation receives the interrupt call, but “doesn’t trust it”. Instead, it checks again the state of the pin within the interrupt routine. However, if the interrupt is delayed, the pin state may no longer correspond to the one that generated the interrupt - and the encoder class “miscounts” even though the interrupt was received.

We could try to remove this double-checking in the Encoder class - it is helpful in situations where there is noise on the encoder signals and the speed is not very high, but it does not work when speeds increase…
Out of interest, what speeds are you running at before you get problems?

Another good option might be to instead use our “GenericSensor” class and combine it with an existing Pico implementation for Encoders based on hardware, perhaps the PIO? Something like this:

Another option can be to switch MCU again - for STM32 MCUs we have a STM32HardwareEncoder class that uses these chip’s timer hardware to implement the encoder counting with no interrupts or MCU overhead…

To your advice I have switched MCU’s to the STM32f401 as the Hardware Encoder class sounded very promising. However, I am unable to get the class to work for the life of me.

The following is my code and I have verified with a scope that the encoder pulses are at the right pins.

Checking the pinout, PB6 and PB7 are connected to Timer 3 which supports encoders according to the datasheet.

#include "Arduino.h"
#include "Wire.h"
#include "SPI.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/stm32hwencoder/STM32HWEncoder.h"


#define ENCODER_PPR 600
#define ENCODER_PIN_A PB6
#define ENCODER_PIN_B PB7
#define ENCODER_PIN_I PC13


STM32HWEncoder encoder = STM32HWEncoder(ENCODER_PPR, ENCODER_PIN_A, ENCODER_PIN_B);


void setup() {
  Serial.begin(115200);
  
  encoder.init();
  _delay(1000);
}

void loop() {
  encoder.update();
  Serial.print(encoder.getAngle());
  Serial.print("\t");
  Serial.println(encoder.getVelocity());
}

The code prints only 0’s for both angle and velocity.

What am I doing wrong?

At first glance this looks good. Let me check into the code and see if I can find any problems…

One comment is to add a delay in the main loop, maybe 10ms or so? delay(10)
Otherwise this loop will execute very very fast, and flood the serial port with values.
(When you add code to control a motor, remember to remove the dalay again)

Looking at the F401CC (which one are you using?) I see PB6/PB7 on TIM4, but it looks to me like the Encoder mode of the timers on the F401 don’t support the index pin.

But the encoder code does not currently use it anyways, so it should not matter.
I assume you’re not using TIM4 also for other purposes?

Other than this I am not sure what’s happening. I will have to test it out on a F401, but I won’t be able to do that for few days as I am traveling.

I spent a while verifying my setup yesterday and I am at the same conclusion.

I briefly looked through the source code but plan to take a deeper dive into it. I found the STM32F439xx HAL User Manual had some documentation for the code that is used. Am I looking in the right place? Is there somewhere else I can look to understand the code?

By the way, I just want to thank you for your incredible support. I have never seen a project with such an active and responsive community.

1 Like

There are application notes from ST you can take a look at. It really is not the easiest thing to find documentation on…

Here are the two on timers:
https://www.st.com/resource/en/application_note/an4776-generalpurpose-timer-cookbook-for-stm32-microcontrollers-stmicroelectronics.pdf
https://www.st.com/resource/en/application_note/an4013-stm32-crossseries-timer-overview-stmicroelectronics.pdf

And I thought there was another one, but I can’t find it right now, so I’m probably confusing it with something else. I’m not at home on my main PC so I can’t check my files…

I think I should give the hardware encoder code some more love at some point soon anyway. When it works it works pretty well, and is much better than the interrupt based solution.
But it should include support for the Index pin on MCUs that can support it, and it should take into account the older generation of timers (like on F401 and F103) which don’t have Index support and don’t seem to work with the current code.

If you do figure out the problem, I would be super-grateful if you feel like posting your findings here…

Bringing this topic back up. I’ve been playing around with the STMHardwareEncoder library, trying to use it with an incremental encoder and a Nucelo F446RE. I’ve been unable to get it to work using TIM1 PWM pins, which the datasheet says supports quadrature encoders. Any suggestions on where to start with troubleshooting? Below is the code i’m using to just test the encoder without any of the motor code.

#include <Arduino.h>
#include <SimpleFOC.h>
#include "SimpleFOCDrivers.h"
#include <encoders/stm32hwencoder/STM32HWEncoder.h>

#define ENCODER_PPR 1024
#define ENCODER_PIN_A PA0
#define ENCODER_PIN_B PA11

STM32HWEncoder encoder = STM32HWEncoder(ENCODER_PPR, ENCODER_PIN_A, ENCODER_PIN_B);
long time_ms = 0;

void setup() {

  Serial.begin(115200);
  
  // initialize encoder sensor hardware
  encoder.init();

  time_ms = millis();
  
}

void loop() {

  encoder.update();

  if(millis() - time_ms > 10){

    Serial.print(encoder.getAngle());
    Serial.print('\t');
    Serial.println(encoder.getVelocity());
    time_ms = millis();

  }
}

The problem I would say is that these pins are not on TIM1.

PA0 isn’t on TIM1 at all, and PA11 is on TIM1_CH4, but for the encoder you have to use channels 1 & 2.

You can use PA8 and PA9 for encoder mode on TIM1.

If you use TIM2 you have a lot more options, including using PA0 and PA1.

@runger Thank you so much!

Using PA8 and PA9 with the STMHardwareEncoder class, I now get an upload error (“Error 1”) when flashing using PlatformIO. This seems to temporarily make the Nucleo unable to be reflashed unless I hold reset while flashing, then flash again. I can confirm using the interrupt based method works fine on those pins. Have you seen this before?

Huh, that’s weird. The pins you use should have no impact on the upload, normally.

Are you using a Nucleo F446RE board, or a different board? Are you uploading use a ST-Link?

In theory having stuff attached to pins on boot-up can cause problems if it is the BOOT0 pin or pins used by the boot loader, but normally none of this affects SWD programming.

Are you also trying to run the motor on TIM1? I think whatever timer you use in encoder mode can’t be used for motor control as well…

Is it maybe the case that you have a second instance of a Serial Monitor connected, or STMCubeProgrammer open in the background or something like this?

Hey! I’m using the Nucleo board with attached USB/stlink daughterboard. I’m uploading through that via USB. Right now I just have the encoder code and nothing else - no motor code. Nothing else is running either, just VScode.

When I tried PA0 and PA1 for the A/B inputs, the upload succeeds, but Serial printing doesnt work…odd. Anyways, this isnt critical and I know the HW encoder stuff isnt well tested at this point, so no need to try and debug unless you have similar hardware on your side and feel like doing it.

It’s strange, because its never given me any problems, but of course there are so many STM32 MCUs and pin combinations one can use…

If there is a conflict with another peripheral like serial output, or SWD, then of course that peripheral can’t work… the serial output to the ST-Link uses USART2 but I’m not sure on which pins. Of course it makes sense to check carefully there aren’t any pin-conflicts, but other than this the encoder code should not really interfere with other operations.

The code is probably not very robust, so if you feed it parameters it doesn’t like I imagine there is a chance it just crashes hard, and this can lead to an unresponsive MCU, requiring a restart.
one can usually find such cases fairly quickly though by adding some printfs to find which call isn’t succeeding.

Hello, i just want to tell about my expérience with the esp32. I rebuilded an cnc with dc motor. When i started the project simple foc had no code for dc motor. I developp the solution with the encodor code from the simple foc library, i build trapezoid wave and all what’s need. The solution run well bu it not so easy to go to a precise position and keep it. I build the solution with the arduino as ide and the version 1.x of the Espressif compiler. With a lot of work the précision of the position is very good and fast. Orders from auomate are given by modbus protocol. After fiew week i decide to do a small update but i changed the espressif compiler version to 2.07. I go to the client and forget I changed the compiler. I install the release and the machine lost the precision an is no more usable. I check all the machine, compile the version before and i was unable to restore performances. The machine lost interrupt ! At 23 o’clock i remeber a changed the compiler and restore the old one. The machine start with all performances and I can use my latest version. What’s append? Esp32 use shared interrupt and for shure somethink changed with the new compiler… but… I found esp32 has hardware counters! These counter can be used for encoder. There is a library… esp32encodor that use these hardware counter inside esp32. I have no chance to test this library until this day because the project is finished… with the old compiler… so interrupt is very good on the paper but… it’s never replace a hardware solution… Regards

@runger, have you tried using the STM32 HW Encoder with a STM32G4 processor?

I’m trying on the G431_ESC, and it doesn’t work. The digitalPinToPinName() and pinmap_function() functions cannot find PB6 alternate mapping, and return 0 (i.e. an invalid peripheral).

Once I fixed those, the timer is not properly initialized (it’s missing a HAL call to properly configure the timer. i fixed that as well, and now the encoder angle seems to work (I’m using a MT6701 in ABZ mode, 1024 cpr). I get the right readings for angle rotations.

But the getVelocity() function seems to return bogus values frequently. It might very well be that my motor still is vibrating a lot and that can throw off the sensor, so I’m not sure

I do appreciate that the code is not very robust, but I was wondering if getVelocity() is supposed to work. The code to calculate speed seems quite different from the standard quadrature encoder. Was the STM32 HW encoder based on a different version? If it works for others, I know it’s me :slight_smile:

I’ve used it successfully, but not on the G431_ESC1… is it connected to the hall inputs?

I’ve been working a lot with the STM32 timers since writing that code, so I might give it an overhaul… if you don’t first :wink:

The thing with the alternate functions I think was known - it’s a pain to make the code so general that it finds all the timer associations by itself. And in some cases it’s ambiguous when you only specify a pin, in the way Arduino likes… how should the code know which timer you want? So really the API would have to be a bit different, I guess.

getVelocity() should work, but there is no special code for handling low-speed scenarios…

Thanks for the prompt reply.

For the first issue (not finding the right timer for the PB6 and PB7 pins), the problem is in how the board variant is defined in ArduinoSTM32. in the file variants/STM32G4xx/G431C(6-8-B)U_G441CBU/PeripheralPins_B_G431B_ESC1 the definitions for PB_6 and PB_7 are commented out (for reasons I don’t understand… most pins are commented out in that file. It could be that the board has no exposed pins like a Nucleo, so the owner doesn’t expose them… even if PB6, PB7 and PB8 are used for the encoder). By removing the // only for PB_6 and PB_7, the code starts working better, but it still fails in multiple ways: the function pinmap_function() doesn’t return the correct value for Alternate (which should be 2), and PB7 returns TIM3, which is not correct either.

It seems that having a custom encoder for the B431_ESC (or at least a portion of #ifdef code) would be simpler than trying to fix the broken variant pinout definition and figuring out how to find the correct alternate configuration.

Just in case, the code below works on the B431_ESC with no changes to the ARDUINO board files (I changed only the init function), using PB6 and PB7 as A and B. No Z (index) support

#include "STM32HWEncoder.h"

#if defined(_STM32_DEF_)

/*
  HardwareEncoder(int cpr)
*/
STM32HWEncoder::STM32HWEncoder(unsigned int _ppr, int8_t pinA, int8_t pinB, int8_t pinI)
{
  rotations_per_overflow = 0;
  ticks_per_overflow = 0;

  overflow_count = 0;
  count = 0;
  prev_count = 0;
  prev_overflow_count = 0;
  pulse_timestamp = 0;

  cpr = _ppr * 4; // 4x for quadrature

  // velocity calculation variables
  prev_timestamp = getCurrentMicros();
  pulse_timestamp = getCurrentMicros();

  _pinA = pinA;
  _pinB = pinB;
  _pinI = pinI;
}

void STM32HWEncoder::update()
{
  // handle overflow of the 16-bit counter here
  // must be called at least twice per traversal of overflow range
  // TODO(conroy-cheers): investigate performance impact
  prev_count = count;
  count = encoder_handle.Instance->CNT;

  prev_timestamp = pulse_timestamp;
  pulse_timestamp = getCurrentMicros();

  prev_overflow_count = overflow_count;
  if (prev_count > (ticks_per_overflow - overflow_margin) &&
      prev_count <= ticks_per_overflow && count < overflow_margin)
    ++overflow_count;
  if (prev_count >= 0 && prev_count < overflow_margin &&
      count >= (ticks_per_overflow - overflow_margin))
    --overflow_count;
}

/*
  Shaft angle calculation
*/
float STM32HWEncoder::getSensorAngle() { return getAngle(); }

float STM32HWEncoder::getMechanicalAngle()
{
  return _2PI * (count % static_cast<int>(cpr)) / static_cast<float>(cpr);
}
float STM32HWEncoder::getAngle()
{
  return _2PI * (count / static_cast<float>(cpr) +
                 overflow_count * rotations_per_overflow);
}
double STM32HWEncoder::getPreciseAngle()
{
  return _2PI * (count / static_cast<double>(cpr) +
                 overflow_count * rotations_per_overflow);
}
int32_t STM32HWEncoder::getFullRotations()
{
  return count / static_cast<int>(cpr) +
         overflow_count * rotations_per_overflow;
}

/*
  Shaft velocity calculation
*/
float STM32HWEncoder::getVelocity()
{
  // sampling time calculation
  float dt = (pulse_timestamp - prev_timestamp) * 1e-6f;
  // quick fix for strange cases (micros overflow)
  if (dt <= 0 || dt > 0.5f)
    dt = 1e-3f;

  // time from last impulse
  int32_t overflow_diff = overflow_count - prev_overflow_count;
  int32_t dN = (count - prev_count) + (ticks_per_overflow * overflow_diff);

  float pulse_per_second = dN / dt;

  // velocity calculation
  return pulse_per_second / (static_cast<float>(cpr)) * _2PI;
}

// getter for index pin
int STM32HWEncoder::needsSearch() { return false; }

// private function used to determine if encoder has index
int STM32HWEncoder::hasIndex() { return 0; }

// encoder initialisation of the hardware pins
// and calculation variables
void STM32HWEncoder::init()
{
  // overflow handling
  rotations_per_overflow = 0xFFFF / cpr;
  ticks_per_overflow = cpr * rotations_per_overflow;

  GPIO_InitTypeDef gpio;

  __HAL_RCC_TIM4_CLK_ENABLE();

  __HAL_RCC_GPIOB_CLK_ENABLE();

  /**TIM4 GPIO Configuration
  PB6     ------> TIM4_CH1
  PB7     ------> TIM4_CH2
  */
  gpio.Pin = GPIO_PIN_6 | GPIO_PIN_7;
  gpio.Mode = GPIO_MODE_AF_PP;
  gpio.Pull = GPIO_NOPULL;
  gpio.Speed = GPIO_SPEED_FREQ_LOW;
  gpio.Alternate = GPIO_AF2_TIM4;
  HAL_GPIO_Init(GPIOB, &gpio);

  TIM_Encoder_InitTypeDef sConfig = {0};
  TIM_MasterConfigTypeDef sMasterConfig = {0};

  /* USER CODE END TIM4_Init 1 */
  encoder_handle.Instance = TIM4;
  encoder_handle.Init.Prescaler = 0;
  encoder_handle.Init.CounterMode = TIM_COUNTERMODE_UP;
  encoder_handle.Init.Period = ticks_per_overflow - 1;
  encoder_handle.Init.ClockDivision = 0;
  encoder_handle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;

  sConfig.EncoderMode = TIM_ENCODERMODE_TI12;
  sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
  sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
  sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
  sConfig.IC1Filter = 0;
  sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
  sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
  sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
  sConfig.IC2Filter = 0;
  if (HAL_TIM_Encoder_Init(&encoder_handle, &sConfig) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }
  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
  if (HAL_TIMEx_MasterConfigSynchronization(&encoder_handle, &sMasterConfig) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }
  if (HAL_TIM_Encoder_Start(&encoder_handle, TIM_CHANNEL_ALL) != HAL_OK)
  {
    _Error_Handler(__FILE__, __LINE__);
  }

  // counter setup
  overflow_count = 0;
  count = 0;
  prev_count = 0;
  prev_overflow_count = 0;

  prev_timestamp = getCurrentMicros();
  pulse_timestamp = getCurrentMicros();
}

#endif

I always had problems with the nano boards, especially the cheap clones. I used teensy boards in their place when I needed more speed, things tend to work a lot better that way.