diff options
Diffstat (limited to 'arduino/libraries/RotaryEncoder')
11 files changed, 775 insertions, 0 deletions
diff --git a/arduino/libraries/RotaryEncoder/LICENSE b/arduino/libraries/RotaryEncoder/LICENSE new file mode 100755 index 0000000..19a9cd8 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2016 Adafruit Industries + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/arduino/libraries/RotaryEncoder/RotaryEncoder.cpp b/arduino/libraries/RotaryEncoder/RotaryEncoder.cpp new file mode 100755 index 0000000..64e612a --- /dev/null +++ b/arduino/libraries/RotaryEncoder/RotaryEncoder.cpp @@ -0,0 +1,206 @@ +/**************************************************************************/ +/*! + @file HardwareEncoder.cpp + @author hathach (tinyusb.org) + + @section LICENSE + + Software License Agreement (BSD License) + + Copyright (c) 2018, Adafruit Industries (adafruit.com) + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + 1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + 3. Neither the name of the copyright holders nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +/**************************************************************************/ + +#include "RotaryEncoder.h" + +class HwRotaryEncoder RotaryEncoder; + +extern "C" +{ + void QDEC_IRQHandler(void); +} + +/** + * Initialize Hardware Encoder + */ +void HwRotaryEncoder::begin(uint8_t pina, uint8_t pinb, int8_t pinled) +{ + // default sample period + NRF_QDEC->SAMPLEPER = QDEC_SAMPLEPER_SAMPLEPER_128us; + + pinMode(pina, INPUT_PULLUP); + pinMode(pinb, INPUT_PULLUP); + + NRF_QDEC->PSEL.A = g_ADigitalPinMap[pina]; + NRF_QDEC->PSEL.B = g_ADigitalPinMap[pinb]; + + if ( pinled >= 0 ) + { + pinMode(pinled, INPUT); + + NRF_QDEC->PSEL.LED = g_ADigitalPinMap[pinled]; + } + + // Disable debounce by default + NRF_QDEC->DBFEN = 0; + + // Reporter is disabled by default + +} + +void HwRotaryEncoder::start(void) +{ + // Enable IRQ + if ( NRF_QDEC->INTENSET ) + { + NVIC_ClearPendingIRQ(QDEC_IRQn); + NVIC_EnableIRQ(QDEC_IRQn); + } + + // Enable + NRF_QDEC->ENABLE = 1; + + // Start + NRF_QDEC->TASKS_START = 1; +} + +void HwRotaryEncoder::stop(void) +{ + if ( NRF_QDEC->INTENSET ) + { + NVIC_DisableIRQ(QDEC_IRQn); + } + + // Stop + NRF_QDEC->TASKS_STOP = 1; + + // Disable + NRF_QDEC->ENABLE = 0; +} + + +/** + * * @param sample_period + * @param period value is QDEC_SAMPLEPER_SAMPLEPER_xxx in nrf52_bitfields.h + */ +void HwRotaryEncoder::setSampler(uint8_t period) +{ + NRF_QDEC->SAMPLEPER = period; +} + +void HwRotaryEncoder::setDebounce(bool enable) +{ + NRF_QDEC->DBFEN = enable; +} + +void HwRotaryEncoder::setReporter(int8_t sample_num) +{ + // Disable + if (sample_num < 0) + { + NRF_QDEC->INTENCLR = QDEC_INTENCLR_REPORTRDY_Msk; + NRF_QDEC->SHORTS &= ~QDEC_SHORTS_REPORTRDY_READCLRACC_Msk; + }else + { + NRF_QDEC->REPORTPER = sample_num; + NRF_QDEC->INTENSET = QDEC_INTENSET_REPORTRDY_Msk; + + // shortcut + NRF_QDEC->SHORTS |= QDEC_SHORTS_REPORTRDY_READCLRACC_Msk; + } +} + +void HwRotaryEncoder::setCallback(callback_t fp) +{ + _cb = fp; + + if (fp) + { + NRF_QDEC->INTENSET = QDEC_INTENSET_SAMPLERDY_Msk; + }else + { + NRF_QDEC->INTENCLR = QDEC_INTENCLR_SAMPLERDY_Msk; + } +} + +int32_t HwRotaryEncoder::read(void) +{ + // Trigger READ CLR ACC + NRF_QDEC->TASKS_RDCLRACC = 1; + + // Nordic QDEC CW is negative, CCW is positive --> invert + int32_t val = -(NRF_QDEC->ACCREAD); + + // Add to absolute value and buffered step + _abs += val; + + int32_t diff = (_abs - _last) / 2; + + if ( diff ) _last = _abs; + return diff; +} + +int32_t HwRotaryEncoder::readDebug(void) +{ + return _abs; +} + +int32_t HwRotaryEncoder::readAbs(void) +{ + // first update the abs value + read(); + + return _abs/2; +} + +void HwRotaryEncoder::writeAbs(int32_t value) +{ + _abs = value; +} + +void HwRotaryEncoder::clearAbs(void) +{ + _abs = 0; +} + +void HwRotaryEncoder::_irq_handler(void) +{ + if ( (NRF_QDEC->INTENSET & QDEC_INTENSET_SAMPLERDY_Msk) && NRF_QDEC->EVENTS_SAMPLERDY ) + { + NRF_QDEC->EVENTS_SAMPLERDY = 0; + + if ( _cb ) + { + int32_t step = read(); + if ( step ) ada_callback_fromISR(NULL, _cb, step); + } + } +} + +void QDEC_IRQHandler(void) +{ + RotaryEncoder._irq_handler(); +} diff --git a/arduino/libraries/RotaryEncoder/RotaryEncoder.h b/arduino/libraries/RotaryEncoder/RotaryEncoder.h new file mode 100755 index 0000000..8a7e8b3 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/RotaryEncoder.h @@ -0,0 +1,85 @@ +/**************************************************************************/ +/*! + @file HarwareEncoder.h + @author hathach (tinyusb.org) + + @section LICENSE + + Software License Agreement (BSD License) + + Copyright (c) 2018, Adafruit Industries (adafruit.com) + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + 1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + 3. Neither the name of the copyright holders nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +/**************************************************************************/ +#ifndef ROTARYENCODER_H_ +#define ROTARYENCODER_H_ + +#include "Arduino.h" +#include "SwRotaryEncoder.h" + +class HwRotaryEncoder +{ + public: + typedef void (*callback_t) (int step); + + HwRotaryEncoder(void) + { + _abs = _last = 0; + _cb = NULL; + } + + void begin(uint8_t pina, uint8_t pinb, int8_t pinled = -1); + + void setSampler(uint8_t period); + void setDebounce(bool enable); + void setReporter(int8_t sample_num); + void setCallback(callback_t fp); + + void start(void); + void stop(void); + + int32_t read(void); + int32_t readAbs(void); + void writeAbs(int32_t value); + void clearAbs(void); + + + int32_t readDebug(void); + + // Internal API + void _irq_handler(void); + + private: + // Note For each turn, encoder generate 2 transitions + int32_t _abs; // Absolute position + int32_t _last; + + callback_t _cb; +}; + +extern class HwRotaryEncoder RotaryEncoder; + + +#endif /* ROTARYENCODER_H_ */ diff --git a/arduino/libraries/RotaryEncoder/SwRotaryEncoder.cpp b/arduino/libraries/RotaryEncoder/SwRotaryEncoder.cpp new file mode 100755 index 0000000..ebab7e1 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/SwRotaryEncoder.cpp @@ -0,0 +1,148 @@ +/**************************************************************************/ +/*! + @file SwRotaryEncoder.cpp + @author hathach (tinyusb.org) + + @section LICENSE + + Software License Agreement (BSD License) + + Copyright (c) 2018, Adafruit Industries (adafruit.com) + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + 1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + 3. Neither the name of the copyright holders nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +/**************************************************************************/ + +#include "SwRotaryEncoder.h" + +void _pina_irq(uint8_t id); + +#define _pina_irqn(n) \ + void _pina_irqn##_##n(void) { \ + _pina_irq(n);\ + } + +extern "C" +{ + _pina_irqn(0) + _pina_irqn(1) + _pina_irqn(2) + _pina_irqn(3) +// _pina_irqn(4) +// _pina_irqn(5) +// _pina_irqn(6) +// _pina_irqn(7) + // add more to match SW_ROTARY_ENCODER_MAX_INSTANCE +} + +static uint8_t _encoder_count = 0; +static SwRotaryEncoder* _encoder_ptr[SW_ROTARY_ENCODER_MAX_INSTANCE] = { NULL }; + +static voidFuncPtr _pina_irq_ptr[SW_ROTARY_ENCODER_MAX_INSTANCE] = +{ + _pina_irqn_0, _pina_irqn_1, _pina_irqn_2, _pina_irqn_3, +// _pina_irqn_4, _pina_irqn_5, _pina_irqn_6, _pina_irqn_7 +}; + +bool SwRotaryEncoder::begin(uint8_t pina, uint8_t pinb) +{ + // Add to pointer array + VERIFY ( _encoder_count < SW_ROTARY_ENCODER_MAX_INSTANCE); + _encoder_ptr[_encoder_count] = this; + + _pina = pina; + _pinb = pinb; + + pinMode(_pina, INPUT_PULLUP); + pinMode(_pinb, INPUT_PULLUP); + + _a_last = digitalRead(_pina); + + attachInterrupt(_pina, _pina_irq_ptr[_encoder_count], CHANGE); + + _encoder_count++; + + return true; +} + +void SwRotaryEncoder::setCallback(callback_t fp) +{ + _cb = fp; +} + +void SwRotaryEncoder::stop(void) +{ + detachInterrupt(_pina); +} + +int32_t SwRotaryEncoder::read(void) +{ + int32_t ret = _abs - _last_read; + _last_read = _abs; + return ret; +} + +int32_t SwRotaryEncoder::readAbs(void) +{ + return _abs; +} + +void SwRotaryEncoder::writeAbs(int32_t value) +{ + _abs = value; +} + +void SwRotaryEncoder::clearAbs(void) +{ + _abs = 0; +} + +void SwRotaryEncoder::_irq_handler(void) +{ + uint32_t val = NRF_GPIO->IN; + uint8_t bita = bitRead(val, _pina); + + if ( bita != _a_last) + { + int32_t step; + + if ( bita != bitRead(val, _pinb) ) + { + step = 1; + }else + { + step = -1; + } + + _abs += step; + _a_last = bita; + + if (_cb) ada_callback_fromISR(NULL, _cb, step); + } +} + +void _pina_irq(uint8_t id) +{ + _encoder_ptr[id]->_irq_handler(); +} diff --git a/arduino/libraries/RotaryEncoder/SwRotaryEncoder.h b/arduino/libraries/RotaryEncoder/SwRotaryEncoder.h new file mode 100755 index 0000000..737251b --- /dev/null +++ b/arduino/libraries/RotaryEncoder/SwRotaryEncoder.h @@ -0,0 +1,83 @@ +/**************************************************************************/ +/*! + @file SwRotaryEncoder.h + @author hathach (tinyusb.org) + + @section LICENSE + + Software License Agreement (BSD License) + + Copyright (c) 2018, Adafruit Industries (adafruit.com) + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + 1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + 3. Neither the name of the copyright holders nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +/**************************************************************************/ +#ifndef SWROTARYENCODER_H_ +#define SWROTARYENCODER_H_ + +#include "Arduino.h" + +#define SW_ROTARY_ENCODER_MAX_INSTANCE 4 + +class SwRotaryEncoder +{ + public: + typedef void (*callback_t) (int step); + + SwRotaryEncoder(void) + { + _pina = _pinb = 0; + + _a_last = 0; + _last_read = _abs = 0; + + _cb = NULL; + } + + bool begin(uint8_t pina, uint8_t pinb); + void setCallback(callback_t fp); + void stop(void); + + int32_t read(void); + int32_t readAbs(void); + void writeAbs(int32_t value); + void clearAbs(void); + + // Internal API + void _irq_handler(void); + + private: + uint8_t _pina, _pinb; + + uint8_t _a_last; + + int32_t _abs; + int32_t _last_read; // debouncing + + callback_t _cb; +}; + + + +#endif /* SWROTARYENCODER_H_ */ diff --git a/arduino/libraries/RotaryEncoder/examples/HwEncoderCallback/HwEncoderCallback.ino b/arduino/libraries/RotaryEncoder/examples/HwEncoderCallback/HwEncoderCallback.ino new file mode 100755 index 0000000..b035423 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/examples/HwEncoderCallback/HwEncoderCallback.ino @@ -0,0 +1,54 @@ +/********************************************************************* + This is an example for our nRF52 based Bluefruit LE modules + + Pick one up today in the adafruit shop! + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + MIT license, check LICENSE for more information + All text above, and the splash screen below must be included in + any redistribution +*********************************************************************/ + +#include <Arduino.h> +#include "RotaryEncoder.h" + +#define PIN_A A0 +#define PIN_B A1 + +void setup() +{ + Serial.begin(115200); + while ( !Serial ) delay(10); // for nrf52840 with native usb + + Serial.println("Bluefruit52 HW Rotary Encoder Callback Example"); + Serial.println("----------------------------------------------\n"); + + // Initialize Encoder + RotaryEncoder.begin(PIN_A, PIN_B); + + // Set callback + RotaryEncoder.setCallback(encoder_callback); + + // Start encoder + RotaryEncoder.start(); +} + +void loop() +{ + // do nothing +} + +void encoder_callback(int step) +{ + if ( step > 0 ) + { + Serial.println("Right"); + }else + { + Serial.println("Left"); + } +} + diff --git a/arduino/libraries/RotaryEncoder/examples/HwEncoderPoll/HwEncoderPoll.ino b/arduino/libraries/RotaryEncoder/examples/HwEncoderPoll/HwEncoderPoll.ino new file mode 100755 index 0000000..c9ea4c3 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/examples/HwEncoderPoll/HwEncoderPoll.ino @@ -0,0 +1,50 @@ +/********************************************************************* + This is an example for our nRF52 based Bluefruit LE modules + + Pick one up today in the adafruit shop! + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + MIT license, check LICENSE for more information + All text above, and the splash screen below must be included in + any redistribution +*********************************************************************/ + +#include <Arduino.h> +#include "RotaryEncoder.h" + +#define PIN_A A0 +#define PIN_B A1 + +void setup() +{ + Serial.begin(115200); + while ( !Serial ) delay(10); // for nrf52840 with native usb + + Serial.println("Bluefruit52 HW Rotary Encoder Polling Example"); + Serial.println("---------------------------------------------\n"); + + // Initialize Encoder + RotaryEncoder.begin(PIN_A, PIN_B); + + // Start encoder + RotaryEncoder.start(); +} + +void loop() +{ + int value = RotaryEncoder.read(); + + if (value) + { + if ( value > 0 ) + { + Serial.println("Right"); + }else + { + Serial.println("Left"); + } + } +} diff --git a/arduino/libraries/RotaryEncoder/examples/SwEncoderCallback/SwEncoderCallback.ino b/arduino/libraries/RotaryEncoder/examples/SwEncoderCallback/SwEncoderCallback.ino new file mode 100755 index 0000000..86b0068 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/examples/SwEncoderCallback/SwEncoderCallback.ino @@ -0,0 +1,50 @@ +/********************************************************************* + This is an example for our nRF52 based Bluefruit LE modules + + Pick one up today in the adafruit shop! + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + MIT license, check LICENSE for more information + All text above, and the splash screen below must be included in + any redistribution +*********************************************************************/ + +#include <Arduino.h> +#include "RotaryEncoder.h" + +#define PIN_A A0 +#define PIN_B A1 + +SwRotaryEncoder swEncoder; + +void setup() +{ + Serial.begin(115200); + while ( !Serial ) delay(10); // for nrf52840 with native usb + + Serial.println("Bluefruit52 SW Rotary Encoder Callback Example"); + Serial.println("----------------------------------------------\n"); + + // Initialize Encoder + swEncoder.begin(PIN_A, PIN_B); + swEncoder.setCallback(encoder_callback); +} + +void loop() +{ + // do nothing +} + +void encoder_callback(int step) +{ + if ( step > 0 ) + { + Serial.println("Right"); + }else + { + Serial.println("Left"); + } +} diff --git a/arduino/libraries/RotaryEncoder/examples/SwEncoderPoll/SwEncoderPoll.ino b/arduino/libraries/RotaryEncoder/examples/SwEncoderPoll/SwEncoderPoll.ino new file mode 100755 index 0000000..2b9c194 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/examples/SwEncoderPoll/SwEncoderPoll.ino @@ -0,0 +1,49 @@ +/********************************************************************* + This is an example for our nRF52 based Bluefruit LE modules + + Pick one up today in the adafruit shop! + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + MIT license, check LICENSE for more information + All text above, and the splash screen below must be included in + any redistribution +*********************************************************************/ + +#include <Arduino.h> +#include "RotaryEncoder.h" + +#define PIN_A A0 +#define PIN_B A1 + +SwRotaryEncoder swEncoder; + +void setup() +{ + Serial.begin(115200); + while ( !Serial ) delay(10); // for nrf52840 with native usb + + Serial.println("Bluefruit52 SW Rotary Encoder Polling Example"); + Serial.println("---------------------------------------------\n"); + + // Initialize Encoder + swEncoder.begin(PIN_A, PIN_B); +} + +void loop() +{ + int value = swEncoder.read(); + + if (value) + { + if ( value > 0 ) + { + Serial.println("Right"); + }else + { + Serial.println("Left"); + } + } +} diff --git a/arduino/libraries/RotaryEncoder/keywords.txt b/arduino/libraries/RotaryEncoder/keywords.txt new file mode 100755 index 0000000..b81e9a5 --- /dev/null +++ b/arduino/libraries/RotaryEncoder/keywords.txt @@ -0,0 +1,19 @@ +####################################### +# Datatypes (KEYWORD1) +####################################### + +HwRotaryEncoder KEYWORD1 +SwRotaryEncoder KEYWORD1 + +####################################### +# Methods (KEYWORD2) +####################################### + +setSampler KEYWORD2 +setDebounce KEYWORD2 +setReporter KEYWORD2 +setCallback KEYWORD2 +read KEYWORD2 +readAbs KEYWORD2 +writeAbs KEYWORD2 +clearAbs KEYWORD2 diff --git a/arduino/libraries/RotaryEncoder/library.properties b/arduino/libraries/RotaryEncoder/library.properties new file mode 100755 index 0000000..05df2dc --- /dev/null +++ b/arduino/libraries/RotaryEncoder/library.properties @@ -0,0 +1,10 @@ +name=Rotary Encoder +version=0.7.5 +author=Adafruit +maintainer=Adafruit <info@adafruit.com> +sentence=Arduino library for nRF52-based Adafruit Bluefruit LE modules +paragraph=Arduino library for nRF52-based Adafruit Bluefruit LE modules +category=Communication +url=https://github.com/adafruit/Adafruit_nRF52_Arduino +architectures=* +includes=HardwareEncoder.h |