-
Notifications
You must be signed in to change notification settings - Fork 69
/
Copy pathESP32HWEncoder.h
66 lines (45 loc) · 1.69 KB
/
ESP32HWEncoder.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
#pragma once
#include <Arduino.h>
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
#include "driver/pcnt.h"
#include "soc/pcnt_struct.h"
#include "common/base_classes/Sensor.h"
#include "common/foc_utils.h"
#include "FunctionalInterrupt.h"
static struct overflowISR_args_t {
int32_t* angleoverflow_val;
pcnt_unit_t unit;
int32_t set;
}overflowISR_args[PCNT_UNIT_MAX];
// Statically allocate and initialize a spinlock
static portMUX_TYPE spinlock;
static int used_units[PCNT_UNIT_MAX];
class ESP32HWEncoder : public Sensor{
public:
/**
Encoder class constructor
@param ppr impulses per rotation (cpr=ppr*4)
*/
explicit ESP32HWEncoder(int pinA, int pinB, int32_t ppr, int pinI=-1);
void init() override;
int needsSearch() override;
int hasIndex();
float getSensorAngle() override;
void setCpr(int32_t ppr);
int32_t getCpr();
void setStepDirMode();
void setQuadratureMode();
bool initialized = false;
Pullup pullup; //!< Configuration parameter internal or external pullups
protected:
void IRAM_ATTR indexHandler();
bool indexFound = false;
int _pinA, _pinB, _pinI;
pcnt_config_t pcnt_config;
int16_t angleCounter; // Stores the PCNT value
int32_t angleOverflow; // In case the PCNT peripheral overflows, this accumulates the max count to keep track of large counts/angles (>= 16 Bit). On index, this gets reset.
int32_t angleSum; // Sum of Counter and Overflow in range [0,cpr]
int32_t cpr; // Counts per rotation = 4 * ppr for quadrature encoders
float inv_cpr;
};
#endif