Add some Doxygen documentation to core and libraries (#2780)

This commit is contained in:
Earle F. Philhower, III 2025-03-18 17:00:44 -07:00 committed by GitHub
parent 50b9ea99bd
commit aabbba67ce
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
6 changed files with 525 additions and 31 deletions

View file

@ -20,10 +20,21 @@
#pragma once
/**
@brief Wrapper class for polling the BOOTSEL button
*/
class __Bootsel {
public:
__Bootsel() { }
/**
@brief Get state of the BOOTSEL pin
@returns True if BOOTSEL pushed
*/
operator bool();
};
/**
@brief BOOTSEL accessor instance
*/
extern __Bootsel BOOTSEL;

View file

@ -182,6 +182,9 @@ extern "C" void loop1() __attribute__((weak));
extern "C" bool core1_separate_stack;
extern "C" uint32_t* core1_separate_stack_address;
/**
@brief RP2040/RP2350 helper function for HW-specific features
*/
class RP2040 {
public:
RP2040() { /* noop */ }
@ -207,26 +210,50 @@ public:
#endif
}
// Convert from microseconds to PIO clock cycles
/**
@brief Convert from microseconds to PIO clock cycles
@returns the PIO cycles for a given microsecond delay
*/
static int usToPIOCycles(int us) {
// Parenthesis needed to guarantee order of operations to avoid 32bit overflow
return (us * (clock_get_hz(clk_sys) / 1'000'000));
}
// Get current clock frequency
/**
@brief Gets the active CPU speed (may differ from F_CPU
@returns CPU frequency in Hz
*/
static int f_cpu() {
return clock_get_hz(clk_sys);
}
// Get current CPU core number
/**
@brief Get the core ID that is currently executing this code
@returns 0 for Core 0, 1 for Core 1
*/
static int cpuid() {
return sio_hw->cpuid;
}
// Get CPU cycle count. Needs to do magic to extens 24b HW to something longer
/**
@brief CPU cycle counter epoch (24-bit cycle). For internal use
*/
volatile uint64_t _epoch = 0;
/**
@brief Get the count of CPU clock cycles since power on.
@details
The 32-bit count will overflow every 4 billion cycles, so consider using ``getCycleCount64`` for
longer measurements
@returns CPU clock cycles since power up
*/
inline uint32_t getCycleCount() {
#if !defined(__riscv) && !defined(__PROFILE)
// Get CPU cycle count. Needs to do magic to extend 24b HW to something longer
if (!__isFreeRTOS) {
uint32_t epoch;
uint32_t ctr;
@ -242,7 +269,11 @@ public:
}
#endif
}
/**
@brief Get the count of CPU clock cycles since power on as a 64-bit quantrity
@returns CPU clock cycles since power up
*/
inline uint64_t getCycleCount64() {
#if !defined(__riscv) && !defined(__PROFILE)
if (!__isFreeRTOS) {
@ -261,23 +292,53 @@ public:
#endif
}
/**
@brief Gets total unused heap (dynamic memory)
@details
Note that the allocations of the size of the total free heap may fail due to fragmentation.
For example, ``getFreeHeap`` can report 100KB available, but an allocation of 90KB may fail
because there may not be a contiguous 90KB space available
@returns Free heap in bytes
*/
inline int getFreeHeap() {
return getTotalHeap() - getUsedHeap();
}
/**
@brief Gets total used heap (dynamic memory)
@returns Used heap in bytes
*/
inline int getUsedHeap() {
struct mallinfo m = mallinfo();
return m.uordblks;
}
/**
@brief Gets total heap (dynamic memory) compiled into the program
@returns Total heap size in bytes
*/
inline int getTotalHeap() {
return &__StackLimit - &__bss_end__;
}
/**
@brief On the RP2350, returns the amount of heap (dynamic memory) available in PSRAM
@returns Total free heap in PSRAM, or 0 if no PSRAM present
*/
inline int getFreePSRAMHeap() {
return getTotalPSRAMHeap() - getUsedPSRAMHeap();
}
/**
@brief On the RP2350, returns the total amount of PSRAM heap (dynamic memory) used
@returns Bytes used in PSRAM, or 0 if no PSRAM present
*/
inline int getUsedPSRAMHeap() {
#if defined(RP2350_PSRAM_CS)
extern size_t __psram_total_used();
@ -287,6 +348,11 @@ public:
#endif
}
/**
@brief On the RP2350, gets total heap (dynamic memory) compiled into the program
@returns Total PSRAM heap size in bytes, or 0 if no PSRAM present
*/
inline int getTotalPSRAMHeap() {
#if defined(RP2350_PSRAM_CS)
extern size_t __psram_total_space();
@ -296,6 +362,11 @@ public:
#endif
}
/**
@brief Gets the current stack pointer in a ARM/RISC-V safe manner
@returns Current SP
*/
inline uint32_t getStackPointer() {
uint32_t *sp;
#if defined(__riscv)
@ -306,6 +377,14 @@ public:
return (uint32_t)sp;
}
/**
@brief Calculates approximately how much stack space is still available for the running core. Handles multiprocessing and separate stacks.
@details
Not valid in FreeRTOS. Use the FreeRTOS internal functions to access this information.
@returns Approximation of the amount of stack available for use on the specific core
*/
inline int getFreeStack() {
const unsigned int sp = getStackPointer();
uint32_t ref = 0x20040000;
@ -319,6 +398,11 @@ public:
return sp - ref;
}
/**
@brief On the RP2350, gets the size of attached PSRAM
@returns PSRAM size in bytes, or 0 if no PSRAM present
*/
inline size_t getPSRAMSize() {
#if defined(RP2350_PSRAM_CS)
extern size_t __psram_size;
@ -328,20 +412,48 @@ public:
#endif
}
/**
@brief Freezes the other core in a flash-write-safe state. Not generally needed by applications
@details
When the external flash chip is erasing or writing, the Pico cannot fetch instructions from it.
In this case both the core doing the writing and the other core (if active) need to run from a
routine that's contained in RAM. This call forces the other core into a tight, RAM-based loop
safe for this operation. When flash erase/write is completed, ``resumeOtherCore`` to return
it to operation.
Be sure to disable any interrupts or task switches before calling to avoid deadlocks.
If the second core is not started, this is a no-op.
*/
void idleOtherCore() {
fifo.idleOtherCore();
}
/**
@brief Resumes normal operation of the other core
*/
void resumeOtherCore() {
fifo.resumeOtherCore();
}
/**
@brief Hard resets the 2nd core (CORE1).
@details
Because core1 will restart with the heap and global variables not in the same state as
power-on, this call may not work as desired and a full CPU reset may be necessary in
certain cases.
*/
void restartCore1() {
multicore_reset_core1();
fifo.clear();
multicore_launch_core1(main1);
}
/**
@brief Warm-reboots the chip in normal mode
*/
void reboot() {
watchdog_reboot(0, 0, 10);
while (1) {
@ -349,10 +461,16 @@ public:
}
}
/**
@brief Warm-reboots the chip in normal mode
*/
inline void restart() {
reboot();
}
/**
@brief Warm-reboots the chip into the USB bootloader mode
*/
inline void rebootToBootloader() {
reset_usb_boot(0, 0);
while (1) {
@ -364,16 +482,32 @@ public:
static void enableDoubleResetBootloader();
#endif
/**
@brief Starts the hardware watchdog timer. The CPU will reset if the watchdog is not fed every delay_ms
@param [in] delay_ms Milliseconds without a wdt_reset before rebooting
*/
void wdt_begin(uint32_t delay_ms) {
watchdog_enable(delay_ms, 1);
}
/**
@brief Feeds the watchdog timer, resetting it for another delay_ms countdown
*/
void wdt_reset() {
watchdog_update();
}
/**
@brief Best-effort reasons for chip reset
*/
enum resetReason_t {UNKNOWN_RESET, PWRON_RESET, RUN_PIN_RESET, SOFT_RESET, WDT_RESET, DEBUG_RESET, GLITCH_RESET, BROWNOUT_RESET};
/**
@brief Attempts to determine the reason for the last chip reset. May not always be able to determine accurately
@returns Reason for reset
*/
resetReason_t getResetReason(void) {
io_rw_32 *WD_reason_reg = (io_rw_32 *)(WATCHDOG_BASE + WATCHDOG_REASON_OFFSET);
@ -427,6 +561,10 @@ public:
return UNKNOWN_RESET;
}
/**
@brief Get unique ID string for the running board
@returns String with the unique board ID as determined by the SDK
*/
const char *getChipID() {
static char id[2 * PICO_UNIQUE_BOARD_ID_SIZE_BYTES + 1] = { 0 };
if (!id[0]) {
@ -437,6 +575,17 @@ public:
#pragma GCC push_options
#pragma GCC optimize ("Os")
/**
@brief Perform a memcpy using a DMA engine for speed
@details
Uses the DMA to copy to and from RAM. Only works on 4-byte aligned, 4-byte multiple length
sources and destination (i.e. word-aligned, word-length). Falls back to normal memcpy otherwise.
@param [out] dest Memcpy destination, 4-byte aligned
@param [in] src Memcpy source, 4-byte aligned
@param [in] n Count in bytes to transfer (should be a multiple of 4 bytes)
*/
void *memcpyDMA(void *dest, const void *src, size_t n) {
// Allocate a DMA channel on 1st call, reuse it every call after
if (memcpyDMAChannel < 1) {
@ -465,14 +614,32 @@ public:
}
#pragma GCC pop_options
// Multicore comms FIFO
/**
@brief Multicore communications FIFO
*/
_MFIFO fifo;
/**
@brief Return a 32-bit from the hardware random number generator
@returns Random value using appropriate hardware (RP2350 has true RNG, RP2040 has a less true RNG method)
*/
uint32_t hwrand32() {
return get_rand_32();
}
/**
@brief Determines if code is running on a Pico or a PicoW
@details
Code compiled for the RP2040 PicoW can run on the RP2040 Pico. This call lets an application
identify if the current device is really a Pico or PicoW and handle appropriately. For
the RP2350, this runtime detection is not available and the call returns whether it was
compiled for the CYW43 WiFi driver
@returns True if running on a PicoW board with CYW43 WiFi chip.
*/
bool isPicoW() {
#if !defined(PICO_CYW43_SUPPORTED)
return false;

View file

@ -24,7 +24,9 @@
// Input/output will be handled by OpenOCD
// From https://developer.arm.com/documentation/dui0471/g/Semihosting/Semihosting-operations?lang=en
/**
@brief Semihosting host API opcodes, from https://developer.arm.com/documentation/dui0471/g/Semihosting/Semihosting-operations?lang=en
*/
typedef enum {
SEMIHOST_SYS_CLOSE = 0x02,
SEMIHOST_SYS_CLOCK = 0x10,
@ -52,7 +54,13 @@ typedef enum {
#ifdef __arm__
// From https://github.com/ErichStyger/mcuoneclipse/blob/master/Examples/MCUXpresso/FRDM-K22F/FRDM-K22F_Semihosting/source/McuSemihost.c
/**
@brief Execute a semihosted request, from https://github.com/ErichStyger/mcuoneclipse/blob/master/Examples/MCUXpresso/FRDM-K22F/FRDM-K22F_Semihosting/source/McuSemihost.c
@param [in] reason Opcode to execute
@param [in] arg Any arguments for the opcode
@returns Result of operation
*/
static inline int __attribute__((always_inline)) Semihost(int reason, void *arg) {
int value;
__asm volatile(
@ -69,7 +77,13 @@ static inline int __attribute__((always_inline)) Semihost(int reason, void *arg)
}
#else
// https://groups.google.com/a/groups.riscv.org/g/sw-dev/c/n-5VQ9PHZ4w/m/KbzH5t9MBgAJ
/**
@brief Execute a semihosted request, from https://groups.google.com/a/groups.riscv.org/g/sw-dev/c/n-5VQ9PHZ4w/m/KbzH5t9MBgAJ
@param [in] reason Opcode to execute
@param [in] argPack Any arguments for the opcode
@returns Result of operation
*/
static inline int __attribute__((always_inline)) Semihost(int reason, void *argPack) {
register int value asm("a0") = reason;
register void *ptr asm("a1") = argPack;

View file

@ -22,9 +22,18 @@
#include "SerialPIO.h"
/**
@brief Implements a UART port using PIO for input and output
*/
class SoftwareSerial : public SerialPIO {
public:
// Note the rx/tx pins are swapped in PIO vs SWSerial
/**
@brief Constructs a PIO-based UART
@param [in] rx GPIO for RX pin or -1 for transmit-only
@param [in] tx GPIO for TX pin or -1 for receive-only
@param [in] invert True to invert the receive and transmit lines
*/
SoftwareSerial(pin_size_t rx, pin_size_t tx, bool invert = false) : SerialPIO(tx, rx) {
_invert = invert;
}
@ -32,18 +41,37 @@ public:
~SoftwareSerial() {
}
/**
@brief Starts the PIO UART
@param [in] baud Serial bit rate
*/
virtual void begin(unsigned long baud = 115200) override {
begin(baud, SERIAL_8N1);
};
/**
@brief Starts the PIO UART
@param [in] baud Serial bit rate
@param [in] config Start/Stop/Len configuration (i.e. SERIAL_8N1 or SERIAL_7E2)
*/
void begin(unsigned long baud, uint16_t config) override {
setInvertTX(_invert);
setInvertRX(_invert);
SerialPIO::begin(baud, config);
}
/**
@brief No-op on this core
*/
void listen() { /* noop */ }
/**
@brief No-op on this core
@returns True always
*/
bool isListening() {
return true;
}

View file

@ -25,65 +25,219 @@
#include <hardware/spi.h>
#include "SPIHelper.h"
/**
@brief Implements a hardware-based SPI interface using the Pico's SPI blocks
*/
class SPIClassRP2040 : public arduino::HardwareSPI {
public:
/**
@brief Create a PIO-based SPI instance, pins can be changed before begin() call
@param [in] spi SPI hardware instance (spi0/spi1)
@param [in] rx MISO GPIO
@param [in] cs CS GPIO
@param [in] sck SCK GPIO
@param [in] tx MOSI GPIO
*/
SPIClassRP2040(spi_inst_t *spi, pin_size_t rx, pin_size_t cs, pin_size_t sck, pin_size_t tx);
// Send or receive 8- or 16-bit data. Returns read back value
/**
@brief Send an 8-bit byte of data and return read-back 8-bit value
@param [in] data Data to send
@returns Read back byte from SPI interface
*/
byte transfer(uint8_t data) override;
/**
@brief Send a 16-bit quantity over SPI and return read-back 16-bit value under a single CS assertion
@param [in] data Data to send
@returns Read back 16-bit quantity
*/
uint16_t transfer16(uint16_t data) override;
// Sends buffer in 8 bit chunks. Overwrites buffer with read data
/**
@brief Sends buffer in 8 bit chunks under a single CS. Overwrites buffer with read data
@param [in, out] buf Buffer to read and write back into
@param [in] count Number of bytes to transmit/read
*/
void transfer(void *buf, size_t count) override;
// Sends one buffer and receives into another, much faster! can set rx or txbuf to nullptr
/**
@brief Sends one buffer and receives into another under a single CS. Can set rx or txbuf to nullptr
@param [in] txbuf Buffer to transmit or nullptr to send 0s
@param [out] rxbuf Buffer to read back into or nullptr to ignore returned data
@param [in] count Numbner of bytes to transmit/receive
*/
void transfer(const void *txbuf, void *rxbuf, size_t count) override;
// DMA/asynchronous transfers. Do not combime with synchronous runs or bad stuff will happen
// All buffers must be valid for entire DMA and not touched until `finished()` returns true.
/**
@brief Perform a transfer() using DMA in the background. Returns immediately, need to check for completion
@details
Do not combine asynchronous and synchronous transfers. All buffers must be valid until
the transfer reports that it is completed (``finished`` returns true).
@param [in] send Buffer to transmit, must remain valid through entire operation
@param [out] recv Buffer to receive, must remain valid through entire operation
@param [in] bytes Number of bytes to transfer under single CS
*/
bool transferAsync(const void *send, void *recv, size_t bytes);
bool finishedAsync(); // Call to check if the async operations is completed and the buffer can be reused/read
void abortAsync(); // Cancel an outstanding async operation
/**
@brief Call to check if the async operations is completed and the buffer can be reused/read
@returns True if the asynchronous SPI operation has completed and ``recv`` buffer is valid
*/
bool finishedAsync();
/**
@brief Aborts an ongoing asynchronous SPI operation, if one is still operating
@details
Not normally needed, but in the case where a large, long SPI operation needs to be aborted
this call allows an application to safely stop the SPI and dispose of the ``recv`` and
``send`` buffers
*/
void abortAsync();
// Call before/after every complete transaction
/**
@brief Begin an SPI transaction, sets SPI speed and masks necessary interrupts
@param [in] SPISettings SPI configuration parameters, including the clock speed
*/
void beginTransaction(SPISettings settings) override;
/**
@brief Ends an SPI transaction, unmasks and masked GPIO interrupts
*/
void endTransaction(void) override;
// Assign pins, call before begin()
/**
@brief Sets the MISO(RX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setRX(pin_size_t pin);
/**
@brief Sets the MISO(RX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
inline bool setMISO(pin_size_t pin) {
return setRX(pin);
}
/**
@brief Sets the CS pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setCS(pin_size_t pin);
/**
@brief Sets the SCK pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setSCK(pin_size_t pin);
/**
@brief Sets the MOSI(TX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setTX(pin_size_t pin);
/**
@brief Sets the MOSI(TX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
inline bool setMOSI(pin_size_t pin) {
return setTX(pin);
}
// Call once to init/deinit SPI class, select pins, etc.
/**
@brief Call once to init/deinit SPI class, select pins, etc.
*/
virtual void begin() override {
begin(false);
}
/**
@brief Call once to init/deinit SPI class, select pins, etc.
@param [in] hwCS Pass in true to enable HW-controlled CS. Otherwise application needs to assert/deassert CS.
*/
void begin(bool hwCS);
/**
@brief Call to deinit and disable the SPI interface.
*/
void end() override;
// Deprecated - do not use!
/**
@brief Deprecated, do not use
@param [in] order Deprecated
*/
void setBitOrder(BitOrder order) __attribute__((deprecated));
/**
@brief Deprecated, do not use
@param [in] order Deprecated
*/
void setDataMode(uint8_t uc_mode) __attribute__((deprecated));
/**
@brief Deprecated, do not use
@param [in] order Deprecated
*/
void setClockDivider(uint8_t uc_div) __attribute__((deprecated));
// List of GPIO IRQs to disable during a transaction
/**
@brief Ensure specific GPIO interrupt is disabled during and SPI transaction to protect against re-entrancy. Multiple GPIOs supported by multiple calls.
@param [in] interruptNumber GPIO pin to mask
*/
virtual void usingInterrupt(int interruptNumber) override {
_helper.usingInterrupt(interruptNumber);
}
/**
@brief Remove a GPIO from the masked-during-transaction list.
@param [in] interruptNumber GPIO pin to unmask
*/
virtual void notUsingInterrupt(int interruptNumber) override {
_helper.notUsingInterrupt(interruptNumber);
}
virtual void attachInterrupt() override { /* noop */ }
virtual void detachInterrupt() override { /* noop */ }
/**
@brief Deprecated, do not use
*/
virtual void attachInterrupt() override __attribute__((deprecated)) { /* noop */ }
/**
@brief Deprecated, do not use
*/
virtual void detachInterrupt() override __attribute__((deprecated)) { /* noop */ }
private:
void adjustBuffer(const void *s, void *d, size_t cnt, bool by16);

View file

@ -25,6 +25,9 @@
#include <api/HardwareSPI.h>
#include <hardware/spi.h>
/**
@brief Implements a PIO-based SPI interface without pin restrictions
*/
class SoftwareSPI : public arduino::HardwareSPI {
public:
/**
@ -37,53 +40,170 @@ public:
*/
SoftwareSPI(pin_size_t sck, pin_size_t miso, pin_size_t mosi, pin_size_t cs = -1);
// Send or receive 8- or 16-bit data. Returns read back value
/**
@brief Send an 8-bit byte of data and return read-back 8-bit value
@param [in] data Data to send
@returns Read back byte from SPI interface
*/
byte transfer(uint8_t data) override;
/**
@brief Send a 16-bit quantity over SPI and return read-back 16-bit value under a single CS assertion
@param [in] data Data to send
@returns Read back 16-bit quantity
*/
uint16_t transfer16(uint16_t data) override;
// Sends buffer in 8 bit chunks. Overwrites buffer with read data
/**
@brief Sends buffer in 8 bit chunks under a single CS. Overwrites buffer with read data
@param [in, out] buf Buffer to read and write back into
@param [in] count Number of bytes to transmit/read
*/
void transfer(void *buf, size_t count) override;
// Sends one buffer and receives into another, much faster! can set rx or txbuf to nullptr
/**
@brief Sends one buffer and receives into another under a single CS. Can set rx or txbuf to nullptr
@param [in] txbuf Buffer to transmit or nullptr to send 0s
@param [out] rxbuf Buffer to read back into or nullptr to ignore returned data
@param [in] count Numbner of bytes to transmit/receive
*/
void transfer(const void *txbuf, void *rxbuf, size_t count) override;
// Call before/after every complete transaction
/**
@brief Begin an SPI transaction, sets SPI speed and masks necessary interrupts
@param [in] SPISettings SPI configuration parameters, including the clock speed
*/
void beginTransaction(SPISettings settings) override;
/**
@brief Ends an SPI transaction, unmasks and masked GPIO interrupts
*/
void endTransaction(void) override;
// Assign pins, call before begin()
/**
@brief Sets the MISO(RX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setMISO(pin_size_t pin);
/**
@brief Sets the MISO(RX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
inline bool setRX(pin_size_t pin) {
return setMISO(pin);
}
/**
@brief Sets the CS pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setCS(pin_size_t pin);
/**
@brief Sets the SCK pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setSCK(pin_size_t pin);
/**
@brief Sets the MOSI(TX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
bool setMOSI(pin_size_t pin);
/**
@brief Sets the MOSI(TX) pin. Call before begin()
@param [in] pin The GPIO number to assign to
@returns True on success
*/
inline bool setTX(pin_size_t pin) {
return setMOSI(pin);
}
// Call once to init/deinit SPI class, select pins, etc.
/**
@brief Call once to init/deinit SPI class, select pins, etc.
*/
virtual void begin() override {
begin(false);
}
/**
@brief Call once to init/deinit SPI class, select pins, etc.
@param [in] hwCS Pass in true to enable HW-controlled CS. Otherwise application needs to assert/deassert CS.
*/
void begin(bool hwCS);
/**
@brief Call to deinit and disable the SPI interface.
*/
void end() override;
// Deprecated - do not use!
/**
@brief Deprecated, do not use
@param [in] order Deprecated
*/
void setBitOrder(BitOrder order) __attribute__((deprecated));
/**
@brief Deprecated, do not use
@param [in] uc_mode Deprecated
*/
void setDataMode(uint8_t uc_mode) __attribute__((deprecated));
/**
@brief Deprecated, do not use
@param [in] uc_div Deprecated
*/
void setClockDivider(uint8_t uc_div) __attribute__((deprecated));
// List of GPIO IRQs to disable during a transaction
/**
@brief Ensure specific GPIO interrupt is disabled during and SPI transaction to protect against re-entrancy. Multiple GPIOs supported by multiple calls.
@param [in] interruptNumber GPIO pin to mask
*/
virtual void usingInterrupt(int interruptNumber) override {
_helper.usingInterrupt(interruptNumber);
}
/**
@brief Remove a GPIO from the masked-during-transaction list.
@param [in] interruptNumber GPIO pin to unmask
*/
virtual void notUsingInterrupt(int interruptNumber) override {
_helper.notUsingInterrupt(interruptNumber);
}
virtual void attachInterrupt() override { /* noop */ }
virtual void detachInterrupt() override { /* noop */ }
/**
@brief Deprecated, do not use
*/
virtual void attachInterrupt() override __attribute__((deprecated)) { /* noop */ }
/**
@brief Deprecated, do not use
*/
virtual void detachInterrupt() override __attribute__((deprecated)) { /* noop */ }
private:
void _adjustPIO(int bits);