@@ -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,33 @@ 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+ // define as not set
47+ last_call_us = _micros ();
48+ }
49+
50+
51+
2552void MagneticSensorPWM::init (){
2653
2754 // initial hardware
0 commit comments