Skip to content

Commit

Permalink
Add RP2350B generic/Pimoroni PGA2350 support (#2433)
Browse files Browse the repository at this point in the history
* Add support for the extra 16 GPIO pins in the menus and core.
* Clean up Generic RP2350 PSRAM ("none" is valid) and flash (other than 16MB) options.
* Add extra GPIO<->peripheral connections
* Add Pimoroni PGA2350 RP2350B-based board
* Pins 32-47 can be used for PIOPrograms
* Avoid hang when PSRAM fails to initialize
* Move libpico to an RP2350B board for SDK (otherwise the SDK drops all GPIOHI support)
  • Loading branch information
earlephilhower authored Sep 12, 2024
1 parent 20c69bd commit 76811d3
Show file tree
Hide file tree
Showing 47 changed files with 1,032 additions and 254 deletions.
608 changes: 473 additions & 135 deletions boards.txt

Large diffs are not rendered by default.

13 changes: 11 additions & 2 deletions cores/rp2040/Arduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -133,8 +133,8 @@ extern const String emptyString;
// Template which will evaluate at *compile time* to a single 32b number
// with the specified bits set.
template <size_t N>
constexpr uint32_t __bitset(const int (&a)[N], size_t i = 0U) {
return i < N ? (1L << a[i]) | __bitset(a, i + 1) : 0;
constexpr uint64_t __bitset(const int (&a)[N], size_t i = 0U) {
return i < N ? (1LL << a[i]) | __bitset(a, i + 1) : 0;
}
#endif

Expand All @@ -149,3 +149,12 @@ constexpr uint32_t __bitset(const int (&a)[N], size_t i = 0U) {

// PSRAM decorator
#define PSRAM __attribute__((section("\".psram\"")))

// General GPIO/ADC layout info
#ifdef PICO_RP2350B
#define __GPIOCNT 48
#define __FIRSTANALOGGPIO 40
#else
#define __GPIOCNT 30
#define __FIRSTANALOGGPIO 26
#endif
76 changes: 63 additions & 13 deletions cores/rp2040/PIOProgram.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <Arduino.h>
#include "PIOProgram.h"
#include <map>
#include <hardware/claim.h>

#if defined(PICO_RP2350)
#define PIOS pio0, pio1, pio2
Expand All @@ -31,6 +32,8 @@
#endif

static std::map<const pio_program_t *, int> __pioMap[PIOCNT];
static bool __pioAllocated[PIOCNT];
static bool __pioHighGPIO[PIOCNT];
auto_init_mutex(_pioMutex);

PIOProgram::PIOProgram(const pio_program_t *pgm) {
Expand All @@ -47,16 +50,30 @@ PIOProgram::~PIOProgram() {
}

// Possibly load into a PIO and allocate a SM
bool PIOProgram::prepare(PIO *pio, int *sm, int *offset) {
bool PIOProgram::prepare(PIO *pio, int *sm, int *offset, int start, int cnt) {
CoreMutex m(&_pioMutex);
PIO pi[PIOCNT] = { PIOS };

#if 0
uint usm;
uint uoff;
auto ret = pio_claim_free_sm_and_add_program_for_gpio_range(_pgm, pio, &usm, &uoff, start, cnt, true);
*sm = usm;
*offset = uoff;
DEBUGV("clain %d\n", ret);
return ret;
#endif

bool needsHigh = (start + cnt) >= 32;
DEBUGV("PIOProgram %p: Searching for high=%d, pins %d-%d\n", _pgm, needsHigh ? 1 : 0, start, start + cnt - 1);

// If it's already loaded into PIO IRAM, try and allocate in that specific PIO
for (int o = 0; o < PIOCNT; o++) {
auto p = __pioMap[o].find(_pgm);
if (p != __pioMap[o].end()) {
if ((p != __pioMap[o].end()) && (__pioHighGPIO[o] == needsHigh)) {
int idx = pio_claim_unused_sm(pi[o], false);
if (idx >= 0) {
DEBUGV("PIOProgram %p: Reusing IMEM ON PIO %p(high=%d) for pins %d-%d\n", _pgm, pi[o], __pioHighGPIO[o] ? 1 : 0, start, start + cnt - 1);
_pio = pi[o];
_sm = idx;
*pio = pi[o];
Expand All @@ -69,19 +86,52 @@ bool PIOProgram::prepare(PIO *pio, int *sm, int *offset) {

// Not in any PIO IRAM, so try and add
for (int o = 0; o < PIOCNT; o++) {
if (pio_can_add_program(pi[o], _pgm)) {
int idx = pio_claim_unused_sm(pi[o], false);
if (idx >= 0) {
int off = pio_add_program(pi[o], _pgm);
__pioMap[o].insert({_pgm, off});
_pio = pi[o];
_sm = idx;
*pio = pi[o];
*sm = idx;
*offset = off;
return true;
if (__pioAllocated[o] && (__pioHighGPIO[o] == needsHigh)) {
DEBUGV("PIOProgram: Checking PIO %p\n", pi[o]);
if (pio_can_add_program(pi[o], _pgm)) {
int idx = pio_claim_unused_sm(pi[o], false);
if (idx >= 0) {
DEBUGV("PIOProgram %p: Adding IMEM ON PIO %p(high=%d) for pins %d-%d\n", _pgm, pi[o], __pioHighGPIO[o] ? 1 : 0, start, start + cnt - 1);
int off = pio_add_program(pi[o], _pgm);
__pioMap[o].insert({_pgm, off});
_pio = pi[o];
_sm = idx;
*pio = pi[o];
*sm = idx;
*offset = off;
return true;
} else {
DEBUGV("PIOProgram: can't claim unused SM\n");
}
} else {
DEBUGV("PIOProgram: can't add program\n");
}
} else {
DEBUGV("PIOProgram: Skipping PIO %p, wrong allocated/needhi\n", pi[o]);
}
}

// No existing PIOs can meet, is there an unallocated one we can allocate?
PIO p;
uint idx;
uint off;
auto rc = pio_claim_free_sm_and_add_program_for_gpio_range(_pgm, &p, &idx, &off, start, cnt, true);
if (rc) {
int o = 0;
while (p != pi[o]) {
o++;
}
assert(!__pioAllocated[o]);
__pioAllocated[o] = true;
__pioHighGPIO[o] = needsHigh;
DEBUGV("PIOProgram %p: Allocating new PIO %p(high=%d) for pins %d-%d\n", _pgm, pi[o], __pioHighGPIO[o] ? 1 : 0, start, start + cnt - 1);
__pioMap[o].insert({_pgm, off});
_pio = pi[o];
_sm = idx;
*pio = pi[o];
*sm = idx;
*offset = off;
return true;
}

// Nope, no room either for SMs or INSNs
Expand Down
2 changes: 1 addition & 1 deletion cores/rp2040/PIOProgram.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class PIOProgram {
PIOProgram(const pio_program_t *pgm);
~PIOProgram();
// Possibly load into a PIO and allocate a SM
bool prepare(PIO *pio, int *sm, int *offset);
bool prepare(PIO *pio, int *sm, int *offset, int gpio_start = 0, int gpio_cnt = 1);

private:
const pio_program_t *_pgm;
Expand Down
5 changes: 3 additions & 2 deletions cores/rp2040/SerialPIO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ static std::map<int, PIOProgram*> _rxMap;
// Duplicate a program and replace the first insn with a "set x, repl"
static pio_program_t *pio_make_uart_prog(int repl, const pio_program_t *pg) {
pio_program_t *p = new pio_program_t;
memcpy(p, pg, sizeof(*p));
p->length = pg->length;
p->origin = pg->origin;
uint16_t *insn = (uint16_t *)malloc(p->length * 2);
Expand Down Expand Up @@ -193,7 +194,7 @@ void SerialPIO::begin(unsigned long baud, uint16_t config) {
_txBits = _bits + _stop + (_parity != UART_PARITY_NONE ? 1 : 0) + 1/*start bit*/;
_txPgm = _getTxProgram(_txBits);
int off;
if (!_txPgm->prepare(&_txPIO, &_txSM, &off)) {
if (!_txPgm->prepare(&_txPIO, &_txSM, &off, _tx, 1)) {
DEBUGCORE("ERROR: Unable to allocate PIO TX UART, out of PIO resources\n");
// ERROR, no free slots
return;
Expand Down Expand Up @@ -221,7 +222,7 @@ void SerialPIO::begin(unsigned long baud, uint16_t config) {
_rxBits = 2 * (_bits + _stop + (_parity != UART_PARITY_NONE ? 1 : 0) + 1) - 1;
_rxPgm = _getRxProgram(_rxBits);
int off;
if (!_rxPgm->prepare(&_rxPIO, &_rxSM, &off)) {
if (!_rxPgm->prepare(&_rxPIO, &_rxSM, &off, _rx, 1)) {
DEBUGCORE("ERROR: Unable to allocate PIO RX UART, out of PIO resources\n");
return;
}
Expand Down
40 changes: 32 additions & 8 deletions cores/rp2040/SerialUART.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,16 @@ extern void serialEvent1() __attribute__((weak));
extern void serialEvent2() __attribute__((weak));

bool SerialUART::setRX(pin_size_t pin) {
constexpr uint32_t valid[2] = { __bitset({1, 13, 17, 29}) /* UART0 */,
#ifdef RP2350B
constexpr uint64_t valid[2] = { __bitset({1, 13, 17, 29, 33, 45}) /* UART0 */,
__bitset({5, 9, 21, 25, 37, 41}) /* UART1 */
};
#else
constexpr uint64_t valid[2] = { __bitset({1, 13, 17, 29}) /* UART0 */,
__bitset({5, 9, 21, 25}) /* UART1 */
};
if ((!_running) && ((1 << pin) & valid[uart_get_index(_uart)])) {
#endif
if ((!_running) && ((1LL << pin) & valid[uart_get_index(_uart)])) {
_rx = pin;
return true;
}
Expand All @@ -53,10 +59,16 @@ bool SerialUART::setRX(pin_size_t pin) {
}

bool SerialUART::setTX(pin_size_t pin) {
constexpr uint32_t valid[2] = { __bitset({0, 12, 16, 28}) /* UART0 */,
#ifdef RP2350B
constexpr uint64_t valid[2] = { __bitset({0, 12, 16, 28, 32, 44}) /* UART0 */,
__bitset({4, 8, 20, 24, 36, 40}) /* UART1 */
};
#else
constexpr uint64_t valid[2] = { __bitset({0, 12, 16, 28}) /* UART0 */,
__bitset({4, 8, 20, 24}) /* UART1 */
};
if ((!_running) && ((1 << pin) & valid[uart_get_index(_uart)])) {
#endif
if ((!_running) && ((1LL << pin) & valid[uart_get_index(_uart)])) {
_tx = pin;
return true;
}
Expand All @@ -74,10 +86,16 @@ bool SerialUART::setTX(pin_size_t pin) {
}

bool SerialUART::setRTS(pin_size_t pin) {
constexpr uint32_t valid[2] = { __bitset({3, 15, 19}) /* UART0 */,
#ifdef RP2350B
constexpr uint64_t valid[2] = { __bitset({3, 15, 19, 31, 35, 47}) /* UART0 */,
__bitset({7, 11, 23, 27, 39, 43}) /* UART1 */
};
#else
constexpr uint64_t valid[2] = { __bitset({3, 15, 19}) /* UART0 */,
__bitset({7, 11, 23, 27}) /* UART1 */
};
if ((!_running) && ((pin == UART_PIN_NOT_DEFINED) || ((1 << pin) & valid[uart_get_index(_uart)]))) {
#endif
if ((!_running) && ((pin == UART_PIN_NOT_DEFINED) || ((1LL << pin) & valid[uart_get_index(_uart)]))) {
_rts = pin;
return true;
}
Expand All @@ -95,10 +113,16 @@ bool SerialUART::setRTS(pin_size_t pin) {
}

bool SerialUART::setCTS(pin_size_t pin) {
constexpr uint32_t valid[2] = { __bitset({2, 14, 18}) /* UART0 */,
#ifdef RP2350B
constexpr uint64_t valid[2] = { __bitset({2, 14, 18, 30, 34, 46}) /* UART0 */,
__bitset({6, 10, 22, 26, 38, 42}) /* UART1 */
};
#else
constexpr uint64_t valid[2] = { __bitset({2, 14, 18}) /* UART0 */,
__bitset({6, 10, 22, 26}) /* UART1 */
};
if ((!_running) && ((pin == UART_PIN_NOT_DEFINED) || ((1 << pin) & valid[uart_get_index(_uart)]))) {
#endif
if ((!_running) && ((pin == UART_PIN_NOT_DEFINED) || ((1LL << pin) & valid[uart_get_index(_uart)]))) {
_cts = pin;
return true;
}
Expand Down
6 changes: 3 additions & 3 deletions cores/rp2040/Tone.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ int64_t _stopTonePIO(alarm_id_t id, void *user_data) {
}

void tone(uint8_t pin, unsigned int frequency, unsigned long duration) {
if (pin > 29) {
if (pin >= __GPIOCNT) {
DEBUGCORE("ERROR: Illegal pin in tone (%d)\n", pin);
return;
}
Expand All @@ -81,7 +81,7 @@ void tone(uint8_t pin, unsigned int frequency, unsigned long duration) {
newTone = new Tone();
newTone->pin = pin;
pinMode(pin, OUTPUT);
if (!_tone2Pgm.prepare(&newTone->pio, &newTone->sm, &newTone->off)) {
if (!_tone2Pgm.prepare(&newTone->pio, &newTone->sm, &newTone->off, pin, 1)) {
DEBUGCORE("ERROR: tone unable to start, out of PIO resources\n");
// ERROR, no free slots
delete newTone;
Expand Down Expand Up @@ -118,7 +118,7 @@ void tone(uint8_t pin, unsigned int frequency, unsigned long duration) {
void noTone(uint8_t pin) {
CoreMutex m(&_toneMutex);

if ((pin > 29) || !m) {
if ((pin > __GPIOCNT) || !m) {
DEBUGCORE("ERROR: Illegal pin in tone (%d)\n", pin);
return;
}
Expand Down
4 changes: 2 additions & 2 deletions cores/rp2040/pio_uart.pio
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ wait_bit:
static inline void pio_tx_program_init(PIO pio, uint sm, uint offset, uint pin_tx) {
// Tell PIO to initially drive output-high on the selected pin, then map PIO
// onto that pin with the IO muxes.
pio_sm_set_pins_with_mask(pio, sm, 1u << pin_tx, 1u << pin_tx);
pio_sm_set_pindirs_with_mask(pio, sm, 1u << pin_tx, 1u << pin_tx);
pio_sm_set_set_pins(pio, sm, pin_tx, 1);
pio_sm_set_consecutive_pindirs(pio, sm, pin_tx, 1, true);
pio_gpio_init(pio, pin_tx);

pio_sm_config c = pio_tx_program_get_default_config(offset);
Expand Down
4 changes: 2 additions & 2 deletions cores/rp2040/pio_uart.pio.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ static inline pio_sm_config pio_tx_program_get_default_config(uint offset) {
static inline void pio_tx_program_init(PIO pio, uint sm, uint offset, uint pin_tx) {
// Tell PIO to initially drive output-high on the selected pin, then map PIO
// onto that pin with the IO muxes.
pio_sm_set_pins_with_mask(pio, sm, 1u << pin_tx, 1u << pin_tx);
pio_sm_set_pindirs_with_mask(pio, sm, 1u << pin_tx, 1u << pin_tx);
pio_sm_set_set_pins(pio, sm, pin_tx, 1);
pio_sm_set_consecutive_pindirs(pio, sm, pin_tx, 1, true);
pio_gpio_init(pio, pin_tx);
pio_sm_config c = pio_tx_program_get_default_config(offset);
// OUT shifts to right, no autopull
Expand Down
3 changes: 3 additions & 0 deletions cores/rp2040/psram.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,6 +332,9 @@ static bool __psram_heap_init() {
return true;
}

if (!__psram_heap_size) {
return false;
}
_mem_heap = NULL;
_mem_psram_pool = NULL;
_mem_heap = tlsf_create_with_pool((void *)&__psram_heap_start__, __psram_heap_size, 16 * 1024 * 1024);
Expand Down
22 changes: 11 additions & 11 deletions cores/rp2040/wiring_analog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ void __clearADCPin(pin_size_t p);

static uint32_t analogScale = 255;
static uint32_t analogFreq = 1000;
static uint32_t pwmInitted = 0;
static uint64_t pwmInitted = 0;
static bool scaleInitted = false;
static bool adcInitted = false;
static uint16_t analogWritePseudoScale = 1;
Expand Down Expand Up @@ -79,7 +79,7 @@ extern "C" void analogWriteResolution(int res) {
extern "C" void analogWrite(pin_size_t pin, int val) {
CoreMutex m(&_dacMutex);

if ((pin > 29) || !m) {
if ((pin >= __GPIOCNT) || !m) {
DEBUGCORE("ERROR: Illegal analogWrite pin (%d)\n", pin);
return;
}
Expand All @@ -101,12 +101,12 @@ extern "C" void analogWrite(pin_size_t pin, int val) {
}
scaleInitted = true;
}
if (!(pwmInitted & (1 << pwm_gpio_to_slice_num(pin)))) {
if (!(pwmInitted & (1LL << pwm_gpio_to_slice_num(pin)))) {
pwm_config c = pwm_get_default_config();
pwm_config_set_clkdiv(&c, clock_get_hz(clk_sys) / ((float)analogScale * analogFreq));
pwm_config_set_wrap(&c, analogScale - 1);
pwm_init(pwm_gpio_to_slice_num(pin), &c, true);
pwmInitted |= 1 << pwm_gpio_to_slice_num(pin);
pwmInitted |= 1LL << pwm_gpio_to_slice_num(pin);
}

val <<= analogWritePseudoScale;
Expand All @@ -125,17 +125,17 @@ extern "C" void analogWrite(pin_size_t pin, int val) {
auto_init_mutex(_adcMutex);
static uint8_t _readBits = 10;
static uint8_t _lastADCMux = 0;
static uint32_t _adcGPIOInit = 0;
static uint64_t _adcGPIOInit = 0;

void __clearADCPin(pin_size_t p) {
_adcGPIOInit &= ~(1 << p);
_adcGPIOInit &= ~(1LL << p);
}

extern "C" int analogRead(pin_size_t pin) {
CoreMutex m(&_adcMutex);

pin_size_t maxPin = max(A0, A3);
pin_size_t minPin = min(A0, A3);
pin_size_t maxPin = __GPIOCNT;
pin_size_t minPin = __FIRSTANALOGGPIO;

if ((pin < minPin) || (pin > maxPin) || !m) {
DEBUGCORE("ERROR: Illegal analogRead pin (%d)\n", pin);
Expand All @@ -145,9 +145,9 @@ extern "C" int analogRead(pin_size_t pin) {
adc_init();
adcInitted = true;
}
if (!(_adcGPIOInit & (1 << pin))) {
if (!(_adcGPIOInit & (1LL << pin))) {
adc_gpio_init(pin);
_adcGPIOInit |= 1 << pin;
_adcGPIOInit |= 1LL << pin;
}
if (_lastADCMux != pin) {
adc_select_input(pin - minPin);
Expand All @@ -169,7 +169,7 @@ extern "C" float analogReadTemp(float vref) {
_lastADCMux = 0;
adc_set_temp_sensor_enabled(true);
delay(1); // Allow things to settle. Without this, readings can be erratic
adc_select_input(4); // Temperature sensor
adc_select_input(__GPIOCNT - __FIRSTANALOGGPIO); // Temperature sensor
int v = adc_read();
adc_set_temp_sensor_enabled(false);
float t = 27.0f - ((v * vref / 4096.0f) - 0.706f) / 0.001721f; // From the datasheet
Expand Down
Loading

0 comments on commit 76811d3

Please sign in to comment.