RSeries astromech firmware
RotaryEncoder Class Reference

#include <encoder/RotaryEncoder.h>

Detailed Description

Decodes the signals from a rotary encoder (quadrature pulses) and translates them into a counter position.

+ Inheritance diagram for RotaryEncoder:
+ Collaboration diagram for RotaryEncoder:

Public Types

enum  Direction { Direction::kNoRotation = 0, Direction::kClockwise = 1, Direction::kCounterClockwise = -1 }
 
enum  LatchMode { LatchMode::kFour3 = 1, LatchMode::kFour0 = 2, LatchMode::kTwo03 = 3 }
 

Public Member Functions

 RotaryEncoder (byte pin1, byte pin2, LatchMode mode=LatchMode::kFour0, bool useInterrupt=true)
 
virtual void setup () override
 Subclasses must implement this function to perform any necessary setup that cannot happen in the constructor. More...
 
virtual void animate () override
 Subclasses must implement this function to run through a single frame of animation/activity. More...
 
void begin ()
 
void end ()
 
bool hasChanged ()
 Returns true if value has changed since last animated event. More...
 
long getValue ()
 Returns current value. More...
 
bool isActive ()
 Returns true if recently used (<250ms) More...
 
Direction getDirection ()
 Return the direction the knob was rotated last time. More...
 
void setValue (long newValue)
 Sets the current value. More...
 
uint32_t getMillisBetweenRotations () const
 Returns time in milliseconds between the current observed. More...
 
uint32_t getRPM ()
 Returns the RPM. More...
 
- Public Member Functions inherited from SetupEvent
 SetupEvent ()
 Default Constructor. More...
 

Protected Member Functions

virtual void interrupt () override
 

Additional Inherited Members

- Static Public Member Functions inherited from SetupEvent
static void ready ()
 Calls setup() for each created AnimatedEvent subclass. More...
 

Member Enumeration Documentation

◆ Direction

Enumerator
kNoRotation 
kClockwise 
kCounterClockwise 

◆ LatchMode

Enumerator
kFour3 
kFour0 
kTwo03 

Constructor & Destructor Documentation

◆ RotaryEncoder()

RotaryEncoder::RotaryEncoder ( byte  pin1,
byte  pin2,
LatchMode  mode = LatchMode::kFour0,
bool  useInterrupt = true 
)
inline

Member Function Documentation

◆ animate()

virtual void RotaryEncoder::animate ( )
inlineoverridevirtual

Subclasses must implement this function to run through a single frame of animation/activity.

Subclasses should not call delay() or otherwise block.

Implements AnimatedEvent.

Reimplemented in AnoRotaryEncoder.

◆ begin()

void RotaryEncoder::begin ( )
inline

◆ end()

void RotaryEncoder::end ( )
inline

◆ getDirection()

Direction RotaryEncoder::getDirection ( )
inline

Return the direction the knob was rotated last time.

◆ getMillisBetweenRotations()

uint32_t RotaryEncoder::getMillisBetweenRotations ( ) const
inline

Returns time in milliseconds between the current observed.

◆ getRPM()

uint32_t RotaryEncoder::getRPM ( )
inline

Returns the RPM.

◆ getValue()

long RotaryEncoder::getValue ( )
inline

Returns current value.

◆ hasChanged()

bool RotaryEncoder::hasChanged ( )
inline

Returns true if value has changed since last animated event.

◆ interrupt()

virtual void RotaryEncoder::interrupt ( )
inlineoverrideprotectedvirtual

Implements PinInterruptHandler.

◆ isActive()

bool RotaryEncoder::isActive ( )
inline

Returns true if recently used (<250ms)

◆ setup()

virtual void RotaryEncoder::setup ( )
inlineoverridevirtual

Subclasses must implement this function to perform any necessary setup that cannot happen in the constructor.

Implements SetupEvent.

◆ setValue()

void RotaryEncoder::setValue ( long  newValue)
inline

Sets the current value.


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