JMotor
Loading...
Searching...
No Matches
Public Member Functions | List of all members
JEncoderPWMAbsolutePinChange Class Reference

uses a pin change interrupt library to support more pins than attachInterrupt(). More...

#include <JEncoderPWMAbsolutePinChange.h>

Inheritance diagram for JEncoderPWMAbsolutePinChange:
Inheritance graph
[legend]
Collaboration diagram for JEncoderPWMAbsolutePinChange:
Collaboration graph
[legend]

Public Member Functions

 JEncoderPWMAbsolutePinChange (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
 
- Public Member Functions inherited from 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)
 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 ()
 
- Public Member Functions inherited from JEncoder
virtual void setRev (bool _rev)
 empty function for directionless encoders to override
 

Additional Inherited Members

- Protected Attributes inherited from JEncoderPWMAbsolute
byte encoderPin
 

Detailed Description

uses a pin change interrupt library to support more pins than attachInterrupt().

Interrupt library (tested with v1.1.0): https://github.com/GreyGnome/EnableInterrupt
platform: AVR (standard Arduinos)

Note
make sure to call setUpInterrupts() when your code starts

Constructor & Destructor Documentation

◆ JEncoderPWMAbsolutePinChange()

JEncoderPWMAbsolutePinChange::JEncoderPWMAbsolutePinChange ( 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
_encoderPinpin 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 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

Member Function Documentation

◆ setUpInterrupts()

void JEncoderPWMAbsolutePinChange::setUpInterrupts ( void(*)(void)  _isrPointer)
inlinevirtual

set up pins and interrupts

Parameters
_isrPointerglobal function that calls internal ISR

Reimplemented from JEncoderPWMAbsolute.

◆ turnOffInterrupts()

void JEncoderPWMAbsolutePinChange::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: