Skip to content

Commit 0ba325c

Browse files
committed
Adding MagneticSensorPWM
This implementation has been tested with the AS5048a PWM output. It follows an almost identical format to the existing MagneticSensorAnalog implementation.
1 parent d1fdfb7 commit 0ba325c

File tree

3 files changed

+124
-0
lines changed

3 files changed

+124
-0
lines changed

src/SimpleFOC.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -102,6 +102,7 @@ void loop() {
102102
#include "sensors/MagneticSensorSPI.h"
103103
#include "sensors/MagneticSensorI2C.h"
104104
#include "sensors/MagneticSensorAnalog.h"
105+
#include "sensors/MagneticSensorPWM.h"
105106
#include "sensors/HallSensor.h"
106107
#include "drivers/BLDCDriver3PWM.h"
107108
#include "drivers/BLDCDriver6PWM.h"

src/sensors/MagneticSensorPWM.cpp

Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
#include "MagneticSensorPWM.h"
2+
3+
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
4+
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
5+
* @param _min_raw_count the smallest expected reading
6+
* @param _max_raw_count the largest expected reading
7+
*/
8+
MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _max_raw_count){
9+
10+
pinPWM = _pinPWM;
11+
12+
cpr = _max_raw_count - _min_raw_count;
13+
min_raw_count = _min_raw_count;
14+
max_raw_count = _max_raw_count;
15+
16+
pinMode(pinPWM, INPUT);
17+
}
18+
19+
20+
void MagneticSensorPWM::init(){
21+
22+
// velocity calculation init
23+
angle_prev = 0;
24+
velocity_calc_timestamp = _micros();
25+
26+
// full rotations tracking number
27+
full_rotation_offset = 0;
28+
raw_count_prev = getRawCount();
29+
}
30+
31+
// get current angle (rad)
32+
float MagneticSensorPWM::getAngle(){
33+
34+
// raw data from sensor
35+
raw_count = getRawCount();
36+
37+
int delta = raw_count - raw_count_prev;
38+
// if overflow happened track it as full rotation
39+
if(abs(delta) > (0.8*cpr) ) full_rotation_offset += delta > 0 ? -_2PI : _2PI;
40+
41+
float angle = full_rotation_offset + ( (float) (raw_count) / (float)cpr) * _2PI;
42+
43+
// calculate velocity here
44+
long now = _micros();
45+
float Ts = (now - velocity_calc_timestamp)*1e-6;
46+
// quick fix for strange cases (micros overflow)
47+
if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
48+
velocity = (angle - angle_prev)/Ts;
49+
50+
// save variables for future pass
51+
raw_count_prev = raw_count;
52+
angle_prev = angle;
53+
velocity_calc_timestamp = now;
54+
55+
return angle;
56+
}
57+
58+
// get velocity (rad/s)
59+
float MagneticSensorPWM::getVelocity(){
60+
return velocity;
61+
}
62+
63+
// read the raw counter of the magnetic sensor
64+
int MagneticSensorPWM::getRawCount(){
65+
return pulseIn(pinPWM,HIGH);
66+
}

src/sensors/MagneticSensorPWM.h

Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
#ifndef MAGNETICSENSORPWM_LIB_H
2+
#define MAGNETICSENSORPWM_LIB_H
3+
4+
#include "Arduino.h"
5+
#include "../common/base_classes/Sensor.h"
6+
#include "../common/foc_utils.h"
7+
#include "../common/time_utils.h"
8+
9+
// This sensor has been tested with AS5048a running in PWM mode.
10+
11+
class MagneticSensorPWM: public Sensor{
12+
public:
13+
/**
14+
* MagneticSensorPWM class constructor
15+
* @param _pinPWM the pin to read the PWM sensor input signal
16+
*/
17+
MagneticSensorPWM(uint8_t _pinPWM,int _min = 0, int _max = 0);
18+
19+
20+
// initialize the sensor hardware
21+
void init();
22+
23+
int pinPWM;
24+
25+
// get current angle (rad)
26+
float getAngle() override;
27+
// get current angular velocity (rad/s)
28+
float getVelocity() override;
29+
30+
31+
private:
32+
// raw count (typically in range of 0-1023)
33+
int raw_count;
34+
int min_raw_count;
35+
int max_raw_count;
36+
int cpr;
37+
int read();
38+
39+
/**
40+
* Function getting current angle register value
41+
* it uses angle_register variable
42+
*/
43+
int getRawCount();
44+
45+
// total angle tracking variables
46+
float full_rotation_offset; //!<number of full rotations made
47+
int raw_count_prev; //!< angle in previous position calculation step
48+
49+
// velocity calculation variables
50+
float angle_prev; //!< angle in previous velocity calculation step
51+
long velocity_calc_timestamp; //!< last velocity calculation timestamp
52+
float velocity;
53+
54+
55+
};
56+
57+
#endif

0 commit comments

Comments
 (0)