reads a PWM signal from an absolute encoder
More...
#include <JEncoderPWMAbsolute.h>
|
struct | pwmSettings |
| struct for holding parameters for reading PWM Absolute Encoders More...
|
|
|
| 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
|
|
virtual void | setUpInterrupts (void(*_isrPointer)(void)) |
| set up pins and interrupts
|
|
virtual void | turnOffInterrupts () |
| disable interrupts and stop monitoring 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
|
|
reads a PWM signal from an absolute encoder
tested with https://ams.com/as0548b
- Note
- platform: esp32, teensy
(could be used with standard avr arduinos but only with pins that support attachInterrupt())
◆ JEncoderPWMAbsolute()
JEncoderPWMAbsolute::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 |
|
) |
| |
|
inline |
sets pins and settings for reading the encoder
- Parameters
-
_encoderPin | pin to read encoder signal with |
_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 (in MICROseconds) 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 (in encoder units) |
_zeroPos | (default=0) change what angle of the absolute encoder is considered zero. set _resetAngleOnStart to false to keep setting from being overridden |
◆ encoderISR()
void JEncoderPWMAbsolute::encoderISR |
( |
| ) |
|
|
inline |
◆ getCounter()
long JEncoderPWMAbsolute::getCounter |
( |
| ) |
|
|
inlinevirtual |
returns how far the encoder has turned from the zero position
- Note
- remember that variables overflow
- Return values
-
Reimplemented from JEncoder.
◆ getDistPerCountFactor()
float JEncoderPWMAbsolute::getDistPerCountFactor |
( |
| ) |
|
|
inlinevirtual |
returns a conversion factor between encoder ticks and distance that can be set for the encoder
- Note
- default is 1.0
- Return values
-
(float) | distPerCountFactor |
Reimplemented from JEncoder.
◆ getPos()
float JEncoderPWMAbsolute::getPos |
( |
| ) |
|
|
inlinevirtual |
returns how far the encoder has turned from the zero position converted to distance
- Note
- remember that variables overflow (counter) and that floats have limited precision
- Return values
-
(float) | encoder ticks converted to distance |
Reimplemented from JEncoder.
◆ getVel()
float JEncoderPWMAbsolute::getVel |
( |
| ) |
|
|
inlinevirtual |
calculates velocity in distance per second where distance was set by setdistPerCountFactor()
- Return values
-
Reimplemented from JEncoder.
◆ hasDirection()
bool JEncoderPWMAbsolute::hasDirection |
( |
| ) |
|
|
inlinevirtual |
can this encoder measure direction or just speed
- Return values
-
(bool) | true = can measure direction |
Reimplemented from JEncoder.
◆ intTurns()
long JEncoderPWMAbsolute::intTurns |
( |
| ) |
|
|
inline |
how many full turns the encoder has made.
- Note
- this and rawReading can be used as an alternative to getPos if the limited precision of a float is a concern
- Return values
-
(long) | how far the encoder has turned |
◆ isVelNew()
bool JEncoderPWMAbsolute::isVelNew |
( |
| ) |
|
|
inlinevirtual |
could be useful for only recalculating a control loop if there's new velocity data
- Return values
-
(bool) | true if velocity has changed since this function was last called |
Reimplemented from JEncoder.
◆ rawReading()
int JEncoderPWMAbsolute::rawReading |
( |
| ) |
|
|
inline |
- Note
- divide by RESOLUTION to get fraction of full turn
- Return values
-
the | angle reading from the sensor [0, RESOLUTION) (but negative if reverse is true) |
◆ run()
void JEncoderPWMAbsolute::run |
( |
| ) |
|
|
inlinevirtual |
- Note
- call this function as frequently as possible or this code can't keep track of how many times the encoder has turned
Reimplemented from JEncoder.
◆ setDistPerCountFactor()
void JEncoderPWMAbsolute::setDistPerCountFactor |
( |
float |
_factor | ) |
|
|
inlinevirtual |
- Note
- for the purposes of setting this factor a "count" is considered a full revolution of the absolute encoder. it is converted to actual counts within this function
Reimplemented from JEncoder.
◆ setUpInterrupts()
virtual void JEncoderPWMAbsolute::setUpInterrupts |
( |
void(*)(void) |
_isrPointer | ) |
|
|
virtual |
◆ setZeroPos()
bool JEncoderPWMAbsolute::setZeroPos |
( |
uint16_t |
zeroAngle | ) |
|
|
inline |
change what angle of the absolute encoder is zero
- Note
- this will cause distance to jump some
- Parameters
-
zeroAngle | [0,ps.RESOLUTION-1) |
- Return values
-
(bool) | did the zeroAngle change |
◆ turnOffInterrupts()
virtual void JEncoderPWMAbsolute::turnOffInterrupts |
( |
| ) |
|
|
virtual |
◆ zeroCounter() [1/2]
long JEncoderPWMAbsolute::zeroCounter |
( |
| ) |
|
|
inlinevirtual |
reset the counter of how far the encoder has turned
- Return values
-
(long) | returns value of counter before it is reset |
Reimplemented from JEncoder.
◆ zeroCounter() [2/2]
long JEncoderPWMAbsolute::zeroCounter |
( |
bool |
resetAngle | ) |
|
|
inline |
reset the zero point of the encoder
- Parameters
-
resetAngle | (bool) true=set the next read angle as zero, false=reset turns, but leave absolute angle measurement as is |
- Return values
-
(long) | old position (number of turns, not including angle!) |
◆ encoderPin
byte JEncoderPWMAbsolute::encoderPin |
|
protected |
The documentation for this class was generated from the following file: