JMotor
Loading...
Searching...
No Matches
JEncoderPWMAbsoluteAttachInterrupt.h
Go to the documentation of this file.
2#include <Arduino.h>
3#ifndef J_ENCODER_PWM_ABSOLUTE_ATTACH_INTERRUPT_H
4#define J_ENCODER_PWM_ABSOLUTE_ATTACH_INTERRUPT_H
5
14public:
26 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)
27 : JEncoderPWMAbsolute(_encoderPin, _ps, _reverse, _distPerCountFactor, _velEnoughTime, _velEnoughTicks, _resetAngleOnStart, _zeroPos)
28 {
29 }
30
31 void setUpInterrupts(void (*_isrPointer)(void))
32 {
33 pinMode(encoderPin, INPUT);
34 attachInterrupt(encoderPin, _isrPointer, CHANGE);
35 }
37 {
38 detachInterrupt(encoderPin);
39 }
40};
41#endif
uses attachInterrupt() (could be used with standard avr arduinos but only with pins that support atta...
Definition JEncoderPWMAbsoluteAttachInterrupt.h:13
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
Definition JEncoderPWMAbsoluteAttachInterrupt.h:26
void setUpInterrupts(void(*_isrPointer)(void))
set up pins and interrupts
Definition JEncoderPWMAbsoluteAttachInterrupt.h:31
void turnOffInterrupts()
disable interrupts and stop monitoring encoder
Definition JEncoderPWMAbsoluteAttachInterrupt.h:36
reads a PWM signal from an absolute encoder
Definition JEncoderPWMAbsolute.h:23
byte encoderPin
Definition JEncoderPWMAbsolute.h:56
struct for holding parameters for reading PWM Absolute Encoders
Definition JEncoderPWMAbsolute.h:28