SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
Encoder Class Reference

#include <Encoder.h>

Inheritance diagram for Encoder:
[legend]
Collaboration diagram for Encoder:
[legend]

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
 

Detailed Description

Definition at line 18 of file Encoder.h.

Constructor & Destructor Documentation

◆ Encoder()

Encoder::Encoder ( int  encA,
int  encB,
float  ppr,
int  index = 0 
)

Encoder class constructor

Parameters
encAencoder B pin
encBencoder B pin
pprimpulses per rotation (cpr=ppr*4)
indexindex pin number (optional input)

Definition at line 11 of file Encoder.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ enableInterrupts()

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

Parameters
doApointer to the A channel interrupt handler function
doBpointer to the B channel interrupt handler function
doIndexpointer to the Index channel interrupt handler function

Definition at line 212 of file Encoder.cpp.

◆ getSensorAngle()

float Encoder::getSensorAngle ( )
overridevirtual

get current angle (rad)

Implements Sensor.

Definition at line 117 of file Encoder.cpp.

◆ getVelocity()

float Encoder::getVelocity ( )
overridevirtual

get current angular velocity (rad/s)

Reimplemented from Sensor.

Definition at line 127 of file Encoder.cpp.

Here is the call graph for this function:

◆ handleA()

void Encoder::handleA ( )

A channel callback function

Definition at line 42 of file Encoder.cpp.

Here is the call graph for this function:

◆ handleB()

void Encoder::handleB ( )

B channel callback function

Definition at line 63 of file Encoder.cpp.

Here is the call graph for this function:

◆ handleIndex()

void Encoder::handleIndex ( )

Index channel callback function

Definition at line 85 of file Encoder.cpp.

◆ init()

void Encoder::init ( )
overridevirtual

encoder initialise pins

Reimplemented from Sensor.

Definition at line 181 of file Encoder.cpp.

Here is the call graph for this function:

◆ needsSearch()

int Encoder::needsSearch ( )
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.

◆ update()

void Encoder::update ( )
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.

Member Data Documentation

◆ cpr

float Encoder::cpr

encoder cpr number

Definition at line 59 of file Encoder.h.

◆ index_pin

int Encoder::index_pin

index pin

Definition at line 54 of file Encoder.h.

◆ pinA

int Encoder::pinA

encoder hardware pin A

Definition at line 52 of file Encoder.h.

◆ pinB

int Encoder::pinB

encoder hardware pin B

Definition at line 53 of file Encoder.h.

◆ pullup

Pullup Encoder::pullup

Configuration parameter internal or external pullups.

Definition at line 57 of file Encoder.h.

◆ quadrature

Quadrature Encoder::quadrature

Configuration parameter enable or disable quadrature mode.

Definition at line 58 of file Encoder.h.


The documentation for this class was generated from the following files: