SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
MagneticSensorPWM.h
Go to the documentation of this file.
1#ifndef MAGNETICSENSORPWM_LIB_H
2#define MAGNETICSENSORPWM_LIB_H
3
4#include "Arduino.h"
5#include "../common/base_classes/Sensor.h"
6#include "../common/foc_utils.h"
7#include "../common/time_utils.h"
8
9// This sensor has been tested with AS5048a running in PWM mode.
10
12 public:
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
17 */
18 MagneticSensorPWM(uint8_t _pinPWM,int _min = 0, int _max = 0);
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);
30
31 // initialize the sensor hardware
32 void init();
33
34 int pinPWM;
35
36 // Interrupt-safe update
37 void update() override;
38
39 // get current angle (rad)
40 float getSensorAngle() override;
41
42 // pwm handler
43 void handlePWM();
44 void enableInterrupt(void (*doPWM)());
45 unsigned long pulse_length_us;
46
47 unsigned int timeout_us = 1200;
48
49 private:
50 // raw count (typically in range of 0-1023)
51 int raw_count;
52 int min_raw_count;
53 int max_raw_count;
54 int cpr;
55
56 // flag saying if the readings are interrupt based or not
57 bool is_interrupt_based;
58
59 int read();
60
61 /**
62 * Function getting current angle register value
63 * it uses angle_register variable
64 */
65 int getRawCount();
66
67 // time tracking variables
68 unsigned long last_call_us;
69 // unsigned long pulse_length_us;
70 unsigned long pulse_timestamp;
71
72
73};
74
75#endif
float getSensorAngle() override
unsigned int timeout_us
void enableInterrupt(void(*doPWM)())
void update() override
unsigned long pulse_length_us