![]() |
SimpleFOClibrary
2.1
|
#include <HallSensor.h>
Public Member Functions | |
HallSensor (int encA, int encB, int encC, int pp) | |
void | init () |
void | enableInterrupts (void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doC)()=nullptr) |
void | handleA () |
void | handleB () |
void | handleC () |
float | getAngle () override |
float | getVelocity () override |
void | attachSectorCallback (void(*onSectorChange)(int a)=nullptr) |
![]() | |
virtual int | needsSearch () |
Public Attributes | |
int | pinA |
HallSensor hardware pin A. More... | |
int | pinB |
HallSensor hardware pin B. More... | |
int | pinC |
HallSensor hardware pin C. More... | |
Pullup | pullup |
Configuration parameter internal or external pullups. More... | |
float | cpr |
HallSensor cpr number. More... | |
Direction | direction |
volatile int8_t | hall_state |
volatile int8_t | electric_sector |
volatile long | electric_rotations |
volatile long | total_interrupts |
Definition at line 12 of file HallSensor.h.
HallSensor::HallSensor | ( | int | encA, |
int | encB, | ||
int | encC, | ||
int | pp | ||
) |
HallSensor class constructor
encA | HallSensor A pin |
encB | HallSensor B pin |
encC | HallSensor C pin |
pp | pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp) |
index | index pin number (optional input) |
Definition at line 9 of file HallSensor.cpp.
void HallSensor::attachSectorCallback | ( | void(*)(int a) | onSectorChange = nullptr | ) |
Optionally set a function callback to be fired when sector changes void onSectorChange(int sector) { ... // for debug or call driver directly? } sensor.attachSectorCallback(onSectorChange);
Definition at line 91 of file HallSensor.cpp.
void HallSensor::enableInterrupts | ( | void(*)() | doA = nullptr , |
void(*)() | doB = nullptr , |
||
void(*)() | doC = nullptr |
||
) |
function enabling hardware interrupts for the HallSensor 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 144 of file HallSensor.cpp.
|
overridevirtual |
|
overridevirtual |
get current angular velocity (rad/s)
Reimplemented from Sensor.
Definition at line 106 of file HallSensor.cpp.
void HallSensor::handleA | ( | ) |
A channel callback function
Definition at line 25 of file HallSensor.cpp.
void HallSensor::handleB | ( | ) |
B channel callback function
Definition at line 30 of file HallSensor.cpp.
void HallSensor::handleC | ( | ) |
C channel callback function
Definition at line 36 of file HallSensor.cpp.
void HallSensor::init | ( | ) |
HallSensor initialise pins
Definition at line 117 of file HallSensor.cpp.
float HallSensor::cpr |
HallSensor cpr number.
Definition at line 53 of file HallSensor.h.
Direction HallSensor::direction |
Definition at line 62 of file HallSensor.h.
volatile long HallSensor::electric_rotations |
Definition at line 71 of file HallSensor.h.
volatile int8_t HallSensor::electric_sector |
Definition at line 69 of file HallSensor.h.
volatile int8_t HallSensor::hall_state |
Definition at line 67 of file HallSensor.h.
int HallSensor::pinA |
HallSensor hardware pin A.
Definition at line 47 of file HallSensor.h.
int HallSensor::pinB |
HallSensor hardware pin B.
Definition at line 48 of file HallSensor.h.
int HallSensor::pinC |
HallSensor hardware pin C.
Definition at line 49 of file HallSensor.h.
Pullup HallSensor::pullup |
Configuration parameter internal or external pullups.
Definition at line 52 of file HallSensor.h.
volatile long HallSensor::total_interrupts |
Definition at line 73 of file HallSensor.h.