MagneticSensorPWM

Hi,

I created a MagneticSensorPWM class. It can handle multiple pwm input magnetic sensors. It is programmed generic, so it can be used for any brand of sensor I guess, but I could test it with the AS5048A/B variants only (don’t have anything else). I receive very stable results at 1kHz update rate with these sensors on the B-G431-ESC, looks promising. It is easy to use, just pass the pinnumber where the PWM signal is connected and a configuration (for AS50xx included in the code already) in the constructor, nothing else required.

The lib is based on the stm32duino HardwareTimer library, so I am not perfectly sure how portable it is. The used pin must have a timer associated which is used to measure frequency and dutycycle, this is the only restriction, but on stm32 you normally have several timers to select on most input pins.

Please let me know if there is interest to share. Happy to provide the code (not sure how I can do it), and further develop the code if somebody is interested. I tested intesively, but would love if some more people here start using it as well.

Best
Christian

#ifndef MAGNETICSENSORPWM_LIB_H
#define MAGNETICSENSORPWM_LIB_H

#include "SimpleFOC.h"
#include <inttypes.h>
#include <HardwareTimer.h>

#define MAGNETICSENSORPWM_VERSION         1    // software version of this library
#define MAGNETICSENSORPWM_MAX_INSTANCES   4    // the maximum amount of inputs that can be handled by this library

struct MagneticSensorPWMConfig_s  {
  int  clocks_frame;                           // amount of total sensor clocks in a full PWM cycle
  int  clocks_data;                            // amount of position data sensor clocks in a PWM cycle
  int  clocks_sync;                            // amount of header sensor clocks at the beginning of a PWM cycle
  int  frequency;                              // rough pwm frequency in Hz, to define timer clock (actual frequency will be measured by the library) 
  bool inverted;                               // inverted logic levels: NON-Inverted: Pulse starts HIGH, Position is encoded LOW 
};

// some predefined structures
extern MagneticSensorPWMConfig_s AS50xx_PWM;

class MagneticSensorPWM: public Sensor {

 public:

    MagneticSensorPWM(uint8_t pin, MagneticSensorPWMConfig_s config);   // constructor with pin and configuration. Hardware timer and channel will be selected automatically by PinMap_PWM in PeripheralPins.c
    float getAngle() override;               // get angle in rad

    HardwareTimer* timer;                    // holds the hardwaretimer used in this instance, required in interrupts           
    int timerChannelFrameStart;              // holds the timer channel used for detecting the frame start edge
    int timerChannelDataStart;               // holds the timer channel used for detecting the data start edge
    void frameStart();                       // called when frame start was detected
    void dataStart();                        // called when data start is detected
    void hwdebug();                          // shows debugging information

  private:
    TIM_TypeDef* tim;
    MagneticSensorPWMConfig_s config;
    float angle;
    uint32_t lastFrameStartTime;
    uint32_t lastDataStartTime;

};

#endif
2 Likes

Hey, that sounds really cool. We have recently started a drivers repository, and if you felt like contributing your code, that would be a good place to put it. If you want to just send me the code, I can add it there, but if you would prefer to send a pull request that would be wonderful too, and people could see that it is your contribution…

Hey @Chris,

I’ve made a very simple interrupt based implementation of the MagneticSensorPWM. It’s in the dev branch, with some provided examples.

But I’m sure that your solution is much more optimal for stm32 boards. So if you have time could you please check the code in the dev branch and maybe run it. If be very interested to hear your thoughts about the performance.

Hey @Antun_Skuric,

sure I am giving it a try and will do some statistics.

I just have a question tough: I need to change the code for the AS5048, as it is encoding the position in the low portion, of the signal, your code is assuming position in the high part of the signal. but I can do this easily. However, I do not understand yet the min and max settings for the 5048 sensor. Could you check the signal in the datasheet? (page 27): Download center | ams OSRAM

Second question: I was not aware how to handle full rotations. My output of getAngle() is always between 0 and 2*Pi. I see your implementation is adding full rotations as well, is this correct?

Your code does not measure the PWM frequency, so it does not do any kind of temperature correction or anything else, I think it is important to do. For example the AS5048 datasheet says the internal chip clock chan change up to 10% over temperature, so full cycle measurement and correction is required. My code is doing this, and I will change my implementation and remove any dependancy to Hardwaretimer, so rewrite it with simple digital interrupt which will be portable. Would be nice if you can test then also on your side and compare results.

Regards
Christian

Low side or high side it doesn’t really matter much.
I’ve implemented the sensor using the microseconds function implemeted in Arduino. And since all of these settings such as owl frequency and temperature dependance are going to be highly dependant of the sensors, I’ve implemented a simple interface to get around this (simpleification, maybe oversimplification). The user defines minimal length of the high side and the maximal length on the high side in microseconds.
That are the min and max. There is a quick example code which helps you find the min and max values. The code interpolates in between and calculates the angle. The code also considers that the owl frequency will not change.

There are many improvements that can be done for sure. But it should at least work. :slight_smile:

Hi,

you are right of course. Ok clear, easy enough, I gave it a try for the AS5048 (us min=3, max=997) and made a little statistic: 10 tests, 1000 samples at 100Hz for each test, and the calulating average and standard deviation:

Interrupt driven (current dev code):
Test-Number 1: Average: 1.145506 - Std.Dev: 0.002660
Test-Number 2: Average: 1.145651 - Std.Dev: 0.002751
Test-Number 3: Average: 1.145626 - Std.Dev: 0.002707
Test-Number 4: Average: 1.145727 - Std.Dev: 0.002780
Test-Number 5: Average: 1.145588 - Std.Dev: 0.002683
Test-Number 6: Average: 1.145733 - Std.Dev: 0.002784
Test-Number 7: Average: 1.145594 - Std.Dev: 0.002717
Test-Number 8: Average: 1.145588 - Std.Dev: 0.002683
Test-Number 9: Average: 1.145702 - Std.Dev: 0.002766
Test-Number 10: Average: 1.145721 - Std.Dev: 0.002791

With input-capture module from hardware timer:
Test-Number 1: Average: 2.564582 - Std.Dev: 0.000749
Test-Number 2: Average: 2.564629 - Std.Dev: 0.000735
Test-Number 3: Average: 2.564633 - Std.Dev: 0.000735
Test-Number 4: Average: 2.564569 - Std.Dev: 0.000736
Test-Number 5: Average: 2.564618 - Std.Dev: 0.000753
Test-Number 6: Average: 2.564671 - Std.Dev: 0.000734
Test-Number 7: Average: 2.564586 - Std.Dev: 0.000758
Test-Number 8: Average: 2.564612 - Std.Dev: 0.000786
Test-Number 9: Average: 2.564615 - Std.Dev: 0.000740
Test-Number 10: Average: 2.564642 - Std.Dev: 0.000758

With an input capture module the sensor readings show around 3-4 times less noise, but the simple edge interrupt approach is easily portable and is probably doing fine as well.