Skip to content

Commit eaf37ca

Browse files
committed
magnetic pwm sensors initial implementation
1 parent bf00d4f commit eaf37ca

File tree

6 files changed

+143
-3
lines changed

6 files changed

+143
-3
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
#include <SimpleFOC.h>
2+
3+
4+
/**
5+
* An example to find out the raw max and min count to be provided to the constructor
6+
* SPin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value
7+
* And replace values 4 and 904 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle().
8+
* If there is a jump that means you can still find better values.
9+
*/
10+
MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904);
11+
void doPWM(){sensor.handlePWM();}
12+
13+
void setup() {
14+
// monitoring port
15+
Serial.begin(115200);
16+
17+
// initialise magnetic sensor hardware
18+
sensor.init();
19+
sensor.enableInterrupt(doPWM);
20+
21+
Serial.println("Sensor ready");
22+
_delay(1000);
23+
}
24+
25+
void loop() {
26+
// display the angle and the angular velocity to the terminal
27+
Serial.print(sensor.pulse_length_us);
28+
Serial.print("\t");
29+
Serial.println(sensor.getAngle());
30+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
#include <SimpleFOC.h>
2+
3+
4+
/**
5+
* Magnetic sensor reading pwm signal on pin 2. The pwm duty cycle is proportional to the sensor angle.
6+
*
7+
* MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max)
8+
* - pinPWM - the pin that is reading the pwm from magnetic sensor
9+
* - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution
10+
* - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation
11+
*/
12+
MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904);
13+
void doPWM(){sensor.handlePWM();}
14+
15+
void setup() {
16+
// monitoring port
17+
Serial.begin(115200);
18+
19+
// initialise magnetic sensor hardware
20+
sensor.init();
21+
sensor.enableInterrupt(doPWM);
22+
23+
Serial.println("Sensor ready");
24+
_delay(1000);
25+
}
26+
27+
void loop() {
28+
// display the angle and the angular velocity to the terminal
29+
Serial.print(sensor.getAngle());
30+
Serial.print("\t");
31+
Serial.println(sensor.getVelocity());
32+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
#include <SimpleFOC.h>
2+
3+
// software interrupt library
4+
#include <PciManager.h>
5+
#include <PciListenerImp.h>
6+
7+
/**
8+
* Magnetic sensor reading analog voltage on pin which does not have hardware interrupt support. Such as A0.
9+
*
10+
* MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max)
11+
* - pinPWM - the pin that is reading the pwm from magnetic sensor
12+
* - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution
13+
* - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation
14+
*/
15+
MagneticSensorPWM sensor = MagneticSensorPWM(A0, 4, 904);
16+
void doPWM(){sensor.handlePWM();}
17+
18+
// encoder interrupt init
19+
PciListenerImp listenerPWM(sensor.pinPWM, doPWM);}
20+
21+
void setup() {
22+
// monitoring port
23+
Serial.begin(115200);
24+
25+
// initialise magnetic sensor hardware
26+
sensor.init();
27+
PciManager.registerListener(&listenerPWM);
28+
29+
Serial.println("Sensor ready");
30+
_delay(1000);
31+
}
32+
33+
void loop() {
34+
// display the angle and the angular velocity to the terminal
35+
Serial.print(sensor.getAngle());
36+
Serial.print("\t");
37+
Serial.println(sensor.getVelocity());
38+
}

keywords.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ HallSensors KEYWORD1
88
MagneticSensorSPI KEYWORD1
99
MagneticSensorI2C KEYWORD1
1010
MagneticSensorAnalog KEYWORD1
11+
MagneticSensorPWM KEYWORD1
1112
BLDCDriver3PWM KEYWORD1
1213
BLDCDriver6PWM KEYWORD1
1314
BLDCDriver KEYWORD1
@@ -92,6 +93,8 @@ scalar KEYWORD2
9293
pid KEYWORD2
9394
lpf KEYWORD2
9495
motor KEYWORD2
96+
handlePWM KEYWORD2
97+
enableInterrupt KEYWORD2
9598

9699

97100

src/sensors/MagneticSensorPWM.cpp

Lines changed: 31 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
#include "MagneticSensorPWM.h"
2+
#include "Arduino.h"
23

34
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
45
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
@@ -14,6 +15,9 @@ MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _m
1415
max_raw_count = _max_raw_count;
1516

1617
pinMode(pinPWM, INPUT);
18+
19+
// init last call
20+
last_call_us = _micros();
1721
}
1822

1923

@@ -57,10 +61,35 @@ float MagneticSensorPWM::getAngle(){
5761

5862
// get velocity (rad/s)
5963
float MagneticSensorPWM::getVelocity(){
60-
return velocity;
64+
return velocity;
6165
}
6266

6367
// read the raw counter of the magnetic sensor
6468
int MagneticSensorPWM::getRawCount(){
65-
return pulseIn(pinPWM,HIGH);
69+
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) // if mcu is not atmega328 && if mcu is not atmega2560
70+
pulse_length_us = pulseIn(pinPWM, HIGH);
71+
#endif
72+
73+
return pulse_length_us;
74+
}
75+
76+
77+
void MagneticSensorPWM::handlePWM() {
78+
// unsigned long now_us = ticks();
79+
unsigned long now_us = _micros();
80+
81+
// if falling edge, calculate the pulse length
82+
if (!digitalRead(pinPWM)) pulse_length_us = now_us - last_call_us;
83+
84+
// save the currrent timestamp for the next call
85+
last_call_us = now_us;
6686
}
87+
88+
// function enabling hardware interrupts of the for the callback provided
89+
// if callback is not provided then the interrupt is not enabled
90+
void MagneticSensorPWM::enableInterrupt(void (*doPWM)()){
91+
#if !defined(__AVR_ATmega328P__) && !defined(__AVR_ATmega168__) && !defined(__AVR_ATmega328PB__) && !defined(__AVR_ATmega2560__) // if mcu is not atmega328 && if mcu is not atmega2560
92+
// enable interrupts on pwm input pin
93+
attachInterrupt(digitalPinToInterrupt(pinPWM), doPWM, CHANGE);
94+
#endif
95+
}

src/sensors/MagneticSensorPWM.h

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,11 @@ class MagneticSensorPWM: public Sensor{
2626
float getAngle() override;
2727
// get current angular velocity (rad/s)
2828
float getVelocity() override;
29-
29+
30+
// pwm handler
31+
void handlePWM();
32+
void enableInterrupt(void (*doPWM)());
33+
unsigned long pulse_length_us;
3034

3135
private:
3236
// raw count (typically in range of 0-1023)
@@ -50,6 +54,10 @@ class MagneticSensorPWM: public Sensor{
5054
float angle_prev; //!< angle in previous velocity calculation step
5155
long velocity_calc_timestamp; //!< last velocity calculation timestamp
5256
float velocity;
57+
58+
// time tracking variables
59+
unsigned long last_call_us;
60+
// unsigned long pulse_length_us;
5361

5462

5563
};

0 commit comments

Comments
 (0)