SimpleFOClibrary
2.4.0
Loading...
Searching...
No Matches
MagneticSensorPWM.cpp
Go to the documentation of this file.
1
#include "
MagneticSensorPWM.h
"
2
#include "Arduino.h"
3
4
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
5
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
6
* @param _min_raw_count the smallest expected reading
7
* @param _max_raw_count the largest expected reading
8
*/
9
MagneticSensorPWM::MagneticSensorPWM
(uint8_t _pinPWM,
int
_min_raw_count,
int
_max_raw_count){
10
11
pinPWM
= _pinPWM;
12
13
cpr = _max_raw_count - _min_raw_count + 1;
14
min_raw_count = _min_raw_count;
15
max_raw_count = _max_raw_count;
16
17
// define if the sensor uses interrupts
18
is_interrupt_based =
false
;
19
20
// define as not set
21
last_call_us =
_micros
();
22
}
23
24
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
54
void
MagneticSensorPWM::init
(){
55
56
// initial hardware
57
pinMode(
pinPWM
,
INPUT
);
58
raw_count = getRawCount();
59
pulse_timestamp =
_micros
();
60
61
this->
Sensor::init
();
// call base class init
62
}
63
64
// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
65
void
MagneticSensorPWM::update
() {
66
if
(is_interrupt_based)
67
noInterrupts();
68
Sensor::update
();
69
angle_prev_ts
= pulse_timestamp;
// Timestamp of actual sample, before the time-consuming PWM communication
70
if
(is_interrupt_based)
71
interrupts();
72
}
73
74
// get current angle (rad)
75
float
MagneticSensorPWM::getSensorAngle
(){
76
// raw data from sensor
77
raw_count = getRawCount();
78
if
(raw_count > max_raw_count) raw_count = max_raw_count;
79
if
(raw_count < min_raw_count) raw_count = min_raw_count;
80
return
( (
float
) (raw_count - min_raw_count) / (
float
)cpr) *
_2PI
;
81
}
82
83
84
// read the raw counter of the magnetic sensor
85
int
MagneticSensorPWM::getRawCount(){
86
if
(!is_interrupt_based){
// if it's not interrupt based read the value in a blocking way
87
pulse_timestamp =
_micros
();
// ideally this should be done right at the rising edge of the pulse
88
pulse_length_us
= pulseIn(
pinPWM
, HIGH,
timeout_us
);
// 1200us timeout, should this be configurable?
89
}
90
return
pulse_length_us
;
91
}
92
93
94
void
MagneticSensorPWM::handlePWM
() {
95
// unsigned long now_us = ticks();
96
unsigned
long
now_us =
_micros
();
97
98
// if falling edge, calculate the pulse length
99
if
(!digitalRead(
pinPWM
)) {
100
pulse_length_us
= now_us - last_call_us;
101
pulse_timestamp = last_call_us;
// angle was sampled at the rising edge of the pulse, so use that timestamp
102
}
103
104
// save the currrent timestamp for the next call
105
last_call_us = now_us;
106
is_interrupt_based =
true
;
// set the flag to true
107
}
108
109
// function enabling hardware interrupts of the for the callback provided
110
// if callback is not provided then the interrupt is not enabled
111
void
MagneticSensorPWM::enableInterrupt
(
void
(*doPWM)()){
112
// declare it's interrupt based
113
is_interrupt_based =
true
;
114
115
// enable interrupts on pwm input pin
116
attachInterrupt(digitalPinToInterrupt(
pinPWM
), doPWM, CHANGE);
117
}
MagneticSensorPWM.h
MagneticSensorPWM::MagneticSensorPWM
MagneticSensorPWM(uint8_t _pinPWM, int _min=0, int _max=0)
Definition
MagneticSensorPWM.cpp:9
MagneticSensorPWM::init
void init()
Definition
MagneticSensorPWM.cpp:54
MagneticSensorPWM::pinPWM
int pinPWM
Definition
MagneticSensorPWM.h:34
MagneticSensorPWM::getSensorAngle
float getSensorAngle() override
Definition
MagneticSensorPWM.cpp:75
MagneticSensorPWM::timeout_us
unsigned int timeout_us
Definition
MagneticSensorPWM.h:47
MagneticSensorPWM::enableInterrupt
void enableInterrupt(void(*doPWM)())
Definition
MagneticSensorPWM.cpp:111
MagneticSensorPWM::update
void update() override
Definition
MagneticSensorPWM.cpp:65
MagneticSensorPWM::pulse_length_us
unsigned long pulse_length_us
Definition
MagneticSensorPWM.h:45
MagneticSensorPWM::handlePWM
void handlePWM()
Definition
MagneticSensorPWM.cpp:94
Sensor::min_elapsed_time
float min_elapsed_time
Definition
Sensor.h:109
Sensor::angle_prev_ts
long angle_prev_ts
Definition
Sensor.h:132
Sensor::update
virtual void update()
Definition
Sensor.cpp:7
Sensor::init
virtual void init()
Definition
Sensor.cpp:59
INPUT
INPUT
Definition
current_sense/hardware_specific/generic_mcu.cpp:14
_2PI
#define _2PI
Definition
foc_utils.h:29
_micros
unsigned long _micros()
Definition
time_utils.cpp:21
src
sensors
MagneticSensorPWM.cpp
Generated by
1.9.8