|
| 1 | +#ifndef ENCODER_LIB_H |
| 2 | +#define ENCODER_LIB_H |
| 3 | + |
| 4 | +#include "Arduino.h" |
| 5 | +#include "common/foc_utils.h" |
| 6 | +#include "common/hardware_utils.h" |
| 7 | +#include "common/Sensor.h" |
| 8 | + |
| 9 | + |
| 10 | +/** |
| 11 | + * Quadrature mode configuration structure |
| 12 | + */ |
| 13 | +enum Quadrature{ |
| 14 | + ON, //!< Enable quadrature mode CPR = 4xPPR |
| 15 | + OFF //!< Disable quadrature mode / CPR = PPR |
| 16 | +}; |
| 17 | + |
| 18 | +class Encoder: public Sensor{ |
| 19 | + public: |
| 20 | + /** |
| 21 | + Encoder class constructor |
| 22 | + @param encA encoder B pin |
| 23 | + @param encB encoder B pin |
| 24 | + @param ppr impulses per rotation (cpr=ppr*4) |
| 25 | + @param index index pin number (optional input) |
| 26 | + */ |
| 27 | + Encoder(int encA, int encB , float ppr, int index = 0); |
| 28 | + |
| 29 | + /** encoder initialise pins */ |
| 30 | + void init(); |
| 31 | + /** |
| 32 | + * function enabling hardware interrupts for the encoder channels with provided callback functions |
| 33 | + * if callback is not provided then the interrupt is not enabled |
| 34 | + * |
| 35 | + * @param doA pointer to the A channel interrupt handler function |
| 36 | + * @param doB pointer to the B channel interrupt handler function |
| 37 | + * @param doIndex pointer to the Index channel interrupt handler function |
| 38 | + * |
| 39 | + */ |
| 40 | + void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr); |
| 41 | + |
| 42 | + // Encoder interrupt callback functions |
| 43 | + /** A channel callback function */ |
| 44 | + void handleA(); |
| 45 | + /** B channel callback function */ |
| 46 | + void handleB(); |
| 47 | + /** Index channel callback function */ |
| 48 | + void handleIndex(); |
| 49 | + |
| 50 | + |
| 51 | + // pins A and B |
| 52 | + int pinA; //!< encoder hardware pin A |
| 53 | + int pinB; //!< encoder hardware pin B |
| 54 | + int index_pin; //!< index pin |
| 55 | + |
| 56 | + // Encoder configuration |
| 57 | + Pullup pullup; //!< Configuration parameter internal or external pullups |
| 58 | + Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode |
| 59 | + float cpr;//!< encoder cpr number |
| 60 | + |
| 61 | + // Abstract functions of the Sensor class implementation |
| 62 | + /** get current angle (rad) */ |
| 63 | + float getAngle(); |
| 64 | + /** get current angular velocity (rad/s) */ |
| 65 | + float getVelocity(); |
| 66 | + /** |
| 67 | + * set current angle as zero angle |
| 68 | + * return the angle [rad] difference |
| 69 | + */ |
| 70 | + float initRelativeZero(); |
| 71 | + /** |
| 72 | + * set index angle as zero angle |
| 73 | + * return the angle [rad] difference |
| 74 | + */ |
| 75 | + float initAbsoluteZero(); |
| 76 | + /** |
| 77 | + * returns 0 if it has no index |
| 78 | + * 0 - encoder without index |
| 79 | + * 1 - encoder with index |
| 80 | + */ |
| 81 | + int hasAbsoluteZero(); |
| 82 | + /** |
| 83 | + * returns 0 if it does need search for absolute zero |
| 84 | + * 0 - encoder without index |
| 85 | + * 1 - ecoder with index |
| 86 | + */ |
| 87 | + int needsAbsoluteZeroSearch(); |
| 88 | + |
| 89 | + private: |
| 90 | + int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not. |
| 91 | + |
| 92 | + volatile long pulse_counter;//!< current pulse counter |
| 93 | + volatile long pulse_timestamp;//!< last impulse timestamp in us |
| 94 | + volatile int A_active; //!< current active states of A channel |
| 95 | + volatile int B_active; //!< current active states of B channel |
| 96 | + volatile int I_active; //!< current active states of Index channel |
| 97 | + volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt |
| 98 | + |
| 99 | + // velocity calculation variables |
| 100 | + float prev_Th, pulse_per_second; |
| 101 | + volatile long prev_pulse_counter, prev_timestamp_us; |
| 102 | +}; |
| 103 | + |
| 104 | + |
| 105 | +#endif |
0 commit comments