![]() |
SimpleFOClibrary 2.4.0
|
#include <Encoder.h>
Public Member Functions | |
| Encoder (int encA, int encB, float ppr, int index=0) | |
| void | init () override |
| void | enableInterrupts (void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doIndex)()=nullptr) |
| void | handleA () |
| void | handleB () |
| void | handleIndex () |
| float | getSensorAngle () override |
| float | getVelocity () override |
| virtual void | update () override |
| int | needsSearch () override |
Public Member Functions inherited from Sensor | |
| virtual float | getMechanicalAngle () |
| virtual float | getAngle () |
| virtual double | getPreciseAngle () |
| virtual int32_t | getFullRotations () |
Public Attributes | |
| int | pinA |
| encoder hardware pin A | |
| int | pinB |
| encoder hardware pin B | |
| int | index_pin |
| index pin | |
| Pullup | pullup |
| Configuration parameter internal or external pullups. | |
| Quadrature | quadrature |
| Configuration parameter enable or disable quadrature mode. | |
| float | cpr |
| encoder cpr number | |
Public Attributes inherited from Sensor | |
| float | min_elapsed_time = 0.000100 |
Additional Inherited Members | |
Protected Attributes inherited from Sensor | |
| float | velocity =0.0f |
| float | angle_prev =0.0f |
| long | angle_prev_ts =0 |
| float | vel_angle_prev =0.0f |
| long | vel_angle_prev_ts =0 |
| int32_t | full_rotations =0 |
| int32_t | vel_full_rotations =0 |
| 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 212 of file Encoder.cpp.
|
overridevirtual |
|
overridevirtual |
get current angular velocity (rad/s)
Reimplemented from Sensor.
Definition at line 127 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.
|
overridevirtual |
encoder initialise pins
Reimplemented from Sensor.
Definition at line 181 of file Encoder.cpp.
|
overridevirtual |
returns 0 if it does need search for absolute zero 0 - encoder without index 1 - encoder with index
Reimplemented from Sensor.
Definition at line 169 of file Encoder.cpp.
|
overridevirtual |
Updates the sensor values by reading the hardware sensor. Some implementations may work with interrupts, and not need this. The base implementation calls getSensorAngle(), and updates internal fields for angle, timestamp and full rotations. This method must be called frequently enough to guarantee that full rotations are not "missed" due to infrequent polling. Override in subclasses if alternative behaviours are required for your sensor hardware.
Reimplemented from Sensor.
Definition at line 103 of file Encoder.cpp.
| Pullup Encoder::pullup |
| Quadrature Encoder::quadrature |