Skip to content

Commit 2d9a407

Browse files
Merge pull request #258 from runger1101001/dev
MagneticSensorPWM: fix cpr calculation, add constructor using clocks Also prevent negative angles, and set the min_elapsed_time on the sensor, since we have the frequency in this constructor
2 parents a8a78e8 + 43d355c commit 2d9a407

File tree

2 files changed

+46
-5
lines changed

2 files changed

+46
-5
lines changed

src/sensors/MagneticSensorPWM.cpp

Lines changed: 31 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _m
1010

1111
pinPWM = _pinPWM;
1212

13-
cpr = _max_raw_count - _min_raw_count;
13+
cpr = _max_raw_count - _min_raw_count + 1;
1414
min_raw_count = _min_raw_count;
1515
max_raw_count = _max_raw_count;
1616

@@ -22,6 +22,35 @@ MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _m
2222
}
2323

2424

25+
/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
26+
*
27+
* Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
28+
*
29+
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
30+
* @param freqHz the frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
31+
* @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
32+
* @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
33+
* @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
34+
*/
35+
MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks){
36+
37+
pinPWM = _pinPWM;
38+
39+
min_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_min_pwm_clocks);
40+
max_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_max_pwm_clocks);
41+
cpr = max_raw_count - min_raw_count + 1;
42+
43+
// define if the sensor uses interrupts
44+
is_interrupt_based = false;
45+
46+
min_elapsed_time = 1.0f/freqHz; // set the minimum time between two readings
47+
48+
// define as not set
49+
last_call_us = _micros();
50+
}
51+
52+
53+
2554
void MagneticSensorPWM::init(){
2655

2756
// initial hardware
@@ -36,6 +65,7 @@ float MagneticSensorPWM::getSensorAngle(){
3665
// raw data from sensor
3766
raw_count = getRawCount();
3867
if (raw_count > max_raw_count) raw_count = max_raw_count;
68+
if (raw_count < min_raw_count) raw_count = min_raw_count;
3969
return( (float) (raw_count - min_raw_count) / (float)cpr) * _2PI;
4070
}
4171

src/sensors/MagneticSensorPWM.h

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -10,12 +10,23 @@
1010

1111
class MagneticSensorPWM: public Sensor{
1212
public:
13-
/**
14-
* MagneticSensorPWM class constructor
15-
* @param _pinPWM the pin to read the PWM sensor input signal
13+
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
14+
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
15+
* @param _min_raw_count the smallest expected reading
16+
* @param _max_raw_count the largest expected reading
1617
*/
1718
MagneticSensorPWM(uint8_t _pinPWM,int _min = 0, int _max = 0);
18-
19+
/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
20+
*
21+
* Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
22+
*
23+
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
24+
* @param freqHz the frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
25+
* @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
26+
* @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
27+
* @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
28+
*/
29+
MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks);
1930

2031
// initialize the sensor hardware
2132
void init();

0 commit comments

Comments
 (0)