Skip to content

MagneticSensorPWM: fix cpr calculation, add constructor using clocks #258

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 4 commits into from
Mar 17, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 31 additions & 1 deletion src/sensors/MagneticSensorPWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _m

pinPWM = _pinPWM;

cpr = _max_raw_count - _min_raw_count;
cpr = _max_raw_count - _min_raw_count + 1;
min_raw_count = _min_raw_count;
max_raw_count = _max_raw_count;

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


/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
*
* Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
*
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
* @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
* @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
* @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
* @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
*/
MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks){

pinPWM = _pinPWM;

min_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_min_pwm_clocks);
max_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_max_pwm_clocks);
cpr = max_raw_count - min_raw_count + 1;

// define if the sensor uses interrupts
is_interrupt_based = false;

min_elapsed_time = 1.0f/freqHz; // set the minimum time between two readings

// define as not set
last_call_us = _micros();
}



void MagneticSensorPWM::init(){

// initial hardware
Expand All @@ -36,6 +65,7 @@ float MagneticSensorPWM::getSensorAngle(){
// raw data from sensor
raw_count = getRawCount();
if (raw_count > max_raw_count) raw_count = max_raw_count;
if (raw_count < min_raw_count) raw_count = min_raw_count;
return( (float) (raw_count - min_raw_count) / (float)cpr) * _2PI;
}

Expand Down
19 changes: 15 additions & 4 deletions src/sensors/MagneticSensorPWM.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,23 @@

class MagneticSensorPWM: public Sensor{
public:
/**
* MagneticSensorPWM class constructor
* @param _pinPWM the pin to read the PWM sensor input signal
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
* @param _min_raw_count the smallest expected reading
* @param _max_raw_count the largest expected reading
*/
MagneticSensorPWM(uint8_t _pinPWM,int _min = 0, int _max = 0);

/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
*
* Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
*
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
* @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
* @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
* @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
* @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
*/
MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks);

// initialize the sensor hardware
void init();
Expand Down