1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00

Merge branch 'PicoRP2350updates' of https://github.com/mjs1441/betaflight into RP2350

# Conflicts:
#	src/config
#	src/main/msp/msp.c
This commit is contained in:
blckmn 2025-06-07 09:49:00 +10:00
commit 6c394b1fce
20 changed files with 1096 additions and 1038 deletions

View file

@ -255,7 +255,6 @@ static void mspEscPassthroughFn(serialPort_t *serialPort)
}
#endif
#ifdef USE_SERIAL_PASSTHROUGH
static serialPort_t *mspFindPassthroughSerialPort(void)
{
serialPortUsage_t *portUsage = NULL;
@ -289,6 +288,9 @@ static void mspSerialPassthroughFn(serialPort_t *serialPort)
static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn)
{
#ifndef USE_SERIAL_PASSTHROUGH
UNUSED(mspPostProcessFn);
#endif
const unsigned int dataSize = sbufBytesRemaining(src);
if (dataSize == 0) {
// Legacy format
@ -311,8 +313,6 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF
sbufWriteU8(dst, 0);
}
break;
#else
UNUSED(mspPostProcessFn);
#endif
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
case MSP_PASSTHROUGH_ESC_4WAY:

View file

@ -60,33 +60,33 @@ const spiHardware_t spiHardware[] = {
.device = SPIDEV_0,
.reg = SPI0,
.sckPins = {
{ DEFIO_TAG_E(P2) },
{ DEFIO_TAG_E(P6) },
{ DEFIO_TAG_E(P18) },
{ DEFIO_TAG_E(P22) },
{ DEFIO_TAG_E(PA2) },
{ DEFIO_TAG_E(PA6) },
{ DEFIO_TAG_E(PA18) },
{ DEFIO_TAG_E(PA22) },
#ifdef RP2350B
{ DEFIO_TAG_E(P34) },
{ DEFIO_TAG_E(P38) },
{ DEFIO_TAG_E(PA34) },
{ DEFIO_TAG_E(PA38) },
#endif
},
.misoPins = {
{ DEFIO_TAG_E(P0) },
{ DEFIO_TAG_E(P4) },
{ DEFIO_TAG_E(P16) },
{ DEFIO_TAG_E(P20) },
{ DEFIO_TAG_E(PA0) },
{ DEFIO_TAG_E(PA4) },
{ DEFIO_TAG_E(PA16) },
{ DEFIO_TAG_E(PA20) },
#ifdef RP2350B
{ DEFIO_TAG_E(P32) },
{ DEFIO_TAG_E(P36) },
{ DEFIO_TAG_E(PA32) },
{ DEFIO_TAG_E(PA36) },
#endif
},
.mosiPins = {
{ DEFIO_TAG_E(P3) },
{ DEFIO_TAG_E(P7) },
{ DEFIO_TAG_E(P19) },
{ DEFIO_TAG_E(P23) },
{ DEFIO_TAG_E(PA3) },
{ DEFIO_TAG_E(PA7) },
{ DEFIO_TAG_E(PA19) },
{ DEFIO_TAG_E(PA23) },
#ifdef RP2350B
{ DEFIO_TAG_E(P35) },
{ DEFIO_TAG_E(P39) },
{ DEFIO_TAG_E(PA35) },
{ DEFIO_TAG_E(PA39) },
#endif
},
},
@ -94,33 +94,33 @@ const spiHardware_t spiHardware[] = {
.device = SPIDEV_1,
.reg = SPI1,
.sckPins = {
{ DEFIO_TAG_E(P10) },
{ DEFIO_TAG_E(P14) },
{ DEFIO_TAG_E(P26) },
{ DEFIO_TAG_E(PA10) },
{ DEFIO_TAG_E(PA14) },
{ DEFIO_TAG_E(PA26) },
#ifdef RP2350B
{ DEFIO_TAG_E(P30) },
{ DEFIO_TAG_E(P42) },
{ DEFIO_TAG_E(P46) },
{ DEFIO_TAG_E(PA30) },
{ DEFIO_TAG_E(PA42) },
{ DEFIO_TAG_E(PA46) },
#endif
},
.misoPins = {
{ DEFIO_TAG_E(P8) },
{ DEFIO_TAG_E(P12) },
{ DEFIO_TAG_E(P24) },
{ DEFIO_TAG_E(P28) },
{ DEFIO_TAG_E(PA8) },
{ DEFIO_TAG_E(PA12) },
{ DEFIO_TAG_E(PA24) },
{ DEFIO_TAG_E(PA28) },
#ifdef RP2350B
{ DEFIO_TAG_E(P40) },
{ DEFIO_TAG_E(P44) },
{ DEFIO_TAG_E(PA40) },
{ DEFIO_TAG_E(PA44) },
#endif
},
.mosiPins = {
{ DEFIO_TAG_E(P11) },
{ DEFIO_TAG_E(P15) },
{ DEFIO_TAG_E(P27) },
{ DEFIO_TAG_E(PA11) },
{ DEFIO_TAG_E(PA15) },
{ DEFIO_TAG_E(PA27) },
#ifdef RP2350B
{ DEFIO_TAG_E(P31) },
{ DEFIO_TAG_E(P43) },
{ DEFIO_TAG_E(P47) },
{ DEFIO_TAG_E(PA31) },
{ DEFIO_TAG_E(PA43) },
{ DEFIO_TAG_E(PA47) },
#endif
},
},
@ -230,6 +230,11 @@ void spiInitDevice(SPIDevice device)
return;
}
// Set owners
IOInit(IOGetByTag(spi->sck), OWNER_SPI_SCK, RESOURCE_INDEX(device));
IOInit(IOGetByTag(spi->miso), OWNER_SPI_SDI, RESOURCE_INDEX(device));
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_SDO, RESOURCE_INDEX(device));
spi_init(SPI_INST(spi->dev), SPI_SPEED_20MHZ);
gpio_set_function(IO_PINBYTAG(spi->miso), GPIO_FUNC_SPI);
@ -260,6 +265,10 @@ bool spiInternalReadWriteBufPolled(SPI_TypeDef *instance, const uint8_t *txData,
// Initialise DMA before first segment transfer
void spiInternalInitStream(const extDevice_t *dev, bool preInit)
{
#ifndef USE_DMA
UNUSED(dev);
UNUSED(preInit);
#else
UNUSED(preInit);
int dma_tx = dma_claim_unused_channel(true);
@ -282,17 +291,22 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
channel_config_set_dreq(&config, spi_get_dreq(SPI_INST(spi->dev), false));
dma_channel_configure(dma_rx, &config, dev->rxBuf, &spi_get_hw(SPI_INST(spi->dev))->dr, 0, false);
#endif
}
// Start DMA transfer for the current segment
void spiInternalStartDMA(const extDevice_t *dev)
{
#ifndef USE_DMA
UNUSED(dev);
#else
// TODO check correct, was len + 1 now len
dma_channel_set_trans_count(dev->bus->dmaTx->channel, dev->bus->curSegment->len, false);
dma_channel_set_trans_count(dev->bus->dmaRx->channel, dev->bus->curSegment->len, false);
dma_channel_start(dev->bus->dmaTx->channel);
dma_channel_start(dev->bus->dmaRx->channel);
#endif
}
// DMA transfer setup and start

View file

@ -0,0 +1,87 @@
;
; Copyright (c) TODO
;
; DSHOT protocol rate (150, 300, 600) is dynamic
; DSHOT bidir / not bidir is compiled in
; For rate, could have separate programs ready to load in (maybe easiest)
; or could have effectively dynamic based on contents of x register if spare, which can be
; set with pio_sm_exec_wait_blocking
; For >4 motors, could configure pin with disable, config set, enable, if blocking
;
; presumably BF writes dshot async, at max of ~10k/sec or so (typical aiming for 8k loop for gyro)
; dshot frame takes approx. 0.1ms dshot150 or dshot300_bidir
; so hopefully never going to be overflowing the tx fifo (but could happen with 150bidir and be close with 150, 300bidir)
; programs dshot_150, dshot_300, dshot_600, dshot_bidir_150, dshot_bidir_300, dshot_bidir_600
;
; All programs, bit width = 40 cycles, clock set accordingly
; Min delay between frames of 2us, number of cycles varies according to program
;
; DSHOT 600
; 1 bit ~ 1.667us, 2us ~ 48 cycles. Allow say 56 cycles between frames
;
; * could get rid of nop by adding delays to 2x jmp !osre, bitloop
; * maybe get rid of discard by writing 16-bit word (dupllicated to top 16 bits), and osre empty after 16 bits
.program dshot_600
start:
set pins, 0 [31] ; Set pin low [assumed pin already set for output]
nop [20] ; min delay 2us at DSHOT600 is 48 cycles, allow 56 before next set
pull block ; Block until someone puts something into the TX FIFO
out y, 16 ; Discard top 16 bits
bitloop:
out y, 1 ; Shift next bit into y
jmp !y, outzero ;
set pins, 1 [29] ; To output a '1' bit, set high for 30 then low for 10 (based on bitlength = 40 cycles)
set pins, 0 [6] ; Delay to next "set" adds up to 10
jmp !osre, bitloop ; If not done output (finished shifting bits) the loop
jmp start
outzero:
set pins, 1 [14] ; To output a '1', set high for 15 then low for 25
set pins, 0 [20] ; Delay to next "set" adds up to 25
jmp !osre, bitloop [1] ; If not done output (finished shifting bits) the loop else wrap to start
/*
#if 0 //def TEST_DSHOT_ETC
static const uint16_t dshot_bidir_PIO_instructions[] = {
// .wrap_target
0xe081, // 0: set pindirs, 1
0xea00, // 1: set pins, 0 [10]
0xe501, // 2: set pins, 1 [5]
0xea00, // 3: set pins, 0 [10]
0xe501, // 4: set pins, 1 [5]
0x0001, // 5: jmp 1
// .wrap
};
/*
#if !PICO_NO_HARDWARE
static const struct pio_program blink_program = {
.instructions = blink_program_instructions,
.length = 6,
.origin = -1,
.pio_version = blink_pio_version,
#if PICO_PIO_VERSION > 0
.used_gpio_ranges = 0x0
#endif
};
#define blink_wrap_target 0
#define blink_wrap 5
#define blink_pio_version 0
static inline pio_sm_config blink_program_get_default_config(uint offset) {
pio_sm_config c = pio_get_default_sm_config();
sm_config_set_wrap(&c, offset + blink_wrap_target, offset + blink_wrap);
return c;
}
*/

View file

@ -0,0 +1,54 @@
// -------------------------------------------------- //
// This file is autogenerated by pioasm; do not edit! //
// -------------------------------------------------- //
#pragma once
#if !PICO_NO_HARDWARE
#include "hardware/pio.h"
#endif
// --------- //
// dshot_600 //
// --------- //
#define dshot_600_wrap_target 0
#define dshot_600_wrap 12
#define dshot_600_pio_version 0
static const uint16_t dshot_600_program_instructions[] = {
// .wrap_target
0xff00, // 0: set pins, 0 [31]
0xb442, // 1: nop [20]
0x80a0, // 2: pull block
0x6050, // 3: out y, 16
0x6041, // 4: out y, 1
0x006a, // 5: jmp !y, 10
0xfd01, // 6: set pins, 1 [29]
0xe600, // 7: set pins, 0 [6]
0x00e4, // 8: jmp !osre, 4
0x0000, // 9: jmp 0
0xee01, // 10: set pins, 1 [14]
0xf400, // 11: set pins, 0 [20]
0x01e4, // 12: jmp !osre, 4 [1]
// .wrap
};
#if !PICO_NO_HARDWARE
static const struct pio_program dshot_600_program = {
.instructions = dshot_600_program_instructions,
.length = 13,
.origin = -1,
.pio_version = dshot_600_pio_version,
#if PICO_PIO_VERSION > 0
.used_gpio_ranges = 0x0
#endif
};
static inline pio_sm_config dshot_600_program_get_default_config(uint offset) {
pio_sm_config c = pio_get_default_sm_config();
sm_config_set_wrap(&c, offset + dshot_600_wrap_target, offset + dshot_600_wrap);
return c;
}
#endif

View file

@ -45,14 +45,19 @@
#include "hardware/pio.h"
#include "hardware/clocks.h"
////////FAST_DATA_ZERO_INIT timeUs_t dshotFrameUs;
//static FAST_DATA_ZERO_INIT timeUs_t lastSendUs;
#ifdef USE_DSHOT_TELEMETRY
// Maximum time to wait for telemetry reception to complete
#define DSHOT_TELEMETRY_TIMEOUT 2000
FAST_DATA_ZERO_INIT timeUs_t dshotFrameUs;
//static FAST_DATA_ZERO_INIT timeUs_t lastSendUs;
// TODO use with TELEMETRY for cli report (or not)
FAST_DATA_ZERO_INIT dshotTelemetryCycleCounters_t dshotDMAHandlerCycleCounters;
#endif
typedef struct motorOutput_s {
int offset;
int offset; // NB current code => offset same for all motors
dshotProtocolControl_t protocolControl;
int pinIndex; // pinIndex of this motor output within a group that bbPort points to
IO_t io; // IO_t for this output
@ -74,45 +79,6 @@ static motorProtocolTypes_e motorProtocol;
static motorOutput_t dshotMotors[MAX_SUPPORTED_MOTORS];
bool useDshotTelemetry = false;
#define DSHOT_BIT_PERIOD 40
static const uint16_t dshot_bidir_PIO_instructions[] = {
// .wrap_target
0xff81, // 0: set pindirs, 1 [31]
0xff01, // 1: set pins, 1 [31]
0x80a0, // 2: pull block
0x6050, // 3: out y, 16
0x00e6, // 4: jmp !osre, 6
0x000e, // 5: jmp 14
0x6041, // 6: out y, 1
0x006b, // 7: jmp !y, 11
0xfd00, // 8: set pins, 0 [29]
0xe501, // 9: set pins, 1 [5]
0x0004, // 10: jmp 4
0xee00, // 11: set pins, 0 [14]
0xf401, // 12: set pins, 1 [20]
0x0004, // 13: jmp 4
0xe055, // 14: set y, 21
0x1f8f, // 15: jmp y--, 15 [31]
0xe080, // 16: set pindirs, 0
0xe05f, // 17: set y, 31
0xa142, // 18: nop [1]
0x0076, // 19: jmp !y, 22
0x0095, // 20: jmp y--, 21
0x00d2, // 21: jmp pin, 18
0xe05e, // 22: set y, 30
0x4901, // 23: in pins, 1 [9]
0x0097, // 24: jmp y--, 23
0x4801, // 25: in pins, 1 [8]
0x8020, // 26: push block
0xe05f, // 27: set y, 31
0x4a01, // 28: in pins, 1 [10]
0x009c, // 29: jmp y--, 28
0x8020, // 30: push block
0x0000, // 31: jmp 0
// .wrap
};
static float getPeriodTiming(void)
{
switch(motorProtocol) {
@ -126,44 +92,237 @@ static float getPeriodTiming(void)
}
}
#define DSHOT_BIT_PERIOD 40
#ifdef USE_DSHOT_TELEMETRY
// Program for bidirectional ("inverted") DSHOT,
// 1 is low, 0 is high voltage
// Outgoing frame starts with transition from 0 to 1
// then 16x bits of 1 == 1 for ~2/3 period, 0 for ~1/3
// or 0 == 1 for ~1/3 period, 0 for ~2/3
// Bit period is DSHOT_BIT_PERIOD (currently 40 cycles)
// Expect the return frame at 30 us after end of outgoing frame
// TODO 30us independent of DSHOT 150, 300, 600,
// so need different number of cycles delay for DSHOT 600 vs 300 vs 150
// Return frame is encoded as 21 bits (simple lo = 0, hi = 1), at 5/4 x outgoing bitrate
// (so return bit period should currently be 40 * 4 / 5 = 32 cycles)
// 1st bit of return frame is always 0, "idle" is 1, so after ~25 us could start waiting for transition
// to 0 - when we finish the out frame, we set pin to input (pindirs 0). Will that respect a previous
// pullup setting?
// see https://forums.raspberrypi.com/viewtopic.php?t=311659
/*
comment on syncing (?) for return frame
https://github.com/betaflight/betaflight/pull/8554
ledvinap commented on Jul 16, 2019
A side note: I didn't analyze it too far, but is seems that 1.5x oversampling (1.5 synchronous samples per bit period) should be enough to handle NRZ protocol including clock drift...
joelucid commented on Jul 17, 2019
Let me specify the new rpm telemetry protocol here for you @sskaug, and others:
Dshot bidir uses inverted signal levels (idle is 1). FC to ESC uses dshot frames but the lowest 4 bits hold the complement of the other nibbles xor'd together (normal dshot does not complement the xor sum). The ESC detects based on the inversion that telemetry packets have to be sent.
30us after receiving the dshot frame the esc responds with a telemetry frame. Logically the telemetry frame is a 16 bit value and the lowest 4 bits hold the complemented xor'd nibbles again.
The upper 12 bit contain the eperiod (1/erps) in the following bitwise encoding:
e e e m m m m m m m m m
The 9 bit value M needs to shifted left E times to get the period in micro seconds. This gives a range of 1 us to 65408 us. Which translates to a min e-frequency of 15.29 hz or for 14 pole motors 3.82 hz.
This 16 bit value is then GCR encoded to a 20 bit value by applying the following map nibble-wise:
0 -> 19
1 -> 1b
2 -> 12
3 -> 13
4 -> 1d
5 -> 15
6 -> 16
7 -> 17
8 -> 1a
9 -> 09
a -> 0a
b -> 0b
c -> 1e
d -> 0d
e -> 0e
f -> 0f
This creates a 20 bit value which has no more than two consecutive zeros. This value is mapped to a new 21 bit value by starting with a bit value of 0 and changing the bit value in the next bit if the current bit in the incoming value is a 1, but repeating the previous bit value otherwise. Example:
1 0 1 1 1 0 0 1 1 0 would become 0 1 1 0 1 0 0 0 1 0 0.
This 21 bit value is then sent uninverted at a bitrate of 5/4 * the dshot bitrate. So Dshot 3 uses 375 kbit, dshot 600 uses 750 kbit.
The esc needs to be ready after 40us + one dshot frame length to receive the next dshot packet.
See https://en.wikipedia.org/wiki/Run-length_limited#GCR:_(0,2)_RLL for more details on the GCR encoding.
*/
static const uint16_t dshot_bidir_PIO_instructions[] = {
// .wrap_target
0xff81, // 0: set pindirs, 1 [31] // min delay... (TODO check, and is this correct for dshot != 600?
0xff01, // 1: set pins, 1 [31]
0x80a0, // 2: pull block // Block until someone puts something into the TX FIFO
0x6050, // 3: out y, 16 // discard top 16 bits (can lose this if 16-bit write? but then would have to count 16)
0x00e6, // 4: jmp !osre, 6 // If not done output then -> 6
0x000e, // 5: jmp 14
0x6041, // 6: out y, 1 // next bit -> into y
0x006b, // 7: jmp !y, 11 // 0 bit to output -> 11
0xfd00, // 8: set pins, 0 [29] // 1 bit to output. Inverted Dshot => 0 for 30, 1 for 10
0xe501, // 9: set pins, 1 [5]
0x0004, // 10: jmp 4
0xee00, // 11: set pins, 0 [14] // 0 bit to output. Inverted Dshot => 0 for 15, 1 for 25
0xf401, // 12: set pins, 1 [20]
0x0004, // 13: jmp 4
0xe055, // 14: set y, 21 // after end of output frame, wait ~30us for start of input which should be transition to 0
0x1f8f, // 15: jmp y--, 15 [31] // wait 32*21 = 672 cycles = 16.8 bit periods ~ 28us at DSHOT600 rate
0xe080, // 16: set pindirs, 0
0xe05f, // 17: set y, 31
0xa142, // 18: nop [1]
0x0076, // 19: jmp !y, 22
0x0095, // 20: jmp y--, 21 // TODO dead code?
0x00d2, // 21: jmp pin, 18 // TODO dead code?
0xe05e, // 22: set y, 30
0x4901, // 23: in pins, 1 [9]
0x0097, // 24: jmp y--, 23 // retrive 31 bits? every 11 cycles (in bits are at 40*4/5 = 32 cycles for dshot600)
0x4801, // 25: in pins, 1 [8] // retrieve 32nd bit TODO we want 21 (or 20 given leading 0) - are we ~3x sampling?
//////////// 0x8020, // 26: push block
0x8000, // 26: push [not block]
0xe05f, // 27: set y, 31
0x4a01, // 28: in pins, 1 [10] // retrieve another 32 bits at 11 cycles
0x009c, // 29: jmp y--, 28
//////////// 0x8020, // 26: push block
0x8000, // 26: push [not block]
// 0x8020, // 30: push block <---- problem if not expecting telemetry...?
0x0000, // 31: jmp 0 // can remove this one with wrap
// .wrap
};
static const struct pio_program dshot_bidir_program = {
.instructions = dshot_bidir_PIO_instructions,
.length = ARRAYLEN(dshot_bidir_PIO_instructions),
.origin = -1,
};
static void dshot_bidir_program_init(PIO pio, uint sm, int offset, uint pin)
static void dshot_program_bidir_init(PIO pio, uint sm, int offset, uint pin)
{
pio_sm_config config = pio_get_default_sm_config();
sm_config_set_wrap(&config, offset + ARRAYLEN(dshot_bidir_PIO_instructions), offset);
// Wrap to = offset + 0, Wrap after instruction = offset + length - 1
sm_config_set_wrap(&config, offset, offset + ARRAYLEN(dshot_bidir_PIO_instructions) - 1);
sm_config_set_set_pins(&config, pin, 1);
sm_config_set_in_pins(&config, pin);
sm_config_set_jmp_pin (&config, pin);
pio_gpio_init(pio, pin);
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true);
gpio_set_pulls(pin, true, false);
sm_config_set_out_shift(&config, false, false, ARRAYLEN(dshot_bidir_PIO_instructions));
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true); // set pin to output
gpio_set_pulls(pin, true, false); // Pull up - idle 1 when awaiting bidir telemetry input (PIO pindirs 0).
// TODO ** autopull == false?
// TODO ** check shiftright = false for dshot program
// recall we aren't outputting the pulled byte, we are using it for timing of transition of output level
// from 0 back to 1
// remember also that DSHOT is effectively hi-endian w.r.t. time (so the timeline looks lo-endian
// in the usual way of picturing memory) -> so shift left
// TODO pull again at 16 bits, then don't need to discard 16 bits in PIO program
sm_config_set_out_shift(&config, false, false, 32); /////ARRAYLEN(dshot_bidir_PIO_instructions));
// TODO ** autopush == false?
sm_config_set_in_shift(&config, false, false, ARRAYLEN(dshot_bidir_PIO_instructions));
float clocks_per_us = clock_get_hz(clk_sys) / 1000000;
#ifdef TEST_DSHOT_SLOW
sm_config_set_clkdiv(&config, (1.0e4f + getPeriodTiming()) / DSHOT_BIT_PERIOD * clocks_per_us);
#else
sm_config_set_clkdiv(&config, getPeriodTiming() / DSHOT_BIT_PERIOD * clocks_per_us);
#endif
pio_sm_init(pio, sm, offset, &config);
}
#else
static const uint16_t dshot_600_program_instructions[] = {
// .wrap_target
0xff00, // 0: set pins, 0 [31]
0xb442, // 1: nop [20]
0x80a0, // 2: pull block
0x6050, // 3: out y, 16
0x6041, // 4: out y, 1
0x006a, // 5: jmp !y, 10
0xfd01, // 6: set pins, 1 [29]
0xe600, // 7: set pins, 0 [6]
0x00e4, // 8: jmp !osre, 4
0x0000, // 9: jmp 0
0xee01, // 10: set pins, 1 [14]
0xf400, // 11: set pins, 0 [20]
0x01e4, // 12: jmp !osre, 4 [1]
// .wrap
};
static const struct pio_program dshot_600_program = {
.instructions = dshot_600_program_instructions,
.length = ARRAYLEN(dshot_600_program_instructions),
.origin = -1,
};
// TODO DSHOT150, 300
static void dshot_program_init(PIO pio, uint sm, int offset, uint pin)
{
pio_sm_config config = pio_get_default_sm_config();
// Wrap to = offset + 0, Wrap after instruction = offset + length - 1
sm_config_set_wrap(&config, offset, offset + ARRAYLEN(dshot_600_program_instructions) - 1);
sm_config_set_set_pins(&config, pin, 1);
pio_gpio_init(pio, pin);
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true); // set pin to output
gpio_set_pulls(pin, false, true); // Pull down - idle low when awaiting next frame to output.
// TODO pull again at 16 bits, then don't need to discard 16 bits in PIO program
// write 16-bits -> duplicates (TBC)
sm_config_set_out_shift(&config, false, false, 32);
sm_config_set_fifo_join(&config, PIO_FIFO_JOIN_TX);
float clocks_per_us = clock_get_hz(clk_sys) / 1000000;
#ifdef TEST_DSHOT_SLOW
sm_config_set_clkdiv(&config, (1.0e4f + getPeriodTiming()) / DSHOT_BIT_PERIOD * clocks_per_us);
#else
sm_config_set_clkdiv(&config, getPeriodTiming() / DSHOT_BIT_PERIOD * clocks_per_us);
#endif
pio_sm_init(pio, sm, offset, &config);
}
#endif
/*
TODO what actually finally fixed this? was it removing gpio_set_dir (unlikely) or
the whole IOConfigGPIO (which needs rethinking)?
TODO is Dshot writing async? (what about telemetry?)
*/
#ifdef USE_DSHOT_TELEMETRY
static uint32_t decodeTelemetry(const uint32_t first, const uint32_t second)
{
UNUSED(first);
UNUSED(second);
return DSHOT_TELEMETRY_INVALID;
}
#endif
static bool dshotTelemetryWait(void)
{
bool telemetryWait = false;
#ifdef USE_DSHOT_TELEMETRY
// Wait for telemetry reception to complete
bool telemetryPending;
bool telemetryWait = false;
const timeUs_t startTimeUs = micros();
do {
@ -171,7 +330,7 @@ static bool dshotTelemetryWait(void)
for (unsigned motorIndex = 0; motorIndex < dshotMotorCount && !telemetryPending; motorIndex++) {
const motorOutput_t *motor = &dshotMotors[motorIndex];
const int fifo_words = pio_sm_get_rx_fifo_level(motor->pio, motor->pio_sm);
telemetryPending |= fifo_words >= 2;
telemetryPending |= fifo_words >= 2; // TODO Current program outputs two words. Should this be <2 ?
}
telemetryWait |= telemetryPending;
@ -179,13 +338,14 @@ static bool dshotTelemetryWait(void)
if (cmpTimeUs(micros(), startTimeUs) > DSHOT_TELEMETRY_TIMEOUT) {
break;
}
} while (telemetryPending);
} while (telemetryPending); // TODO logic here? supposed to block until all telemetry available?
if (telemetryWait) {
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 2, debug[2] + 1);
}
return telemetryWait;
#endif
return telemetryWait; // TODO what should the return value be? (don't think it's used)
}
static void dshotUpdateInit(void)
@ -256,6 +416,7 @@ static void dshotWriteInt(uint8_t motorIndex, uint16_t value)
if (dshotCommandIsProcessing()) {
value = dshotCommandGetCurrent(motorIndex);
if (value) {
// Request telemetry on other return wire (this isn't DSHOT bidir)
motor->protocolControl.requestTelemetry = true;
}
}
@ -263,7 +424,15 @@ static void dshotWriteInt(uint8_t motorIndex, uint16_t value)
motor->protocolControl.value = value;
uint16_t packet = prepareDshotPacket(&motor->protocolControl);
// TODO what to do if TX buffer is full? (unlikely at standard scheduler loop rates?)
#ifdef TEST_DSHOT_ETC
// for testing, can be convenient to block, not lose any writes
pio_sm_put_blocking(motor->pio, motor->pio_sm, packet);
//// pio_sm_put(motor->pio, motor->pio_sm, packet);
#else
pio_sm_put(motor->pio, motor->pio_sm, packet);
#endif
}
static void dshotWrite(uint8_t motorIndex, float value)
@ -273,6 +442,9 @@ static void dshotWrite(uint8_t motorIndex, float value)
static void dshotUpdateComplete(void)
{
// TODO: anything here?
// aargh, dshotCommandQueueEmpty is a query, but dshotCommandOutputIsEnabled has side-effects...
// If there is a dshot command loaded up, time it correctly with motor update
if (!dshotCommandQueueEmpty()) {
if (!dshotCommandOutputIsEnabled(dshotMotorCount)) {
@ -286,7 +458,13 @@ static bool dshotEnableMotors(void)
for (int i = 0; i < dshotMotorCount; i++) {
const motorOutput_t *motor = &dshotMotors[i];
if (motor->configured) {
IOConfigGPIO(motor->io, 0);
// TODO is this valid on a PIO pin
// no, it only affects the pin when configured as "SIO"
// gpio_set_dir(ioPin, (cfg & 0x01)); // 0 = in, 1 = out
///// not this now it inits the pin... IOConfigGPIO(motor->io, 0);
// if we want to set the direction in a PIO mode, we do
// pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true); // set pin to output
}
}
return true;
@ -294,11 +472,28 @@ static bool dshotEnableMotors(void)
static void dshotDisableMotors(void)
{
// TODO: implement?
return;
}
#ifdef TEST_DSHOT_ETC
void dshotTestWrites(void)
{
// const int mnum = 0;
const int mval = DSHOT_MIN_THROTTLE;
for (int ii = mval; ii< DSHOT_MAX_THROTTLE; ii += 123) {
// dshotWriteInt(mnum, ii);
dshotWriteInt(0, ii);
dshotWriteInt(1, ii);
dshotWriteInt(2, ii);
dshotWriteInt(3, ii);
}
}
#endif
static void dshotShutdown(void)
{
// TODO: implement?
return;
}
@ -324,7 +519,9 @@ static bool dshotIsMotorIdle(unsigned motorIndex)
static void dshotRequestTelemetry(unsigned index)
{
#ifdef USE_DSHOT_TELEMETRY
#ifndef USE_DSHOT_TELEMETRY
UNUSED(index);
#else
if (index < dshotMotorCount) {
dshotMotors[index].protocolControl.requestTelemetry = true;
}
@ -351,55 +548,90 @@ static motorVTable_t dshotVTable = {
bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
{
// Return false if not enough motors initialised for the mixer or a break in the motors or issue with PIO
dbgPinLo(0);
dbgPinLo(1);
device->vTable = NULL; // Only set vTable if initialisation is succesful (TODO: check)
dshotMotorCount = 0; // Only set dshotMotorCount ble if initialisation is succesful (TODO: check)
uint8_t motorCountProvisional = device->count;
if (motorCountProvisional > 4) {
// Currently support 4 motors with one PIO block, four state machines
// TODO (possible future) support more than 4 motors
// (by reconfiguring state machines perhaps? batching if required)
return false;
}
motorProtocol = motorConfig->motorProtocol;
device->vTable = &dshotVTable;
dshotMotorCount = device->count;
#ifdef USE_DSHOT_TELEMETRY
useDshotTelemetry = motorConfig->useDshotTelemetry;
#endif
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
IO_t io = IOGetByTag(motorConfig->ioTags[motorIndex]);
// TODO somehow configure which PIO block to use for dshot? pio0 for now.
const PIO pio = pio0;
const PIO pio = pio0;
#ifdef TEST_DSHOT_ETC
pio_set_gpio_base(pio, 16);
#endif
// Use one program for all motors.
// NB the PIO block is limited to 32 instructions (shared across 4 state machines)
#ifdef USE_DSHOT_TELEMETRY
int offset = pio_add_program(pio, &dshot_bidir_program);
#else
int offset = pio_add_program(pio, &dshot_600_program);
#endif
if (offset < 0) {
/* error loading PIO */
return false;
}
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCountProvisional; motorIndex++) {
IO_t io = IOGetByTag(motorConfig->ioTags[motorIndex]);
if (!IOIsFreeOrPreinit(io)) {
return false;
}
// TODO: might make use of pio_claim_free_sm_and_add_program_for_gpio_range
// -> automatically sets the GPIO base if we might be using pins in 32..47
const int pio_sm = pio_claim_unused_sm(pio, false);
if (!IOIsFreeOrPreinit(io) || pio_sm < 0) {
/* not enough motors initialised for the mixer or a break in the motors or issue with PIO */
device->vTable = NULL;
dshotMotorCount = 0;
if (pio_sm < 0) {
return false;
}
int pinIndex = DEFIO_TAG_PIN(motorConfig->ioTags[motorIndex]);
// TODO: take account of motor reordering,
// cf. versions of pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex, motorProtocolTypes_e pwmProtocolType, uint8_t output)
dshotMotors[motorIndex].pinIndex = pinIndex;
dshotMotors[motorIndex].io = io;
dshotMotors[motorIndex].pio = pio;
dshotMotors[motorIndex].pio_sm = pio_sm;
dshotMotors[motorIndex].offset = offset;
uint8_t iocfg = 0;
IOInit(io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
IOConfigGPIO(io, iocfg);
// uint8_t iocfg = 0;
// IOConfigGPIO(io, iocfg); // TODO: don't need this? assigned and dir in program init
#ifdef USE_DSHOT_TELEMETRY
dshot_program_bidir_init(pio, pio_sm, dshotMotors[motorIndex].offset, pinIndex);
#else
dshot_program_init(pio, pio_sm, dshotMotors[motorIndex].offset, pinIndex);
#endif
int offset = pio_add_program(pio, &dshot_bidir_program);
if (offset == -1) {
/* error loading PIO */
pio_sm_unclaim(pio, pio_sm);
device->vTable = NULL;
dshotMotorCount = 0;
return false;
} else {
dshotMotors[motorIndex].offset = offset;
}
dshot_bidir_program_init(pio, pio_sm, dshotMotors[motorIndex].offset, pinIndex);
// TODO pio_sm_set_enabled for pio_sm of dshotMotors[0..3] maybe
// better in vTable functions dshotEnable/DisableMotors
pio_sm_set_enabled(pio, pio_sm, true);
dshotMotors[motorIndex].configured = true;
}
device->vTable = &dshotVTable;
dshotMotorCount = motorCountProvisional;
return true;
}

View file

@ -77,7 +77,15 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define FAST_IRQ_HANDLER
#define DEFAULT_CPU_OVERCLOCK 0
#ifdef TEST_SLOW_SCHEDULE
// (testing) allow time for more / all tasks
#define TASK_GYROPID_DESIRED_PERIOD 30000 // 1000 // 50000 // 125 // 125us = 8kHz
#else
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
#endif
#define SCHEDULER_DELAY_LIMIT 10
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
@ -96,7 +104,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define SPI_IO_AF_SCK_CFG_HIGH 0
#define SPI_IO_AF_SCK_CFG_LOW 0
#define SPI_IO_AF_SDI_CFG 0
#define SPI_IO_CS_CFG 0
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_OUT, 0, 0) // todo pullup/down etc.
#define SERIAL_UART_FIRST_INDEX 0

View file

@ -32,193 +32,179 @@
#error "Unsupported target MCU type for PICO"
#endif
#undef DEFIO_TAG_MAKE
#define DEFIO_TAG_MAKE(pin) ((ioTag_t)(((1) << DEFIO_PORT_BITSHIFT) | (pin)))
// GPIOID for potential different banks ("ports") of GPIO pins - for RP2350 there's only one
#undef DEFIO_TAG_GPIOID
#define DEFIO_TAG_GPIOID(tag) (((tag) >> DEFIO_PORT_BITSHIFT) - 1)
#undef DEFIO_TAG_PIN
#define DEFIO_TAG_PIN(tag) ((tag) & DEFIO_PIN_BITMASK)
// DEFIO_TAG__P<port><pin> will expand to TAG if defined for target, error is triggered otherwise
// DEFIO_TAG_E__P<port><pin> will expand to TAG if defined, to NONE otherwise (usefull for tables that are CPU-specific)
// DEFIO_REC__P<port><pin> will expand to ioRec* (using DEFIO_REC_INDEX(idx))
#define DEFIO_TAG__P0 DEFIO_TAG_MAKE(0)
#define DEFIO_TAG__P1 DEFIO_TAG_MAKE(1)
#define DEFIO_TAG__P2 DEFIO_TAG_MAKE(2)
#define DEFIO_TAG__P3 DEFIO_TAG_MAKE(3)
#define DEFIO_TAG__P4 DEFIO_TAG_MAKE(4)
#define DEFIO_TAG__P5 DEFIO_TAG_MAKE(5)
#define DEFIO_TAG__P6 DEFIO_TAG_MAKE(6)
#define DEFIO_TAG__P7 DEFIO_TAG_MAKE(7)
#define DEFIO_TAG__P8 DEFIO_TAG_MAKE(8)
#define DEFIO_TAG__P9 DEFIO_TAG_MAKE(9)
#define DEFIO_TAG__P10 DEFIO_TAG_MAKE(10)
#define DEFIO_TAG__P11 DEFIO_TAG_MAKE(11)
#define DEFIO_TAG__P12 DEFIO_TAG_MAKE(12)
#define DEFIO_TAG__P13 DEFIO_TAG_MAKE(13)
#define DEFIO_TAG__P14 DEFIO_TAG_MAKE(14)
#define DEFIO_TAG__P15 DEFIO_TAG_MAKE(15)
#define DEFIO_TAG__P16 DEFIO_TAG_MAKE(16)
#define DEFIO_TAG__P17 DEFIO_TAG_MAKE(17)
#define DEFIO_TAG__P18 DEFIO_TAG_MAKE(18)
#define DEFIO_TAG__P19 DEFIO_TAG_MAKE(19)
#define DEFIO_TAG__P20 DEFIO_TAG_MAKE(20)
#define DEFIO_TAG__P21 DEFIO_TAG_MAKE(21)
#define DEFIO_TAG__P22 DEFIO_TAG_MAKE(22)
#define DEFIO_TAG__P23 DEFIO_TAG_MAKE(23)
#define DEFIO_TAG__P24 DEFIO_TAG_MAKE(24)
#define DEFIO_TAG__P25 DEFIO_TAG_MAKE(25)
#define DEFIO_TAG__P26 DEFIO_TAG_MAKE(26)
#define DEFIO_TAG__P27 DEFIO_TAG_MAKE(27)
#define DEFIO_TAG__P28 DEFIO_TAG_MAKE(28)
#define DEFIO_TAG__P29 DEFIO_TAG_MAKE(29)
#define DEFIO_TAG__PA0 DEFIO_TAG_MAKE(0,0)
#define DEFIO_TAG__PA1 DEFIO_TAG_MAKE(0,1)
#define DEFIO_TAG__PA2 DEFIO_TAG_MAKE(0,2)
#define DEFIO_TAG__PA3 DEFIO_TAG_MAKE(0,3)
#define DEFIO_TAG__PA4 DEFIO_TAG_MAKE(0,4)
#define DEFIO_TAG__PA5 DEFIO_TAG_MAKE(0,5)
#define DEFIO_TAG__PA6 DEFIO_TAG_MAKE(0,6)
#define DEFIO_TAG__PA7 DEFIO_TAG_MAKE(0,7)
#define DEFIO_TAG__PA8 DEFIO_TAG_MAKE(0,8)
#define DEFIO_TAG__PA9 DEFIO_TAG_MAKE(0,9)
#define DEFIO_TAG__PA10 DEFIO_TAG_MAKE(0,10)
#define DEFIO_TAG__PA11 DEFIO_TAG_MAKE(0,11)
#define DEFIO_TAG__PA12 DEFIO_TAG_MAKE(0,12)
#define DEFIO_TAG__PA13 DEFIO_TAG_MAKE(0,13)
#define DEFIO_TAG__PA14 DEFIO_TAG_MAKE(0,14)
#define DEFIO_TAG__PA15 DEFIO_TAG_MAKE(0,15)
#define DEFIO_TAG__PA16 DEFIO_TAG_MAKE(0,16)
#define DEFIO_TAG__PA17 DEFIO_TAG_MAKE(0,17)
#define DEFIO_TAG__PA18 DEFIO_TAG_MAKE(0,18)
#define DEFIO_TAG__PA19 DEFIO_TAG_MAKE(0,19)
#define DEFIO_TAG__PA20 DEFIO_TAG_MAKE(0,20)
#define DEFIO_TAG__PA21 DEFIO_TAG_MAKE(0,21)
#define DEFIO_TAG__PA22 DEFIO_TAG_MAKE(0,22)
#define DEFIO_TAG__PA23 DEFIO_TAG_MAKE(0,23)
#define DEFIO_TAG__PA24 DEFIO_TAG_MAKE(0,24)
#define DEFIO_TAG__PA25 DEFIO_TAG_MAKE(0,25)
#define DEFIO_TAG__PA26 DEFIO_TAG_MAKE(0,26)
#define DEFIO_TAG__PA27 DEFIO_TAG_MAKE(0,27)
#define DEFIO_TAG__PA28 DEFIO_TAG_MAKE(0,28)
#define DEFIO_TAG__PA29 DEFIO_TAG_MAKE(0,29)
#if defined(RP2350B)
#define DEFIO_TAG__P30 DEFIO_TAG_MAKE(30)
#define DEFIO_TAG__P31 DEFIO_TAG_MAKE(31)
#define DEFIO_TAG__P32 DEFIO_TAG_MAKE(32)
#define DEFIO_TAG__P33 DEFIO_TAG_MAKE(33)
#define DEFIO_TAG__P34 DEFIO_TAG_MAKE(34)
#define DEFIO_TAG__P35 DEFIO_TAG_MAKE(35)
#define DEFIO_TAG__P36 DEFIO_TAG_MAKE(36)
#define DEFIO_TAG__P37 DEFIO_TAG_MAKE(37)
#define DEFIO_TAG__P38 DEFIO_TAG_MAKE(38)
#define DEFIO_TAG__P39 DEFIO_TAG_MAKE(39)
#define DEFIO_TAG__P40 DEFIO_TAG_MAKE(40)
#define DEFIO_TAG__P41 DEFIO_TAG_MAKE(41)
#define DEFIO_TAG__P42 DEFIO_TAG_MAKE(42)
#define DEFIO_TAG__P43 DEFIO_TAG_MAKE(43)
#define DEFIO_TAG__P44 DEFIO_TAG_MAKE(44)
#define DEFIO_TAG__P45 DEFIO_TAG_MAKE(45)
#define DEFIO_TAG__P46 DEFIO_TAG_MAKE(46)
#define DEFIO_TAG__P47 DEFIO_TAG_MAKE(47)
#define DEFIO_TAG__PA30 DEFIO_TAG_MAKE(0,30)
#define DEFIO_TAG__PA31 DEFIO_TAG_MAKE(0,31)
#define DEFIO_TAG__PA32 DEFIO_TAG_MAKE(0,32)
#define DEFIO_TAG__PA33 DEFIO_TAG_MAKE(0,33)
#define DEFIO_TAG__PA34 DEFIO_TAG_MAKE(0,34)
#define DEFIO_TAG__PA35 DEFIO_TAG_MAKE(0,35)
#define DEFIO_TAG__PA36 DEFIO_TAG_MAKE(0,36)
#define DEFIO_TAG__PA37 DEFIO_TAG_MAKE(0,37)
#define DEFIO_TAG__PA38 DEFIO_TAG_MAKE(0,38)
#define DEFIO_TAG__PA39 DEFIO_TAG_MAKE(0,39)
#define DEFIO_TAG__PA40 DEFIO_TAG_MAKE(0,40)
#define DEFIO_TAG__PA41 DEFIO_TAG_MAKE(0,41)
#define DEFIO_TAG__PA42 DEFIO_TAG_MAKE(0,42)
#define DEFIO_TAG__PA43 DEFIO_TAG_MAKE(0,43)
#define DEFIO_TAG__PA44 DEFIO_TAG_MAKE(0,44)
#define DEFIO_TAG__PA45 DEFIO_TAG_MAKE(0,45)
#define DEFIO_TAG__PA46 DEFIO_TAG_MAKE(0,46)
#define DEFIO_TAG__PA47 DEFIO_TAG_MAKE(0,47)
#endif
#define DEFIO_TAG_E__P0 DEFIO_TAG__P0
#define DEFIO_TAG_E__P1 DEFIO_TAG__P1
#define DEFIO_TAG_E__P2 DEFIO_TAG__P2
#define DEFIO_TAG_E__P3 DEFIO_TAG__P3
#define DEFIO_TAG_E__P4 DEFIO_TAG__P4
#define DEFIO_TAG_E__P5 DEFIO_TAG__P5
#define DEFIO_TAG_E__P6 DEFIO_TAG__P6
#define DEFIO_TAG_E__P7 DEFIO_TAG__P7
#define DEFIO_TAG_E__P8 DEFIO_TAG__P8
#define DEFIO_TAG_E__P9 DEFIO_TAG__P9
#define DEFIO_TAG_E__P10 DEFIO_TAG__P10
#define DEFIO_TAG_E__P11 DEFIO_TAG__P11
#define DEFIO_TAG_E__P12 DEFIO_TAG__P12
#define DEFIO_TAG_E__P13 DEFIO_TAG__P13
#define DEFIO_TAG_E__P14 DEFIO_TAG__P14
#define DEFIO_TAG_E__P15 DEFIO_TAG__P15
#define DEFIO_TAG_E__P16 DEFIO_TAG__P16
#define DEFIO_TAG_E__P17 DEFIO_TAG__P17
#define DEFIO_TAG_E__P18 DEFIO_TAG__P18
#define DEFIO_TAG_E__P19 DEFIO_TAG__P19
#define DEFIO_TAG_E__P20 DEFIO_TAG__P20
#define DEFIO_TAG_E__P21 DEFIO_TAG__P21
#define DEFIO_TAG_E__P22 DEFIO_TAG__P22
#define DEFIO_TAG_E__P23 DEFIO_TAG__P23
#define DEFIO_TAG_E__P24 DEFIO_TAG__P24
#define DEFIO_TAG_E__P25 DEFIO_TAG__P25
#define DEFIO_TAG_E__P26 DEFIO_TAG__P26
#define DEFIO_TAG_E__P27 DEFIO_TAG__P27
#define DEFIO_TAG_E__P28 DEFIO_TAG__P28
#define DEFIO_TAG_E__P29 DEFIO_TAG__P29
#define DEFIO_TAG_E__PA0 DEFIO_TAG__PA0
#define DEFIO_TAG_E__PA1 DEFIO_TAG__PA1
#define DEFIO_TAG_E__PA2 DEFIO_TAG__PA2
#define DEFIO_TAG_E__PA3 DEFIO_TAG__PA3
#define DEFIO_TAG_E__PA4 DEFIO_TAG__PA4
#define DEFIO_TAG_E__PA5 DEFIO_TAG__PA5
#define DEFIO_TAG_E__PA6 DEFIO_TAG__PA6
#define DEFIO_TAG_E__PA7 DEFIO_TAG__PA7
#define DEFIO_TAG_E__PA8 DEFIO_TAG__PA8
#define DEFIO_TAG_E__PA9 DEFIO_TAG__PA9
#define DEFIO_TAG_E__PA10 DEFIO_TAG__PA10
#define DEFIO_TAG_E__PA11 DEFIO_TAG__PA11
#define DEFIO_TAG_E__PA12 DEFIO_TAG__PA12
#define DEFIO_TAG_E__PA13 DEFIO_TAG__PA13
#define DEFIO_TAG_E__PA14 DEFIO_TAG__PA14
#define DEFIO_TAG_E__PA15 DEFIO_TAG__PA15
#define DEFIO_TAG_E__PA16 DEFIO_TAG__PA16
#define DEFIO_TAG_E__PA17 DEFIO_TAG__PA17
#define DEFIO_TAG_E__PA18 DEFIO_TAG__PA18
#define DEFIO_TAG_E__PA19 DEFIO_TAG__PA19
#define DEFIO_TAG_E__PA20 DEFIO_TAG__PA20
#define DEFIO_TAG_E__PA21 DEFIO_TAG__PA21
#define DEFIO_TAG_E__PA22 DEFIO_TAG__PA22
#define DEFIO_TAG_E__PA23 DEFIO_TAG__PA23
#define DEFIO_TAG_E__PA24 DEFIO_TAG__PA24
#define DEFIO_TAG_E__PA25 DEFIO_TAG__PA25
#define DEFIO_TAG_E__PA26 DEFIO_TAG__PA26
#define DEFIO_TAG_E__PA27 DEFIO_TAG__PA27
#define DEFIO_TAG_E__PA28 DEFIO_TAG__PA28
#define DEFIO_TAG_E__PA29 DEFIO_TAG__PA29
#if defined(RP2350B)
#define DEFIO_TAG_E__P30 DEFIO_TAG__P30
#define DEFIO_TAG_E__P31 DEFIO_TAG__P31
#define DEFIO_TAG_E__P32 DEFIO_TAG__P32
#define DEFIO_TAG_E__P33 DEFIO_TAG__P33
#define DEFIO_TAG_E__P34 DEFIO_TAG__P34
#define DEFIO_TAG_E__P35 DEFIO_TAG__P35
#define DEFIO_TAG_E__P36 DEFIO_TAG__P36
#define DEFIO_TAG_E__P37 DEFIO_TAG__P37
#define DEFIO_TAG_E__P38 DEFIO_TAG__P38
#define DEFIO_TAG_E__P39 DEFIO_TAG__P39
#define DEFIO_TAG_E__P40 DEFIO_TAG__P40
#define DEFIO_TAG_E__P41 DEFIO_TAG__P41
#define DEFIO_TAG_E__P42 DEFIO_TAG__P42
#define DEFIO_TAG_E__P43 DEFIO_TAG__P43
#define DEFIO_TAG_E__P44 DEFIO_TAG__P44
#define DEFIO_TAG_E__P45 DEFIO_TAG__P45
#define DEFIO_TAG_E__P46 DEFIO_TAG__P46
#define DEFIO_TAG_E__P47 DEFIO_TAG__P47
#define DEFIO_TAG_E__PA30 DEFIO_TAG__PA30
#define DEFIO_TAG_E__PA31 DEFIO_TAG__PA31
#define DEFIO_TAG_E__PA32 DEFIO_TAG__PA32
#define DEFIO_TAG_E__PA33 DEFIO_TAG__PA33
#define DEFIO_TAG_E__PA34 DEFIO_TAG__PA34
#define DEFIO_TAG_E__PA35 DEFIO_TAG__PA35
#define DEFIO_TAG_E__PA36 DEFIO_TAG__PA36
#define DEFIO_TAG_E__PA37 DEFIO_TAG__PA37
#define DEFIO_TAG_E__PA38 DEFIO_TAG__PA38
#define DEFIO_TAG_E__PA39 DEFIO_TAG__PA39
#define DEFIO_TAG_E__PA40 DEFIO_TAG__PA40
#define DEFIO_TAG_E__PA41 DEFIO_TAG__PA41
#define DEFIO_TAG_E__PA42 DEFIO_TAG__PA42
#define DEFIO_TAG_E__PA43 DEFIO_TAG__PA43
#define DEFIO_TAG_E__PA44 DEFIO_TAG__PA44
#define DEFIO_TAG_E__PA45 DEFIO_TAG__PA45
#define DEFIO_TAG_E__PA46 DEFIO_TAG__PA46
#define DEFIO_TAG_E__PA47 DEFIO_TAG__PA47
#else
#define DEFIO_TAG_E__P30 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P31 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P32 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P33 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P34 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P35 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P36 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P37 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P38 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P39 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P40 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P41 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P42 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P43 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P44 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P45 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P46 DEFIO_TAG__NONE
#define DEFIO_TAG_E__P47 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA30 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA31 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA32 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA33 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA34 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA35 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA36 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA37 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA38 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA39 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA40 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA41 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA42 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA43 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA44 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA45 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA46 DEFIO_TAG__NONE
#define DEFIO_TAG_E__PA47 DEFIO_TAG__NONE
#endif
#define DEFIO_REC__P0 DEFIO_REC_INDEXED(0)
#define DEFIO_REC__P1 DEFIO_REC_INDEXED(1)
#define DEFIO_REC__P2 DEFIO_REC_INDEXED(2)
#define DEFIO_REC__P3 DEFIO_REC_INDEXED(3)
#define DEFIO_REC__P4 DEFIO_REC_INDEXED(4)
#define DEFIO_REC__P5 DEFIO_REC_INDEXED(5)
#define DEFIO_REC__P6 DEFIO_REC_INDEXED(6)
#define DEFIO_REC__P7 DEFIO_REC_INDEXED(7)
#define DEFIO_REC__P8 DEFIO_REC_INDEXED(8)
#define DEFIO_REC__P9 DEFIO_REC_INDEXED(9)
#define DEFIO_REC__P10 DEFIO_REC_INDEXED(10)
#define DEFIO_REC__P11 DEFIO_REC_INDEXED(11)
#define DEFIO_REC__P12 DEFIO_REC_INDEXED(12)
#define DEFIO_REC__P13 DEFIO_REC_INDEXED(13)
#define DEFIO_REC__P14 DEFIO_REC_INDEXED(14)
#define DEFIO_REC__P15 DEFIO_REC_INDEXED(15)
#define DEFIO_REC__P16 DEFIO_REC_INDEXED(16)
#define DEFIO_REC__P17 DEFIO_REC_INDEXED(17)
#define DEFIO_REC__P18 DEFIO_REC_INDEXED(18)
#define DEFIO_REC__P19 DEFIO_REC_INDEXED(19)
#define DEFIO_REC__P20 DEFIO_REC_INDEXED(20)
#define DEFIO_REC__P21 DEFIO_REC_INDEXED(21)
#define DEFIO_REC__P22 DEFIO_REC_INDEXED(22)
#define DEFIO_REC__P23 DEFIO_REC_INDEXED(23)
#define DEFIO_REC__P24 DEFIO_REC_INDEXED(24)
#define DEFIO_REC__P25 DEFIO_REC_INDEXED(25)
#define DEFIO_REC__P26 DEFIO_REC_INDEXED(26)
#define DEFIO_REC__P27 DEFIO_REC_INDEXED(27)
#define DEFIO_REC__P28 DEFIO_REC_INDEXED(28)
#define DEFIO_REC__P29 DEFIO_REC_INDEXED(29)
#define DEFIO_REC__PA0 DEFIO_REC_INDEXED(0)
#define DEFIO_REC__PA1 DEFIO_REC_INDEXED(1)
#define DEFIO_REC__PA2 DEFIO_REC_INDEXED(2)
#define DEFIO_REC__PA3 DEFIO_REC_INDEXED(3)
#define DEFIO_REC__PA4 DEFIO_REC_INDEXED(4)
#define DEFIO_REC__PA5 DEFIO_REC_INDEXED(5)
#define DEFIO_REC__PA6 DEFIO_REC_INDEXED(6)
#define DEFIO_REC__PA7 DEFIO_REC_INDEXED(7)
#define DEFIO_REC__PA8 DEFIO_REC_INDEXED(8)
#define DEFIO_REC__PA9 DEFIO_REC_INDEXED(9)
#define DEFIO_REC__PA10 DEFIO_REC_INDEXED(10)
#define DEFIO_REC__PA11 DEFIO_REC_INDEXED(11)
#define DEFIO_REC__PA12 DEFIO_REC_INDEXED(12)
#define DEFIO_REC__PA13 DEFIO_REC_INDEXED(13)
#define DEFIO_REC__PA14 DEFIO_REC_INDEXED(14)
#define DEFIO_REC__PA15 DEFIO_REC_INDEXED(15)
#define DEFIO_REC__PA16 DEFIO_REC_INDEXED(16)
#define DEFIO_REC__PA17 DEFIO_REC_INDEXED(17)
#define DEFIO_REC__PA18 DEFIO_REC_INDEXED(18)
#define DEFIO_REC__PA19 DEFIO_REC_INDEXED(19)
#define DEFIO_REC__PA20 DEFIO_REC_INDEXED(20)
#define DEFIO_REC__PA21 DEFIO_REC_INDEXED(21)
#define DEFIO_REC__PA22 DEFIO_REC_INDEXED(22)
#define DEFIO_REC__PA23 DEFIO_REC_INDEXED(23)
#define DEFIO_REC__PA24 DEFIO_REC_INDEXED(24)
#define DEFIO_REC__PA25 DEFIO_REC_INDEXED(25)
#define DEFIO_REC__PA26 DEFIO_REC_INDEXED(26)
#define DEFIO_REC__PA27 DEFIO_REC_INDEXED(27)
#define DEFIO_REC__PA28 DEFIO_REC_INDEXED(28)
#define DEFIO_REC__PA29 DEFIO_REC_INDEXED(29)
#if defined(RP2350B)
#define DEFIO_REC__P30 DEFIO_REC_INDEXED(30)
#define DEFIO_REC__P31 DEFIO_REC_INDEXED(31)
#define DEFIO_REC__P32 DEFIO_REC_INDEXED(32)
#define DEFIO_REC__P33 DEFIO_REC_INDEXED(33)
#define DEFIO_REC__P34 DEFIO_REC_INDEXED(34)
#define DEFIO_REC__P35 DEFIO_REC_INDEXED(35)
#define DEFIO_REC__P36 DEFIO_REC_INDEXED(36)
#define DEFIO_REC__P37 DEFIO_REC_INDEXED(37)
#define DEFIO_REC__P38 DEFIO_REC_INDEXED(38)
#define DEFIO_REC__P39 DEFIO_REC_INDEXED(39)
#define DEFIO_REC__P40 DEFIO_REC_INDEXED(40)
#define DEFIO_REC__P41 DEFIO_REC_INDEXED(41)
#define DEFIO_REC__P42 DEFIO_REC_INDEXED(42)
#define DEFIO_REC__P43 DEFIO_REC_INDEXED(43)
#define DEFIO_REC__P44 DEFIO_REC_INDEXED(44)
#define DEFIO_REC__P45 DEFIO_REC_INDEXED(45)
#define DEFIO_REC__P46 DEFIO_REC_INDEXED(46)
#define DEFIO_REC__P47 DEFIO_REC_INDEXED(47)
#define DEFIO_REC__PA30 DEFIO_REC_INDEXED(30)
#define DEFIO_REC__PA31 DEFIO_REC_INDEXED(31)
#define DEFIO_REC__PA32 DEFIO_REC_INDEXED(32)
#define DEFIO_REC__PA33 DEFIO_REC_INDEXED(33)
#define DEFIO_REC__PA34 DEFIO_REC_INDEXED(34)
#define DEFIO_REC__PA35 DEFIO_REC_INDEXED(35)
#define DEFIO_REC__PA36 DEFIO_REC_INDEXED(36)
#define DEFIO_REC__PA37 DEFIO_REC_INDEXED(37)
#define DEFIO_REC__PA38 DEFIO_REC_INDEXED(38)
#define DEFIO_REC__PA39 DEFIO_REC_INDEXED(39)
#define DEFIO_REC__PA40 DEFIO_REC_INDEXED(40)
#define DEFIO_REC__PA41 DEFIO_REC_INDEXED(41)
#define DEFIO_REC__PA42 DEFIO_REC_INDEXED(42)
#define DEFIO_REC__PA43 DEFIO_REC_INDEXED(43)
#define DEFIO_REC__PA44 DEFIO_REC_INDEXED(44)
#define DEFIO_REC__PA45 DEFIO_REC_INDEXED(45)
#define DEFIO_REC__PA46 DEFIO_REC_INDEXED(46)
#define DEFIO_REC__PA47 DEFIO_REC_INDEXED(47)
#endif
// DEFIO_IO_USED_COUNT is number of io pins supported on target
@ -231,6 +217,7 @@
// DEFIO_PORT_USED_LIST - comma separated list of bitmask for all used ports.
// DEFIO_PORT_OFFSET_LIST - comma separated list of port offsets (count of pins before this port)
// unused ports on end of list are skipped
// NB the following are not required in src/main
#define DEFIO_PORT_USED_COUNT 1
#define DEFIO_PORT_USED_LIST
#define DEFIO_PORT_OFFSET_LIST 0

View file

@ -27,8 +27,12 @@
#include "common/utils.h"
#include "hardware/gpio.h"
// initialize all ioRec_t structures from ROM
// currently only bitmask is used, this may change in future
#if DEFIO_PORT_USED_COUNT > 1
#error PICO code currently based on a single io port
#endif
// Initialize all ioRec_t structures.
// PICO (single port) doesn't use the gpio field.
void IOInitGlobal(void)
{
ioRec_t *ioRec = ioRecs;
@ -37,6 +41,15 @@ void IOInitGlobal(void)
ioRec->pin = pin;
ioRec++;
}
#ifdef PICO_TRACE
#ifdef PICO_DEFAULT_UART_TX_PIN
ioRecs[PICO_DEFAULT_UART_TX_PIN].owner = OWNER_SYSTEM;
#endif
#ifdef PICO_DEFAULT_UART_RX_PIN
ioRecs[PICO_DEFAULT_UART_RX_PIN].owner = OWNER_SYSTEM;
#endif
#endif
}
uint32_t IO_EXTI_Line(IO_t io)
@ -105,7 +118,9 @@ SPI_IO_CS_HIGH_CFG (as defined)
}
uint16_t ioPin = IO_Pin(io);
gpio_init(ioPin);
if (gpio_get_function(ioPin) == GPIO_FUNC_NULL) {
gpio_init(ioPin);
}
gpio_set_dir(ioPin, (cfg & 0x01)); // 0 = in, 1 = out
}
@ -124,3 +139,30 @@ IO_t IOGetByTag(ioTag_t tag)
return &ioRecs[pinIdx];
}
int IO_GPIOPortIdx(IO_t io)
{
if (!io) {
return -1;
}
return 0; // Single port
}
int IO_GPIO_PortSource(IO_t io)
{
return IO_GPIOPortIdx(io);
}
// zero based pin index
int IO_GPIOPinIdx(IO_t io)
{
if (!io) {
return -1;
}
return IO_Pin(io);
}
int IO_GPIO_PinSource(IO_t io)
{
return IO_GPIOPinIdx(io);
}

View file

@ -248,7 +248,7 @@ SECTIONS
*(.scratch_y.*)
. = ALIGN(4);
__scratch_y_end__ = .;
} > SCRATCH_Y AT > FLASH
} > SCRATCH_Y AT > FLASH =0xa5a5a5a5 /* BF: want to fill with STACK_FILL_CHAR to allow stack check - this doesn't seem to do it */
__scratch_y_source__ = LOADADDR(.scratch_y);
/* .stack*_dummy section doesn't contains any symbols. It is only
@ -306,6 +306,14 @@ SECTIONS
__StackBottom = __StackTop - SIZEOF(.stack_dummy);
PROVIDE(__stack = __StackTop);
/* BetaFlight:
* &_estack == Highest address of the user mode stack
* &_Min_Stack_Size = "required" (guaranteed) amount of stack
* We have all of SCRATCH_Y available uncontested for stack, length 4k = 0x1000
*/
_estack = __StackTop;
_Min_Stack_Size = 0x1000;
/* picolibc and LLVM */
PROVIDE (__heap_start = __end__);
PROVIDE (__heap_end = __HeapLimit);

View file

@ -4,10 +4,9 @@
# The top level Makefile adds $(MCU_COMMON_SRC) and $(DEVICE_STDPERIPH_SRC) to SRC collection.
#
# PICO_TRACE = 1
DEFAULT_OUTPUT := uf2
PICO_TRACE = 1
PICO_LIB_OPTIMISATION := -O2 -fuse-linker-plugin -ffast-math -fmerge-all-constants
# This file PICO.mk is $(TARGET_PLATFORM_DIR)/mk/$(TARGET_MCU_FAMILY).mk

View file

@ -1,4 +1,12 @@
# PICO_trace
#
# Allow tracing into and out of functions without modifying the source code
#
# Enable by setting PICO_TRACE variable in make, e.g. by export PICO_TRACE=1; make ...
#
PICO_WRAPPED_FUNCTIONS = main
PICO_WRAPPED_FUNCTIONS += init initEEPROM isEEPROMVersionValid
PICO_WRAPPED_FUNCTIONS += init initEEPROM isEEPROMVersionValid resetEEPROM writeUnmodifiedConfigToEEPROM resetConfig pgResetAll
PICO_TRACE_LD_FLAGS += $(foreach fn, $(PICO_WRAPPED_FUNCTIONS), -Wl,--wrap=$(fn))
PICO_TRACE_SRC += PICO/pico_trace.c
DEVICE_FLAGS += -DPICO_TRACE

View file

@ -1,287 +0,0 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
/** \file platform.h
* \defgroup pico_platform pico_platform
*
* \brief Macros and definitions (and functions when included by non assembly code) for the RP2 family device / architecture
* to provide a common abstraction over low level compiler / platform specifics
*
* This header may be included by assembly code
*/
#ifndef _PICO_PLATFORM_H
#define _PICO_PLATFORM_H
#ifndef _PICO_H
#error pico/platform.h should not be included directly; include pico.h instead
#endif
#include "pico/platform/compiler.h"
#include "pico/platform/sections.h"
#include "pico/platform/panic.h"
#include "hardware/regs/addressmap.h"
#include "hardware/regs/sio.h"
#ifdef __riscv
#include "hardware/regs/rvcsr.h"
#endif
// PICO_CONFIG: PICO_RP2350A, Whether the current board has an RP2350 in an A (30 GPIO) package, type=bool, default=Usually provided via board header, group=pico_platform
#if 0 // make tooling checks happy
#define PICO_RP2350A 0
#endif
// PICO_CONFIG: PICO_RP2350_A2_SUPPORTED, Whether to include any specific software support for RP2350 A2 revision, type=bool, default=1, advanced=true, group=pico_platform
#ifndef PICO_RP2350_A2_SUPPORTED
#define PICO_RP2350_A2_SUPPORTED 1
#endif
// PICO_CONFIG: PICO_STACK_SIZE, Minimum amount of stack space reserved in the linker script for each core. See also PICO_CORE1_STACK_SIZE, min=0x100, default=0x800, advanced=true, group=pico_platform
#ifndef PICO_STACK_SIZE
#define PICO_STACK_SIZE _u(0x800)
#endif
// PICO_CONFIG: PICO_HEAP_SIZE, Minimum amount of heap space reserved by the linker script, min=0x100, default=0x800, advanced=true, group=pico_platform
#ifndef PICO_HEAP_SIZE
#define PICO_HEAP_SIZE _u(0x800)
#endif
// PICO_CONFIG: PICO_NO_RAM_VECTOR_TABLE, Enable/disable the RAM vector table, type=bool, default=0, advanced=true, group=pico_platform
#ifndef PICO_NO_RAM_VECTOR_TABLE
#define PICO_NO_RAM_VECTOR_TABLE 0
#endif
#ifndef PICO_RAM_VECTOR_TABLE_SIZE
#define PICO_RAM_VECTOR_TABLE_SIZE (VTABLE_FIRST_IRQ + NUM_IRQS)
#endif
// PICO_CONFIG: PICO_USE_STACK_GUARDS, Enable/disable stack guards, type=bool, default=0, advanced=true, group=pico_platform
#ifndef PICO_USE_STACK_GUARDS
#define PICO_USE_STACK_GUARDS 0
#endif
// PICO_CONFIG: PICO_CLKDIV_ROUND_NEAREST, True if floating point clock divisors should be rounded to the nearest possible clock divisor by default rather than rounding down, type=bool, default=1, group=pico_platform
#ifndef PICO_CLKDIV_ROUND_NEAREST
#define PICO_CLKDIV_ROUND_NEAREST 1
#endif
#ifndef __ASSEMBLER__
/*! \brief No-op function for the body of tight loops
* \ingroup pico_platform
*
* No-op function intended to be called by any tight hardware polling loop. Using this ubiquitously
* makes it much easier to find tight loops, but also in the future \#ifdef-ed support for lockup
* debugging might be added
*/
static __force_inline void tight_loop_contents(void) {}
/*! \brief Helper method to busy-wait for at least the given number of cycles
* \ingroup pico_platform
*
* This method is useful for introducing very short delays.
*
* This method busy-waits in a tight loop for the given number of system clock cycles. The total wait time is only accurate to within 2 cycles,
* and this method uses a loop counter rather than a hardware timer, so the method will always take longer than expected if an
* interrupt is handled on the calling core during the busy-wait; you can of course disable interrupts to prevent this.
*
* You can use \ref clock_get_hz(clk_sys) to determine the number of clock cycles per second if you want to convert an actual
* time duration to a number of cycles.
*
* \param minimum_cycles the minimum number of system clock cycles to delay for
*/
static inline void busy_wait_at_least_cycles(uint32_t minimum_cycles) {
pico_default_asm_volatile (
#ifdef __riscv
// Note the range is halved on RISC-V due to signed comparison (no carry flag)
".option push\n"
".option norvc\n" // force 32 bit addi, so branch prediction guaranteed
".p2align 2\n"
"1: \n"
"addi %0, %0, -2 \n"
"bgez %0, 1b\n"
".option pop"
#else
"1: subs %0, #3\n"
"bcs 1b\n"
#endif
: "+r" (minimum_cycles) : : "cc", "memory"
);
}
// PICO_CONFIG: PICO_NO_FPGA_CHECK, Remove the FPGA platform check for small code size reduction, type=bool, default=1, advanced=true, group=pico_runtime
#ifndef PICO_NO_FPGA_CHECK
#define PICO_NO_FPGA_CHECK 1
#endif
// PICO_CONFIG: PICO_NO_SIM_CHECK, Remove the SIM platform check for small code size reduction, type=bool, default=1, advanced=true, group=pico_runtime
#ifndef PICO_NO_SIM_CHECK
#define PICO_NO_SIM_CHECK 1
#endif
#if PICO_NO_FPGA_CHECK
static inline bool running_on_fpga(void) {return false;}
#else
bool running_on_fpga(void);
#endif
#if PICO_NO_SIM_CHECK
static inline bool running_in_sim(void) {return false;}
#else
bool running_in_sim(void);
#endif
/*! \brief Execute a breakpoint instruction
* \ingroup pico_platform
*/
static __force_inline void __breakpoint(void) {
#ifdef __riscv
__asm ("ebreak");
#else
pico_default_asm_volatile ("bkpt #0" : : : "memory");
#endif
}
/*! \brief Get the current core number
* \ingroup pico_platform
*
* \return The core number the call was made from
*/
__force_inline static uint get_core_num(void) {
return (*(uint32_t *) (SIO_BASE + SIO_CPUID_OFFSET));
}
/*! \brief Get the current exception level on this core
* \ingroup pico_platform
*
* On Cortex-M this is the exception number defined in the architecture
* reference, which is equal to VTABLE_FIRST_IRQ + irq num if inside an
* interrupt handler. (VTABLE_FIRST_IRQ is defined in platform_defs.h).
*
* On Hazard3, this function returns VTABLE_FIRST_IRQ + irq num if inside of
* an external IRQ handler (or a fault from such a handler), and 0 otherwise,
* generally aligning with the Cortex-M values.
*
* \return the exception number if the CPU is handling an exception, or 0 otherwise
*/
static __force_inline uint __get_current_exception(void) {
#ifdef __riscv
uint32_t meicontext;
pico_default_asm_volatile (
"csrr %0, %1\n"
: "=r" (meicontext) : "i" (RVCSR_MEICONTEXT_OFFSET)
);
if (meicontext & RVCSR_MEICONTEXT_NOIRQ_BITS) {
return 0;
} else {
return VTABLE_FIRST_IRQ + (
(meicontext & RVCSR_MEICONTEXT_IRQ_BITS) >> RVCSR_MEICONTEXT_IRQ_LSB
);
}
#else
uint exception;
pico_default_asm_volatile (
"mrs %0, ipsr\n"
"uxtb %0, %0\n"
: "=l" (exception)
);
return exception;
#endif
}
/*! \brief Return true if executing in the NonSecure state (Arm-only)
* \ingroup pico_platform
*
* \return True if currently executing in the NonSecure state on an Arm processor
*/
__force_inline static bool pico_processor_state_is_nonsecure(void) {
#ifndef __riscv
// todo add a define to disable NS checking at all?
// IDAU-Exempt addresses return S=1 when tested in the Secure state,
// whereas executing a tt in the NonSecure state will always return S=0.
uint32_t tt;
pico_default_asm_volatile (
"movs %0, #0\n"
"tt %0, %0\n"
: "=r" (tt) : : "cc"
);
return !(tt & (1u << 22));
#else
// NonSecure is an Arm concept, there is nothing meaningful to return
// here. Note it's not possible in general to detect whether you are
// executing in U-mode as, for example, M-mode is classically
// virtualisable in U-mode.
return false;
#endif
}
#define host_safe_hw_ptr(x) ((uintptr_t)(x))
#define native_safe_hw_ptr(x) host_safe_hw_ptr(x)
/*! \brief Returns the RP2350 chip revision number
* \ingroup pico_platform
* @return the RP2350 chip revision number (1 for B0/B1, 2 for B2)
*/
uint8_t rp2350_chip_version(void);
/*! \brief Returns the RP2040 chip revision number for compatibility
* \ingroup pico_platform
* @return 2 RP2040 errata fixed in B2 are fixed in RP2350
*/
static inline uint8_t rp2040_chip_version(void) {
return 2;
}
/*! \brief Returns the RP2040 rom version number
* \ingroup pico_platform
* @return the RP2040 rom version number (1 for RP2040-B0, 2 for RP2040-B1, 3 for RP2040-B2)
*/
static inline uint8_t rp2040_rom_version(void) {
GCC_Pragma("GCC diagnostic push")
GCC_Pragma("GCC diagnostic ignored \"-Warray-bounds\"")
return *(uint8_t*)0x13;
GCC_Pragma("GCC diagnostic pop")
}
/*! \brief Multiply two integers using an assembly `MUL` instruction
* \ingroup pico_platform
*
* This multiplies a by b using multiply instruction using the ARM mul instruction regardless of values (the compiler
* might otherwise choose to perform shifts/adds), i.e. this is a 1 cycle operation.
*
* \param a the first operand
* \param b the second operand
* \return a * b
*/
__force_inline static int32_t __mul_instruction(int32_t a, int32_t b) {
#ifdef __riscv
__asm ("mul %0, %0, %1" : "+r" (a) : "r" (b) : );
#else
pico_default_asm ("muls %0, %1" : "+l" (a) : "l" (b) : "cc");
#endif
return a;
}
/*! \brief multiply two integer values using the fastest method possible
* \ingroup pico_platform
*
* Efficiently multiplies value a by possibly constant value b.
*
* If b is known to be constant and not zero or a power of 2, then a mul instruction is used rather than gcc's default
* which is often a slow combination of shifts and adds. If b is a power of 2 then a single shift is of course preferable
* and will be used
*
* \param a the first operand
* \param b the second operand
* \return a * b
*/
#define __fast_mul(a, b) __builtin_choose_expr(__builtin_constant_p(b) && !__builtin_constant_p(a), \
(__builtin_popcount(b) >= 2 ? __mul_instruction(a,b) : (a)*(b)), \
(a)*(b))
#endif // __ASSEMBLER__
#endif

View file

@ -1,25 +1,102 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software under the terms of the GNU General
* Public License as published by the Free Software Foundation,
* either version 3 of the License, or (at your option) any later
* version.
*
* Betaflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public
* License along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "pico_trace.h"
#include "pico/stdio.h"
#include "pico/stdio_uart.h"
#include "pico/platform/compiler.h"
static int depth;
static const char* prefix[]= {
"-- ",
"--- ",
"---- ",
"----- ",
"------ ",
"------- "
};
static const int plen = sizeof(prefix)/sizeof(prefix[0]);
void picotrace_prefix(void)
{
stdio_printf(prefix[depth%plen]);
}
// Wrap main to insert the initialisation code.
extern int main(int argc, char * argv[]);
extern int REAL_FUNC(main)(int argc, char * argv[]);
int WRAPPER_FUNC(main)(int argc, char * argv[])
{
stdio_init_all();
return REAL_FUNC(main)(argc, argv);
//stdio_init_all();
stdio_uart_init();
tprintf("\n=== Betaflight main ===");
depth++;
int mr = REAL_FUNC(main)(argc, argv);
depth--;
tprintf("\n=== Betaflight main end ===");
return mr;
}
#define TRACEvoidvoid(x) \
extern void x(void);\
extern void REAL_FUNC(x)(void); \
void WRAPPER_FUNC(x)(void)\
{\
tprintf("*** enter " #x " ***");\
REAL_FUNC(x)();\
tprintf("*** exit " #x " ***");\
extern void x(void); \
extern void REAL_FUNC(x)(void); \
void WRAPPER_FUNC(x)(void) \
{ \
tprintf("Enter " #x ""); \
depth++;REAL_FUNC(x)();depth--; \
tprintf("Exit " #x ""); \
}
#define TRACEboolvoid(x) \
extern bool x(void); \
extern bool REAL_FUNC(x)(void); \
bool WRAPPER_FUNC(x)(void) \
{ \
tprintf("Enter " #x ""); \
depth++; \
bool ret__ = REAL_FUNC(x)(); \
depth--; \
tprintf("Exit " #x ""); \
return ret__; \
}
#define TRACEvoidbool(x) \
extern void x(bool _); \
extern void REAL_FUNC(x)(bool _); \
void WRAPPER_FUNC(x)(bool xyz__) \
{ \
tprintf("Enter " #x " [%d]", xyz__); \
depth++; REAL_FUNC(x)(xyz__); depth--; \
tprintf("Exit " #x ""); \
}
// remember to add to PICO_WRAPPED_FUNCTIONS in PICO_trace.mk
TRACEvoidvoid(init)
TRACEvoidvoid(initEEPROM)
TRACEvoidvoid(isEEPROMVersionValid)
TRACEvoidvoid(initEEPROM)
TRACEvoidvoid(isEEPROMVersionValid)
TRACEvoidvoid(writeUnmodifiedConfigToEEPROM)
TRACEboolvoid(resetEEPROM)
TRACEvoidvoid(resetConfig)
TRACEvoidvoid(pgResetAll)
TRACEvoidbool(serialInit)

View file

@ -1,5 +1,10 @@
#include "pico/stdio.h"
#include "pico/platform/compiler.h"
#pragma once
#define tprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0)
extern void picotrace_prefix(void);
#define tprintf(fmt,...) do { \
picotrace_prefix(); \
stdio_printf(fmt, ## __VA_ARGS__); \
stdio_printf("\n"); \
} while (0)

View file

@ -45,35 +45,35 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.identifier = SERIAL_PORT_UART0,
.reg = uart0,
.rxPins = {
{ DEFIO_TAG_E(P1) },
{ DEFIO_TAG_E(P3) },
{ DEFIO_TAG_E(P13) },
{ DEFIO_TAG_E(P15) },
{ DEFIO_TAG_E(P17) },
{ DEFIO_TAG_E(P19) },
{ DEFIO_TAG_E(P29) },
{ DEFIO_TAG_E(PA1) },
{ DEFIO_TAG_E(PA3) },
{ DEFIO_TAG_E(PA13) },
{ DEFIO_TAG_E(PA15) },
{ DEFIO_TAG_E(PA17) },
{ DEFIO_TAG_E(PA19) },
{ DEFIO_TAG_E(PA29) },
#ifdef RP2350B
{ DEFIO_TAG_E(P31) },
{ DEFIO_TAG_E(P33) },
{ DEFIO_TAG_E(P35) },
{ DEFIO_TAG_E(P45) },
{ DEFIO_TAG_E(P47) },
{ DEFIO_TAG_E(PA31) },
{ DEFIO_TAG_E(PA33) },
{ DEFIO_TAG_E(PA35) },
{ DEFIO_TAG_E(PA45) },
{ DEFIO_TAG_E(PA47) },
#endif
},
.txPins = {
{ DEFIO_TAG_E(P0) },
{ DEFIO_TAG_E(P2) },
{ DEFIO_TAG_E(P12) },
{ DEFIO_TAG_E(P14) },
{ DEFIO_TAG_E(P16) },
{ DEFIO_TAG_E(P18) },
{ DEFIO_TAG_E(P28) },
{ DEFIO_TAG_E(PA0) },
{ DEFIO_TAG_E(PA2) },
{ DEFIO_TAG_E(PA12) },
{ DEFIO_TAG_E(PA14) },
{ DEFIO_TAG_E(PA16) },
{ DEFIO_TAG_E(PA18) },
{ DEFIO_TAG_E(PA28) },
#ifdef RP2350B
{ DEFIO_TAG_E(P30) },
{ DEFIO_TAG_E(P32) },
{ DEFIO_TAG_E(P34) },
{ DEFIO_TAG_E(P44) },
{ DEFIO_TAG_E(P46) },
{ DEFIO_TAG_E(PA30) },
{ DEFIO_TAG_E(PA32) },
{ DEFIO_TAG_E(PA34) },
{ DEFIO_TAG_E(PA44) },
{ DEFIO_TAG_E(PA46) },
#endif
},
.irqn = UART0_IRQ,
@ -89,35 +89,35 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.identifier = SERIAL_PORT_UART1,
.reg = uart1,
.rxPins = {
{ DEFIO_TAG_E(P5) },
{ DEFIO_TAG_E(P7) },
{ DEFIO_TAG_E(P9) },
{ DEFIO_TAG_E(P11) },
{ DEFIO_TAG_E(P21) },
{ DEFIO_TAG_E(P23) },
{ DEFIO_TAG_E(P25) },
{ DEFIO_TAG_E(P27) },
{ DEFIO_TAG_E(PA5) },
{ DEFIO_TAG_E(PA7) },
{ DEFIO_TAG_E(PA9) },
{ DEFIO_TAG_E(PA11) },
{ DEFIO_TAG_E(PA21) },
{ DEFIO_TAG_E(PA23) },
{ DEFIO_TAG_E(PA25) },
{ DEFIO_TAG_E(PA27) },
#ifdef RP2350B
{ DEFIO_TAG_E(P37) },
{ DEFIO_TAG_E(P39) },
{ DEFIO_TAG_E(P41) },
{ DEFIO_TAG_E(P43) },
{ DEFIO_TAG_E(PA37) },
{ DEFIO_TAG_E(PA39) },
{ DEFIO_TAG_E(PA41) },
{ DEFIO_TAG_E(PA43) },
#endif
},
.txPins = {
{ DEFIO_TAG_E(P4) },
{ DEFIO_TAG_E(P6) },
{ DEFIO_TAG_E(P8) },
{ DEFIO_TAG_E(P10) },
{ DEFIO_TAG_E(P20) },
{ DEFIO_TAG_E(P22) },
{ DEFIO_TAG_E(P24) },
{ DEFIO_TAG_E(P26) },
{ DEFIO_TAG_E(PA4) },
{ DEFIO_TAG_E(PA6) },
{ DEFIO_TAG_E(PA8) },
{ DEFIO_TAG_E(PA10) },
{ DEFIO_TAG_E(PA20) },
{ DEFIO_TAG_E(PA22) },
{ DEFIO_TAG_E(PA24) },
{ DEFIO_TAG_E(PA26) },
#ifdef RP2350B
{ DEFIO_TAG_E(P36) },
{ DEFIO_TAG_E(P38) },
{ DEFIO_TAG_E(P40) },
{ DEFIO_TAG_E(P42) },
{ DEFIO_TAG_E(PA36) },
{ DEFIO_TAG_E(PA38) },
{ DEFIO_TAG_E(PA40) },
{ DEFIO_TAG_E(PA42) },
#endif
},
.irqn = UART1_IRQ,
@ -195,7 +195,7 @@ uartPort_t *serialUART(uartDevice_t *uartdev, uint32_t baudRate, portMode_e mode
const resourceOwner_e ownerTxRx = serialOwnerTxRx(identifier); // rx is always +1
IOInit(txIO, ownerTxRx, ownerIndex);
IOInit(txIO, ownerTxRx, ownerIndex);
IOInit(rxIO, ownerTxRx, ownerIndex);
uart_init(hardware->reg, baudRate);

View file

@ -34,16 +34,11 @@
#include "hardware/clocks.h"
#include "pico/unique_id.h"
int main(int argc, char * argv[]);
void Reset_Handler(void);
void Default_Handler(void);
// cycles per microsecond
static uint32_t usTicks = 0;
///////////////////////////////////////////////////
// SystemInit and SystemCoreClock variables/functions,
// as per pico-sdk rp2_common/cmsis/stub/CMSIS/Device/RP2350/Source/system_RP2350.c
uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock)*/
void SystemCoreClockUpdate (void)
@ -56,61 +51,7 @@ void __attribute__((constructor)) SystemInit (void)
SystemCoreClockUpdate();
}
/////////////////////////////////////////////////
// TODO: check: don't define functions here provided by pico-sdk crt0
// crt0.S defines the vector table in the .vectors section, with
// initial stack pointer at __StackTop (defined in linker script),
// and with reset handler pointing to code inside crt0.S
#if 0
void (* const vector_table[])() __attribute__((section(".vectors"))) = {
(void (*)())0x20000000, // Initial Stack Pointer
Reset_Handler, // Interrupt Handler for reset
Default_Handler, // Default handler for other interrupts
};
void Default_Handler(void)
{
while (1); // Infinite loop on default handler
}
void Reset_Handler(void)
{
// Initialize data segments
extern uint32_t _sdata, _edata, _sidata;
uint32_t *src = &_sidata;
uint32_t *dst = &_sdata;
while (dst < &_edata) {
*dst++ = *src++;
}
// Clear bss segment
extern uint32_t _sbss, _ebss;
dst = &_sbss;
while (dst < &_ebss) {
*dst++ = 0;
}
usTicks = clock_get_hz(clk_sys) / 1000000;
// Call main function
main(0, 0);
}
void __unhandled_user_irq(void)
{
// TODO
}
#endif
/////////////////////////////////////////////////////
////////////////////////////////////////////////////
void systemReset(void)
{
@ -119,10 +60,36 @@ void systemReset(void)
uint32_t systemUniqueId[3] = { 0 };
// cycles per microsecond
static uint32_t usTicks = 0;
static float usTicksInv = 0.0f;
#define PICO_DWT_CTRL ((uint32_t *)(PPB_BASE + M33_DWT_CTRL_OFFSET))
#define PICO_DWT_CYCCNT ((uint32_t *)(PPB_BASE + M33_DWT_CYCCNT_OFFSET))
#define PICO_DEMCR ((uint32_t *)(PPB_BASE + M33_DEMCR_OFFSET))
void cycleCounterInit(void)
{
// TODO check clock_get_hz(clk_sys) is the clock for CPU cycles
usTicks = SystemCoreClock / 1000000;
usTicksInv = 1e6f / SystemCoreClock;
// Global DWT enable
*PICO_DEMCR |= M33_DEMCR_TRCENA_BITS;
// Reset and enable cycle counter
*PICO_DWT_CYCCNT = 0;
*PICO_DWT_CTRL |= M33_DWT_CTRL_CYCCNTENA_BITS;
}
void systemInit(void)
{
//TODO: implement
SystemInit();
cycleCounterInit();
// load the unique id into a local array
pico_unique_board_id_t id;
pico_get_unique_board_id(&id);
@ -138,11 +105,10 @@ void systemResetToBootloader(bootloaderRequestType_e requestType)
// Return system uptime in milliseconds (rollover in 49 days)
uint32_t millis(void)
{
//TODO: correction required?
return time_us_32() / 1000;
return (uint32_t)(time_us_64() / 1000);
}
// Return system uptime in micros
// Return system uptime in micros (rollover in 71 mins)
uint32_t micros(void)
{
return time_us_32();
@ -153,38 +119,46 @@ uint32_t microsISR(void)
return micros();
}
#define PICO_NON_BUSY_SLEEP
void delayMicroseconds(uint32_t us)
{
#ifdef PICO_NON_BUSY_SLEEP
sleep_us(us);
#else
uint32_t now = micros();
while (micros() - now < us);
#endif
}
void delay(uint32_t ms)
{
#ifdef PICO_NON_BUSY_SLEEP
sleep_ms(ms);
#else
while (ms--) {
delayMicroseconds(1000);
}
#endif
}
uint32_t getCycleCounter(void)
{
return time_us_32();
return *PICO_DWT_CYCCNT;
}
// Conversion routines copied from platform/common/stm32/system.c
int32_t clockCyclesToMicros(int32_t clockCycles)
{
return clockCycles / usTicks;
}
float clockCyclesToMicrosf(int32_t clockCycles)
{
return clockCycles * usTicksInv;
}
// Note that this conversion is signed as this is used for periods rather than absolute timestamps
int32_t clockCyclesTo10thMicros(int32_t clockCycles)
{
return 10 * clockCycles / (int32_t)usTicks;
}
// Note that this conversion is signed as this is used for periods rather than absolute timestamps
int32_t clockCyclesTo100thMicros(int32_t clockCycles)
{
return 100 * clockCycles / (int32_t)usTicks;
}
uint32_t clockMicrosToCycles(uint32_t micros)
{
if (!usTicks) {
usTicks = clock_get_hz(clk_sys) / 1000000;
}
return micros * usTicks;
}
@ -232,7 +206,6 @@ void failureMode(failureMode_e mode)
#endif
}
static void unusedPinInit(IO_t io)
{
if (IOGetOwner(io) == OWNER_FREE) {

View file

@ -21,10 +21,12 @@
#pragma once
#ifdef PICO_STDIO_TEST
void _bprintf(const char * format, ...);
#ifdef PICO_TRACE
//void _bprintf(const char * format, ...);
//#define bprintf(fmt,...) _bprintf(fmt, ## __VA_ARGS__)
#define bprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0)
//#define bprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0)
#include "pico_trace.h"
#define bprintf tprintf
//int __wrap_printf(const char * fmt, ...);
//#define bprintf __wrap_printf
#else
@ -149,30 +151,30 @@ void _bprintf(const char * format, ...);
/* to be moved to a config file once target if working
defaults as per Laurel board for now */
#define LED0_PIN P25
#define LED0_PIN PA25
#undef LED1_PIN
#undef LED2_PIN
// These pin selections are currently fairly arbitrary for RP2350A
#define SPI0_SCK_PIN P2
#define SPI0_SDI_PIN P4
#define SPI0_SDO_PIN P3
#define SPI0_SCK_PIN PA2
#define SPI0_SDI_PIN PA4
#define SPI0_SDO_PIN PA3
#define SPI1_SCK_PIN P26
#define SPI1_SDI_PIN P24
#define SPI1_SDO_PIN P27
#define SPI1_SCK_PIN PA26
#define SPI1_SDI_PIN PA24
#define SPI1_SDO_PIN PA27
#define SDCARD_CS_PIN P25
#define FLASH_CS_PIN P25
#define MAX7456_SPI_CS_PIN P17
#define SDCARD_CS_PIN PA25
#define FLASH_CS_PIN PA25
#define MAX7456_SPI_CS_PIN PA17
#define GYRO_1_CS_PIN P1
#define GYRO_1_CS_PIN PA1
#define GYRO_2_CS_PIN NONE
#define MOTOR1_PIN P18
#define MOTOR2_PIN P19
#define MOTOR3_PIN P20
#define MOTOR4_PIN P21
#define MOTOR1_PIN PA18
#define MOTOR2_PIN PA19
#define MOTOR3_PIN PA20
#define MOTOR4_PIN PA21
#define MAX7456_SPI_INSTANCE SPI1
#define SDCARD_SPI_INSTANCE SPI1
@ -188,58 +190,58 @@ void _bprintf(const char * format, ...);
/*
SPI0_CS P1
SPI0_SCLK P2
SPI0_COPI P3
SPI0_CIPO P4
BUZZER P5
LED0 P6
LED1 P7
UART1_TX P8
UART1_RX P9
I2C1_SDA P10
I2C1_SCL P11
UART0_TX P12
UART0_RX P13
SPI0_CS PA1
SPI0_SCLK PA2
SPI0_COPI PA3
SPI0_CIPO PA4
BUZZER PA5
LED0 PA6
LED1 PA7
UART1_TX PA8
UART1_RX PA9
I2C1_SDA PA10
I2C1_SCL PA11
UART0_TX PA12
UART0_RX PA13
OSD_CS P17
OSD_CS PA17
UART2_TX P20
UART2_RX P21
UART2_TX PA20
UART2_RX PA21
GYRO_INT P22
GYRO_INT PA22
GYRO_CLK P23
GYRO_CLK PA23
SPI1_CIPO P24
SPI1_CS P25
SPI1_SCLK P26
SPI1_COPI P27
SPI1_CIPO PA24
SPI1_CS PA25
SPI1_SCLK PA26
SPI1_COPI PA27
MOTOR1 P28
MOTOR2 P29
MOTOR3 P30
MOTOR4 P31
MOTOR1 PA28
MOTOR2 PA29
MOTOR3 PA30
MOTOR4 PA31
SPARE1 P32
SPARE2 P33
SPARE1 PA32
SPARE2 PA33
UART3_TX P34
UART3_RX P35
UART3_TX PA34
UART3_RX PA35
DVTX_SBUS_RX P36
TELEM_RX P37
LED_STRIP P38
RGB_LED P39
DVTX_SBUS_RX PA36
TELEM_RX PA37
LED_STRIP PA38
RGB_LED PA39
VBAT_SENSE P40
CURR_SENSE P41
ADC_SPARE P42
VBAT_SENSE PA40
CURR_SENSE PA41
ADC_SPARE PA42
I2C0_SDA P44
I2C0_SCL P45
I2C0_SDA PA44
I2C0_SCL PA45
SPARE3 P47
SPARE3 PA47
*/

View file

@ -21,17 +21,18 @@
#pragma once
#ifdef PICO_STDIO_TEST
void _bprintf(const char * format, ...);
#ifdef PICO_TRACE
//void _bprintf(const char * format, ...);
//#define bprintf(fmt,...) _bprintf(fmt, ## __VA_ARGS__)
#define bprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0)
//#define bprintf(fmt,...) do {stdio_printf(fmt, ## __VA_ARGS__); stdio_printf("\n"); } while (0)
#include "pico_trace.h"
#define bprintf tprintf
//int __wrap_printf(const char * fmt, ...);
//#define bprintf __wrap_printf
#else
#define bprintf(fmt,...)
#endif
#ifndef RP2350B
#define RP2350B
#endif
@ -69,7 +70,7 @@ void _bprintf(const char * format, ...);
#undef USE_TIMER
#undef USE_I2C
#undef USE_RCC
#undef USE_CLI
#undef USE_RX_PWM
#undef USE_RX_PPM
#undef USE_RX_SPI
@ -96,9 +97,22 @@ void _bprintf(const char * format, ...);
#undef USE_OSD
#undef USE_SPEKTRUM
#undef USE_SPEKTRUM_BIND
#undef USE_MSP
// #undef USE_CLI
#undef USE_SERIAL_PASSTHROUGH
// #undef USE_MSP
#undef USE_MSP_UART
#undef USE_MSP_DISPLAYPORT
#undef USE_DMA
#undef USE_DMA_SPEC
#undef USE_DSHOT_TELEMETRY
#undef USE_ESC_SENSOR
#undef USE_PWM_OUTPUT
#undef USE_GPS
#undef USE_GPS_UBLOX
#undef USE_GPS_MTK
@ -134,7 +148,6 @@ void _bprintf(const char * format, ...);
#undef USE_OSD_SD
#undef USE_OSD_HD
#undef USE_OSD_QUICK_MENU
#undef USE_GPS
#undef USE_POSITION_HOLD
//#define FLASH_PAGE_SIZE 0x1
@ -147,28 +160,36 @@ void _bprintf(const char * format, ...);
/* to be moved to a config file once target if working
defaults as per Laurel board for now */
#define LED0_PIN P6
#define LED1_PIN P7
#define LED0_PIN PA6
#define LED1_PIN PA7
#define SPI0_SCK_PIN P2
#define SPI0_SDI_PIN P4
#define SPI0_SDO_PIN P3
#define SPI0_SCK_PIN PA2
#define SPI0_SDI_PIN PA4
#define SPI0_SDO_PIN PA3
#define SPI1_SCK_PIN P26
#define SPI1_SDI_PIN P24
#define SPI1_SDO_PIN P27
#define SPI1_SCK_PIN PA26
#define SPI1_SDI_PIN PA24
#define SPI1_SDO_PIN PA27
#define SDCARD_CS_PIN P25
#define FLASH_CS_PIN P25
#define MAX7456_SPI_CS_PIN P17
#define SDCARD_CS_PIN PA25
#define FLASH_CS_PIN PA25
#define MAX7456_SPI_CS_PIN PA17
#define GYRO_1_CS_PIN P1
#define GYRO_1_CS_PIN PA1
#define GYRO_2_CS_PIN NONE
#define MOTOR1_PIN P28
#define MOTOR2_PIN P29
#define MOTOR3_PIN P30
#define MOTOR4_PIN P31
#if 0 // def TEST_DSHOT_ETC
// testing motor1 and motor2 pins -> GPIO_SPARE1, GPIO_SPARE2
#define MOTOR1_PIN PA32
#define MOTOR2_PIN PA33
#define MOTOR3_PIN PA30
#define MOTOR4_PIN PA31
#else
#define MOTOR1_PIN PA28
#define MOTOR2_PIN PA29
#define MOTOR3_PIN PA30
#define MOTOR4_PIN PA31
#endif
#define MAX7456_SPI_INSTANCE SPI1
#define SDCARD_SPI_INSTANCE SPI1
@ -178,64 +199,76 @@ void _bprintf(const char * format, ...);
#define USE_GYRO_SPI_ICM42688P
#define USE_ACC
#define USE_ACC_SPI_ICM42688P
#ifdef GYRO_ONLY_ICM42688
#undef USE_ACCGYRO_LSM6DSV16X
#undef USE_GYRO_SPI_ICM20689
#undef USE_GYRO_SPI_MPU6000
#undef USE_GYRO_SPI_MPU6500
#undef USE_GYRO_SPI_MPU9250
#undef USE_ACCGYRO_LSM6DSO
#undef USE_ACCGYRO_BMI160
#undef USE_ACCGYRO_BMI270
#endif
//#define USE_FLASH
//#define USE_FLASH_W25Q128FV
//#define USE_MAX7456
/*
SPI0_CS P1
SPI0_SCLK P2
SPI0_COPI P3
SPI0_CIPO P4
BUZZER P5
LED0 P6
LED1 P7
UART1_TX P8
UART1_RX P9
I2C1_SDA P10
I2C1_SCL P11
UART0_TX P12
UART0_RX P13
SPI0_CS PA1
SPI0_SCLK PA2
SPI0_COPI PA3
SPI0_CIPO PA4
BUZZER PA5
LED0 PA6
LED1 PA7
UART1_TX PA8
UART1_RX PA9
I2C1_SDA PA10
I2C1_SCL PA11
UART0_TX PA12
UART0_RX PA13
OSD_CS P17
OSD_CS PA17
UART2_TX P20
UART2_RX P21
UART2_TX PA20
UART2_RX PA21
GYRO_INT P22
GYRO_INT PA22
GYRO_CLK P23
GYRO_CLK PA23
SPI1_CIPO P24
SPI1_CS P25
SPI1_SCLK P26
SPI1_COPI P27
SPI1_CIPO PA24
SPI1_CS PA25
SPI1_SCLK PA26
SPI1_COPI PA27
MOTOR1 P28
MOTOR2 P29
MOTOR3 P30
MOTOR4 P31
MOTOR1 PA28
MOTOR2 PA29
MOTOR3 PA30
MOTOR4 PA31
SPARE1 P32
SPARE2 P33
SPARE1 PA32
SPARE2 PA33
UART3_TX P34
UART3_RX P35
UART3_TX PA34
UART3_RX PA35
DVTX_SBUS_RX P36
TELEM_RX P37
LED_STRIP P38
RGB_LED P39
DVTX_SBUS_RX PA36
TELEM_RX PA37
LED_STRIP PA38
RGB_LED PA39
VBAT_SENSE P40
CURR_SENSE P41
ADC_SPARE P42
VBAT_SENSE PA40
CURR_SENSE PA41
ADC_SPARE PA42
I2C0_SDA P44
I2C0_SCL P45
I2C0_SDA PA44
I2C0_SCL PA45
SPARE3 P47
SPARE3 PA47
*/

View file

@ -19,6 +19,8 @@
* If not, see <http://www.gnu.org/licenses/>.
*/
// TODO replace with stdio_usb from pico-sdk, with a few wrappers
#include "platform.h"
#include "tusb_config.h"

View file

@ -1,186 +0,0 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software under the terms of the GNU General
* Public License as published by the Free Software Foundation,
* either version 3 of the License, or (at your option) any later
* version.
*
* Betaflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public
* License along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* This file is based on a file originally part of the
* MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
* Copyright (c) 2019 Damien P. George
*
* 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.
*/
#include "tusb.h"
#include "pico/unique_id.h"
#include "common/utils.h"
#ifndef USBD_VID
// Raspberry Pi
#define USBD_VID (0x2E8A)
#endif
#ifndef USBD_PID
#if PICO_RP2040
// Raspberry Pi Pico SDK CDC for RP2040
#define USBD_PID (0x000a)
#else
// Raspberry Pi Pico SDK CDC
#define USBD_PID (0x0009)
#endif
#endif
#ifndef USBD_MANUFACTURER
#define USBD_MANUFACTURER "Betaflight Pico"
#endif
#ifndef USBD_PRODUCT
#define USBD_PRODUCT "Pico"
#endif
#define TUD_RPI_RESET_DESC_LEN 9
#define USBD_DESC_LEN (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_RPI_RESET_DESC_LEN)
#define USBD_CONFIGURATION_DESCRIPTOR_ATTRIBUTE 0
#define USBD_MAX_POWER_MA 250
#define USBD_ITF_CDC 0 // needs 2 interfaces
#define USBD_ITF_MAX 2
#define USBD_CDC_EP_CMD 0x81
#define USBD_CDC_EP_OUT 0x02
#define USBD_CDC_EP_IN 0x82
#define USBD_CDC_CMD_MAX_SIZE 8
#define USBD_CDC_IN_OUT_MAX_SIZE 64
#define USBD_STR_0 0x00
#define USBD_STR_MANUF 0x01
#define USBD_STR_PRODUCT 0x02
#define USBD_STR_SERIAL 0x03
#define USBD_STR_CDC 0x04
#define USBD_STR_RPI_RESET 0x05
// Note: descriptors returned from callbacks must exist long enough for transfer to complete
static const tusb_desc_device_t usbd_desc_device = {
.bLength = sizeof(tusb_desc_device_t),
.bDescriptorType = TUSB_DESC_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = TUSB_CLASS_MISC,
.bDeviceSubClass = MISC_SUBCLASS_COMMON,
.bDeviceProtocol = MISC_PROTOCOL_IAD,
.bMaxPacketSize0 = CFG_TUD_ENDPOINT0_SIZE,
.idVendor = USBD_VID,
.idProduct = USBD_PID,
.bcdDevice = 0x0100,
.iManufacturer = USBD_STR_MANUF,
.iProduct = USBD_STR_PRODUCT,
.iSerialNumber = USBD_STR_SERIAL,
.bNumConfigurations = 1,
};
#define TUD_RPI_RESET_DESCRIPTOR(_itfnum, _stridx) \
/* Interface */\
9, TUSB_DESC_INTERFACE, _itfnum, 0, 0, TUSB_CLASS_VENDOR_SPECIFIC, RESET_INTERFACE_SUBCLASS, RESET_INTERFACE_PROTOCOL, _stridx,
static const uint8_t usbd_desc_cfg[USBD_DESC_LEN] = {
TUD_CONFIG_DESCRIPTOR(1, USBD_ITF_MAX, USBD_STR_0, USBD_DESC_LEN,
USBD_CONFIGURATION_DESCRIPTOR_ATTRIBUTE, USBD_MAX_POWER_MA),
TUD_CDC_DESCRIPTOR(USBD_ITF_CDC, USBD_STR_CDC, USBD_CDC_EP_CMD,
USBD_CDC_CMD_MAX_SIZE, USBD_CDC_EP_OUT, USBD_CDC_EP_IN, USBD_CDC_IN_OUT_MAX_SIZE),
};
static char usbd_serial_str[PICO_UNIQUE_BOARD_ID_SIZE_BYTES * 2 + 1];
static const char *const usbd_desc_str[] = {
[USBD_STR_MANUF] = USBD_MANUFACTURER,
[USBD_STR_PRODUCT] = USBD_PRODUCT,
[USBD_STR_SERIAL] = usbd_serial_str,
[USBD_STR_CDC] = "Board CDC",
};
const uint8_t *tud_descriptor_device_cb(void)
{
return (const uint8_t *)&usbd_desc_device;
}
const uint8_t *tud_descriptor_configuration_cb(uint8_t index)
{
UNUSED(index);
return usbd_desc_cfg;
}
const uint16_t *tud_descriptor_string_cb(uint8_t index, uint16_t langid)
{
UNUSED(langid);
#ifndef USBD_DESC_STR_MAX
#define USBD_DESC_STR_MAX (20)
#elif USBD_DESC_STR_MAX > 127
#error USBD_DESC_STR_MAX too high (max is 127).
#elif USBD_DESC_STR_MAX < 17
#error USBD_DESC_STR_MAX too low (min is 17).
#endif
static uint16_t desc_str[USBD_DESC_STR_MAX];
// Assign the SN using the unique flash id
if (!usbd_serial_str[0]) {
pico_get_unique_board_id_string(usbd_serial_str, sizeof(usbd_serial_str));
}
unsigned len;
if (index == 0) {
desc_str[1] = 0x0409; // supported language is English
len = 1;
} else {
if (index >= ARRAYLEN(usbd_desc_str)) {
return NULL;
}
const char *str = usbd_desc_str[index];
for (len = 0; len < USBD_DESC_STR_MAX - 1 && str[len]; ++len) {
desc_str[1 + len] = str[len];
}
}
// first byte is length (including header), second byte is string type
desc_str[0] = (uint16_t)((TUSB_DESC_STRING << 8) | (2 * len + 2));
return desc_str;
}