uses attachInterrupt() (could be used with standard avr arduinos but only with pins that support attachInterrupt())
platform: esp32, teensy
More...
#include <JEncoderPWMAbsoluteAttachInterrupt.h>
|
| JEncoderPWMAbsoluteAttachInterrupt (byte _encoderPin, pwmSettings _ps, bool _reverse=false, float _distPerCountFactor=1.0, unsigned long _velEnoughTime=0, unsigned long _velEnoughTicks=0, bool _resetAngleOnStart=false, uint16_t _zeroPos=0) |
| sets pins and settings for reading the encoder
|
|
void | setUpInterrupts (void(*_isrPointer)(void)) |
| set up pins and interrupts
|
|
void | turnOffInterrupts () |
| disable interrupts and stop monitoring encoder
|
|
| JEncoderPWMAbsolute (byte _encoderPin, pwmSettings _ps, bool _reverse=false, float _distPerCountFactor=1.0, unsigned long _velEnoughTime=0, unsigned long _velEnoughTicks=0, bool _resetAngleOnStart=false, uint16_t _zeroPos=0) |
| sets pins and settings for reading the encoder
|
|
int | rawReading () |
|
long | intTurns () |
| how many full turns the encoder has made.
|
|
long | zeroCounter () |
| reset the counter of how far the encoder has turned
|
|
long | zeroCounter (bool resetAngle) |
| reset the zero point of the encoder
|
|
float | getVel () |
| calculates velocity in distance per second where distance was set by setdistPerCountFactor()
|
|
long | getCounter () |
| returns how far the encoder has turned from the zero position
|
|
float | getPos () |
| returns how far the encoder has turned from the zero position converted to distance
|
|
float | getDistPerCountFactor () |
| returns a conversion factor between encoder ticks and distance that can be set for the encoder
|
|
void | setDistPerCountFactor (float _factor) |
|
bool | hasDirection () |
| can this encoder measure direction or just speed
|
|
bool | isVelNew () |
| could be useful for only recalculating a control loop if there's new velocity data
|
|
bool | setZeroPos (uint16_t zeroAngle) |
| change what angle of the absolute encoder is zero
|
|
void | run () |
|
void | encoderISR () |
|
virtual void | setRev (bool _rev) |
| empty function for directionless encoders to override
|
|
uses attachInterrupt() (could be used with standard avr arduinos but only with pins that support attachInterrupt())
platform: esp32, teensy
- Note
- make sure to call setUpInterrupts() when your code starts
◆ JEncoderPWMAbsoluteAttachInterrupt()
JEncoderPWMAbsoluteAttachInterrupt::JEncoderPWMAbsoluteAttachInterrupt |
( |
byte |
_encoderPin, |
|
|
pwmSettings |
_ps, |
|
|
bool |
_reverse = false , |
|
|
float |
_distPerCountFactor = 1.0 , |
|
|
unsigned long |
_velEnoughTime = 0 , |
|
|
unsigned long |
_velEnoughTicks = 0 , |
|
|
bool |
_resetAngleOnStart = false , |
|
|
uint16_t |
_zeroPos = 0 |
|
) |
| |
|
inline |
sets pins and settings for reading the encoder
- Parameters
-
_encoderPin | pin to read encoder signal with, or, if they are different, interrupt number |
_ps | (struct pwmSettings) parameters of encoder signal |
_reverse | (bool) reverse positive direction, default=false |
_distPerCountFactor | (float) for the purposes of setting this factor a "count" is considered a full revolution of the absolute encoder |
_velEnoughTime | (default=0, no limit) shortest interval between velocity calculations, if run() is called faster the calculation will wait to run |
_velEnoughTicks | (default=0, no limit) if the encoder turns more than this number of steps velocity calculations will be done even if velEnoughTime hasn't been reached |
_resetAngleOnStart | (default=false) zero encoder angle on startup |
_zeroPos | (default=0) change what angle of the absolute encoder is considered zero. set _resetAngleOnStart to false to keep setting from being overridden |
◆ setUpInterrupts()
void JEncoderPWMAbsoluteAttachInterrupt::setUpInterrupts |
( |
void(*)(void) |
_isrPointer | ) |
|
|
inlinevirtual |
set up pins and interrupts
- Parameters
-
_isrPointer | global function that calls internal ISR |
Reimplemented from JEncoderPWMAbsolute.
◆ turnOffInterrupts()
void JEncoderPWMAbsoluteAttachInterrupt::turnOffInterrupts |
( |
| ) |
|
|
inlinevirtual |
disable interrupts and stop monitoring encoder
- Note
- use setUpInterrupts to start encoder again
Reimplemented from JEncoderPWMAbsolute.
The documentation for this class was generated from the following file: