SimpleFOClibrary
2.1
|
#include <Encoder.h>
Public Member Functions | |
Encoder (int encA, int encB, float ppr, int index=0) | |
void | init () |
void | enableInterrupts (void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doIndex)()=nullptr) |
void | handleA () |
void | handleB () |
void | handleIndex () |
float | getAngle () override |
float | getVelocity () override |
int | needsSearch () override |
Public Attributes | |
int | pinA |
encoder hardware pin A More... | |
int | pinB |
encoder hardware pin B More... | |
int | index_pin |
index pin More... | |
Pullup | pullup |
Configuration parameter internal or external pullups. More... | |
Quadrature | quadrature |
Configuration parameter enable or disable quadrature mode. More... | |
float | cpr |
encoder cpr number More... | |
Encoder::Encoder | ( | int | encA, |
int | encB, | ||
float | ppr, | ||
int | index = 0 |
||
) |
Encoder class constructor
encA | encoder B pin |
encB | encoder B pin |
ppr | impulses per rotation (cpr=ppr*4) |
index | index pin number (optional input) |
Definition at line 11 of file Encoder.cpp.
void Encoder::enableInterrupts | ( | void(*)() | doA = nullptr , |
void(*)() | doB = nullptr , |
||
void(*)() | doIndex = nullptr |
||
) |
function enabling hardware interrupts for the encoder channels with provided callback functions if callback is not provided then the interrupt is not enabled
doA | pointer to the A channel interrupt handler function |
doB | pointer to the B channel interrupt handler function |
doIndex | pointer to the Index channel interrupt handler function |
Definition at line 190 of file Encoder.cpp.
|
overridevirtual |
|
overridevirtual |
get current angular velocity (rad/s)
Reimplemented from Sensor.
Definition at line 111 of file Encoder.cpp.
void Encoder::handleA | ( | ) |
A channel callback function
Definition at line 42 of file Encoder.cpp.
void Encoder::handleB | ( | ) |
B channel callback function
Definition at line 63 of file Encoder.cpp.
void Encoder::handleIndex | ( | ) |
Index channel callback function
Definition at line 85 of file Encoder.cpp.
void Encoder::init | ( | ) |
encoder initialise pins
Definition at line 160 of file Encoder.cpp.
|
overridevirtual |
returns 0 if it does need search for absolute zero 0 - encoder without index 1 - ecoder with index
Reimplemented from Sensor.
Definition at line 148 of file Encoder.cpp.
Pullup Encoder::pullup |
Quadrature Encoder::quadrature |