mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 11:00:02 +03:00
Merge branch 'RP2350'
This commit is contained in:
commit
9b4d123db3
45 changed files with 6600 additions and 1 deletions
|
@ -727,6 +727,7 @@ void init(void)
|
|||
delay(50);
|
||||
#endif
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
|
|
243
src/platform/PICO/bus_i2c_pico.c
Normal file
243
src/platform/PICO/bus_i2c_pico.c
Normal file
|
@ -0,0 +1,243 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_I2C) && !defined(SOFT_I2C)
|
||||
|
||||
#include "pg/bus_i2c.h"
|
||||
|
||||
#include "hardware/i2c.h"
|
||||
#include "hardware/dma.h"
|
||||
#include "hardware/irq.h"
|
||||
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_i2c_impl.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
|
||||
#define I2C_TX_BUFFER_LENGTH 32
|
||||
|
||||
static volatile uint16_t i2cErrorCount = 0;
|
||||
|
||||
i2cDevice_t i2cDevice[I2CDEV_COUNT];
|
||||
|
||||
const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
|
||||
#ifdef USE_I2C_DEVICE_0
|
||||
{
|
||||
.device = I2CDEV_0,
|
||||
.reg = i2c0,
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
{
|
||||
.device = I2CDEV_1,
|
||||
.reg = i2c1,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
void i2cPinConfigure(const i2cConfig_t *i2cConfig)
|
||||
{
|
||||
for (int index = 0 ; index < I2CDEV_COUNT ; index++) {
|
||||
const i2cHardware_t *hardware = &i2cHardware[index];
|
||||
|
||||
if (!hardware->reg) {
|
||||
continue;
|
||||
}
|
||||
|
||||
I2CDevice device = hardware->device;
|
||||
i2cDevice_t *pDev = &i2cDevice[device];
|
||||
|
||||
memset(pDev, 0, sizeof(*pDev));
|
||||
IO_t confSclIO = IOGetByTag(i2cConfig[device].ioTagScl);
|
||||
IO_t confSdaIO = IOGetByTag(i2cConfig[device].ioTagSda);
|
||||
int confSclPin = IO_GPIOPinIdx(confSclIO);
|
||||
int confSdaPin = IO_GPIOPinIdx(confSdaIO);
|
||||
|
||||
#ifdef RP2350B
|
||||
uint16_t numPins = 48;
|
||||
#else
|
||||
uint16_t numPins = 30;
|
||||
#endif
|
||||
|
||||
// I2C0 on pins 0,1 mod 4, I2C1 on pins 2,3 mod 4
|
||||
// SDA on pins 0 mod 2, SCL on pins 1 mod 2
|
||||
int pinOffset = device == I2CDEV_0 ? 0 : 2;
|
||||
if (confSdaPin >= 0 && confSclPin >= 0 &&
|
||||
confSdaPin < numPins && confSclPin < numPins &&
|
||||
(confSdaPin % 4) == pinOffset && (confSclPin % 4) == (pinOffset + 1)) {
|
||||
pDev->scl = confSclIO;
|
||||
pDev->sda = confSdaIO;
|
||||
pDev->hardware = hardware;
|
||||
pDev->reg = hardware->reg;
|
||||
pDev->pullUp = i2cConfig[device].pullUp;
|
||||
pDev->clockSpeed = i2cConfig[device].clockSpeed;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool i2cHandleHardwareFailure(I2CDevice device)
|
||||
{
|
||||
UNUSED(device);
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
|
||||
uint16_t i2cGetErrorCounter(void)
|
||||
{
|
||||
return i2cErrorCount;
|
||||
}
|
||||
|
||||
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||
{
|
||||
return i2cWriteBuffer(device, addr_, reg_, 1, &data);
|
||||
}
|
||||
|
||||
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
|
||||
{
|
||||
// TODO: Implement non-blocking write using DMA or similar mechanism
|
||||
if (device == I2CINVALID || device >= I2CDEV_COUNT) {
|
||||
return false;
|
||||
}
|
||||
|
||||
i2c_inst_t *port = I2C_INST(i2cHardware[device].reg);
|
||||
|
||||
if (!port) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (len_ > I2C_TX_BUFFER_LENGTH - 1) {
|
||||
return false; // Buffer too long
|
||||
}
|
||||
|
||||
uint8_t buf[I2C_TX_BUFFER_LENGTH] = { reg_, 0 };
|
||||
memcpy(&buf[1], data, len_);
|
||||
bool nostop = false;
|
||||
int status = i2c_write_timeout_us(port, addr_, buf, len_ + 1, nostop, I2C_TIMEOUT_US);
|
||||
|
||||
if (status < 0) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
if (device == I2CINVALID || device >= I2CDEV_COUNT) {
|
||||
return false;
|
||||
}
|
||||
|
||||
i2c_inst_t *port = I2C_INST(i2cHardware[device].reg);
|
||||
|
||||
if (!port) {
|
||||
return false;
|
||||
}
|
||||
|
||||
bool nostop = true;
|
||||
int status = i2c_write_timeout_us(port, addr_, ®_, 1, nostop, I2C_TIMEOUT_US);
|
||||
if (status < 0) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
}
|
||||
|
||||
nostop = false;
|
||||
status = i2c_read_timeout_us(port, addr_, buf, len, nostop, I2C_TIMEOUT_US);
|
||||
if (status < 0) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cReadBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
// TODO: Implement genuine non-blocking read using DMA or similar mechanism
|
||||
// ( I2C0_IRQ, I2C1_IRQ ...)
|
||||
return i2cRead(device, addr_, reg_, len, buf);
|
||||
}
|
||||
|
||||
bool i2cBusy(I2CDevice device, bool *error)
|
||||
{
|
||||
if (device == I2CINVALID || device >= I2CDEV_COUNT) {
|
||||
return false;
|
||||
}
|
||||
|
||||
i2c_inst_t *port = I2C_INST(i2cHardware[device].reg);
|
||||
|
||||
if (!port) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (error) {
|
||||
*error = 0;
|
||||
}
|
||||
|
||||
// TODO check: If we are using DMA (for a sequence of transfers?), then we will need to
|
||||
// protect against that being in progress
|
||||
|
||||
// Read the IC_STATUS register
|
||||
uint32_t status_reg = port->hw->status;
|
||||
|
||||
// The bit for (combined master/slave) ACTIVITY is (1 << 0).
|
||||
return (status_reg & (1 << 0)) != 0;
|
||||
}
|
||||
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
if (device == I2CINVALID) {
|
||||
return;
|
||||
}
|
||||
|
||||
i2cDevice_t *pDev = &i2cDevice[device];
|
||||
|
||||
const i2cHardware_t *hardware = pDev->hardware;
|
||||
|
||||
const IO_t scl = pDev->scl;
|
||||
const IO_t sda = pDev->sda;
|
||||
const uint8_t sclPin = IO_Pin(scl);
|
||||
const uint8_t sdaPin = IO_Pin(sda);
|
||||
|
||||
if (!hardware || !scl || !sda) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Set owners
|
||||
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
|
||||
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
|
||||
|
||||
// Initialise device
|
||||
i2c_init(I2C_INST(hardware->reg), 1000 * pDev->clockSpeed);
|
||||
|
||||
// Set up GPIO pins for I2C
|
||||
gpio_set_function(sdaPin, GPIO_FUNC_I2C);
|
||||
gpio_set_function(sclPin, GPIO_FUNC_I2C);
|
||||
|
||||
// Enable internal pull-up resistors
|
||||
gpio_pull_up(sdaPin);
|
||||
gpio_pull_up(sclPin);
|
||||
}
|
||||
|
||||
#endif // #if defined(USE_I2C) && !defined(SOFT_I2C)
|
508
src/platform/PICO/bus_spi_pico.c
Normal file
508
src/platform/PICO/bus_spi_pico.c
Normal file
|
@ -0,0 +1,508 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
* Clock divider code based on pico-sdk/src/rp2_common/hardware_spi.c
|
||||
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SPI
|
||||
//#define TESTING_NO_DMA 1
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/bus_spi_impl.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_def.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/nvic.h"
|
||||
|
||||
#include "hardware/spi.h"
|
||||
#include "hardware/gpio.h"
|
||||
#include "hardware/clocks.h"
|
||||
#include "hardware/dma.h"
|
||||
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
#define SPI_SPEED_20MHZ 20000000
|
||||
#define SPI_DATAWIDTH 8
|
||||
#define SPI_DMA_THRESHOLD 8
|
||||
|
||||
const spiHardware_t spiHardware[] = {
|
||||
{
|
||||
.device = SPIDEV_0,
|
||||
.reg = SPI0,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA2) },
|
||||
{ DEFIO_TAG_E(PA6) },
|
||||
{ DEFIO_TAG_E(PA18) },
|
||||
{ DEFIO_TAG_E(PA22) },
|
||||
#ifdef RP2350B
|
||||
{ DEFIO_TAG_E(PA34) },
|
||||
{ DEFIO_TAG_E(PA38) },
|
||||
#endif
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PA0) },
|
||||
{ DEFIO_TAG_E(PA4) },
|
||||
{ DEFIO_TAG_E(PA16) },
|
||||
{ DEFIO_TAG_E(PA20) },
|
||||
#ifdef RP2350B
|
||||
{ DEFIO_TAG_E(PA32) },
|
||||
{ DEFIO_TAG_E(PA36) },
|
||||
#endif
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PA3) },
|
||||
{ DEFIO_TAG_E(PA7) },
|
||||
{ DEFIO_TAG_E(PA19) },
|
||||
{ DEFIO_TAG_E(PA23) },
|
||||
#ifdef RP2350B
|
||||
{ DEFIO_TAG_E(PA35) },
|
||||
{ DEFIO_TAG_E(PA39) },
|
||||
#endif
|
||||
},
|
||||
},
|
||||
{
|
||||
.device = SPIDEV_1,
|
||||
.reg = SPI1,
|
||||
.sckPins = {
|
||||
{ DEFIO_TAG_E(PA10) },
|
||||
{ DEFIO_TAG_E(PA14) },
|
||||
{ DEFIO_TAG_E(PA26) },
|
||||
#ifdef RP2350B
|
||||
{ DEFIO_TAG_E(PA30) },
|
||||
{ DEFIO_TAG_E(PA42) },
|
||||
{ DEFIO_TAG_E(PA46) },
|
||||
#endif
|
||||
},
|
||||
.misoPins = {
|
||||
{ DEFIO_TAG_E(PA8) },
|
||||
{ DEFIO_TAG_E(PA12) },
|
||||
{ DEFIO_TAG_E(PA24) },
|
||||
{ DEFIO_TAG_E(PA28) },
|
||||
#ifdef RP2350B
|
||||
{ DEFIO_TAG_E(PA40) },
|
||||
{ DEFIO_TAG_E(PA44) },
|
||||
#endif
|
||||
},
|
||||
.mosiPins = {
|
||||
{ DEFIO_TAG_E(PA11) },
|
||||
{ DEFIO_TAG_E(PA15) },
|
||||
{ DEFIO_TAG_E(PA27) },
|
||||
#ifdef RP2350B
|
||||
{ DEFIO_TAG_E(PA31) },
|
||||
{ DEFIO_TAG_E(PA43) },
|
||||
{ DEFIO_TAG_E(PA47) },
|
||||
#endif
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
extern busDevice_t spiBusDevice[SPIDEV_COUNT];
|
||||
|
||||
void spiPinConfigure(const struct spiPinConfig_s *pConfig)
|
||||
{
|
||||
for (size_t hwindex = 0 ; hwindex < ARRAYLEN(spiHardware) ; hwindex++) {
|
||||
const spiHardware_t *hw = &spiHardware[hwindex];
|
||||
|
||||
if (!hw->reg) {
|
||||
continue;
|
||||
}
|
||||
|
||||
SPIDevice device = hw->device;
|
||||
spiDevice_t *pDev = &spiDevice[device];
|
||||
|
||||
for (int pindex = 0 ; pindex < MAX_SPI_PIN_SEL ; pindex++) {
|
||||
if (pConfig[device].ioTagSck == hw->sckPins[pindex].pin) {
|
||||
pDev->sck = hw->sckPins[pindex].pin;
|
||||
}
|
||||
if (pConfig[device].ioTagMiso == hw->misoPins[pindex].pin) {
|
||||
pDev->miso = hw->misoPins[pindex].pin;
|
||||
}
|
||||
if (pConfig[device].ioTagMosi == hw->mosiPins[pindex].pin) {
|
||||
pDev->mosi = hw->mosiPins[pindex].pin;
|
||||
}
|
||||
}
|
||||
|
||||
if (pDev->sck && pDev->miso && pDev->mosi) {
|
||||
pDev->dev = hw->reg;
|
||||
pDev->leadingEdge = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
static spi_inst_t *getSpiInstanceByDevice(SPI_TypeDef *spi)
|
||||
{
|
||||
if (spi == SPI0) {
|
||||
return spi0;
|
||||
} else if (spi == SPI1) {
|
||||
return spi1;
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
*/
|
||||
|
||||
static void spiSetClockFromSpeed(spi_inst_t *spi, uint16_t speed)
|
||||
{
|
||||
uint32_t freq = spiCalculateClock(speed);
|
||||
spi_set_baudrate(spi, freq);
|
||||
}
|
||||
|
||||
/*
|
||||
|
||||
enum spi_cpha_t { SPI_CPHA_0 = 0, SPI_CPHA_1 = 1 }
|
||||
Enumeration of SPI CPHA (clock phase) values.
|
||||
|
||||
enum spi_cpol_t { SPI_CPOL_0 = 0, SPI_CPOL_1 = 1 }
|
||||
Enumeration of SPI CPOL (clock polarity) values.
|
||||
|
||||
enum spi_order_t { SPI_LSB_FIRST = 0, SPI_MSB_FIRST = 1 }
|
||||
Enumeration of SPI bit-order values.
|
||||
|
||||
|
||||
static void spi_set_format (spi_inst_t * spi, uint data_bits, spi_cpol_t cpol, spi_cpha_t cpha, __unused spi_order_t order) [inline], [static]
|
||||
|
||||
Configure SPI.
|
||||
|
||||
Configure how the SPI serialises and deserialises data on the wire
|
||||
|
||||
Parameters
|
||||
|
||||
spi
|
||||
SPI instance specifier, either spi0 or spi1
|
||||
|
||||
data_bits
|
||||
Number of data bits per transfer. Valid values 4..16.
|
||||
|
||||
cpol
|
||||
SSPCLKOUT polarity, applicable to Motorola SPI frame format only.
|
||||
|
||||
cpha
|
||||
SSPCLKOUT phase, applicable to Motorola SPI frame format only
|
||||
|
||||
order
|
||||
Must be SPI_MSB_FIRST, no other values supported on the PL022
|
||||
|
||||
|
||||
*/
|
||||
|
||||
|
||||
void spiInitDevice(SPIDevice device)
|
||||
{
|
||||
// maybe here set getSpiInstanceByDevice(spi->dev) SPI device with
|
||||
// settings like
|
||||
// STM does
|
||||
//SetRXFIFOThreshold ...QF (1/4 full presumably)
|
||||
// Init -> full duplex, master, 8biut, baudrate, MSBfirst, no CRC,
|
||||
// Clock = PolarityHigh, Phase_2Edge
|
||||
|
||||
|
||||
const spiDevice_t *spi = &spiDevice[device];
|
||||
|
||||
if (!spi->dev) {
|
||||
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);
|
||||
gpio_set_function(IO_PINBYTAG(spi->mosi), GPIO_FUNC_SPI);
|
||||
gpio_set_function(IO_PINBYTAG(spi->sck), GPIO_FUNC_SPI);
|
||||
}
|
||||
|
||||
void spiInternalStopDMA (const extDevice_t *dev)
|
||||
{
|
||||
dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx;
|
||||
dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx;
|
||||
|
||||
if (dmaRx && dma_channel_is_busy(dmaRx->channel)) {
|
||||
// Abort active DMA - this should never happen
|
||||
dma_channel_abort(dmaRx->channel);
|
||||
}
|
||||
|
||||
if (dmaTx && dma_channel_is_busy(dmaTx->channel)) {
|
||||
// Abort active DMA - this should never happen as Tx should complete before Rx
|
||||
dma_channel_abort(dmaTx->channel);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Interrupt handler for SPI receive DMA completion
|
||||
FAST_IRQ_HANDLER static void spiRxIrqHandler(dmaChannelDescriptor_t* descriptor)
|
||||
{
|
||||
const extDevice_t *dev = (const extDevice_t *)descriptor->userParam;
|
||||
|
||||
if (!dev) {
|
||||
return;
|
||||
}
|
||||
|
||||
busDevice_t *bus = dev->bus;
|
||||
|
||||
if (bus->curSegment->negateCS) {
|
||||
// Negate Chip Select
|
||||
IOHi(dev->busType_u.spi.csnPin);
|
||||
}
|
||||
|
||||
spiInternalStopDMA(dev);
|
||||
|
||||
spiIrqHandler(dev);
|
||||
}
|
||||
|
||||
extern dmaChannelDescriptor_t dmaDescriptors[];
|
||||
|
||||
void spiInitBusDMA(void)
|
||||
{
|
||||
for (uint32_t device = 0; device < SPIDEV_COUNT; device++) {
|
||||
busDevice_t *bus = &spiBusDevice[device];
|
||||
int32_t channel_tx;
|
||||
int32_t channel_rx;
|
||||
|
||||
if (bus->busType != BUS_TYPE_SPI) {
|
||||
// This bus is not in use
|
||||
continue;
|
||||
}
|
||||
|
||||
channel_tx = dma_claim_unused_channel(true);
|
||||
if (channel_tx == -1) {
|
||||
// no more available channels so give up
|
||||
return;
|
||||
}
|
||||
channel_rx = dma_claim_unused_channel(true);
|
||||
if (channel_rx == -1) {
|
||||
// no more available channels so give up, first releasing the one
|
||||
// channel we did claim
|
||||
dma_channel_unclaim(channel_tx);
|
||||
return;
|
||||
}
|
||||
|
||||
if (!dmaAllocate(DMA_CHANNEL_TO_IDENTIFIER(channel_tx), OWNER_SPI_SDO, device + 1) ||
|
||||
!dmaAllocate(DMA_CHANNEL_TO_IDENTIFIER(channel_rx), OWNER_SPI_SDI, device + 1)) {
|
||||
// This should never happen if all allocated channels are claimed
|
||||
dma_channel_unclaim(channel_tx);
|
||||
dma_channel_unclaim(channel_rx);
|
||||
return;
|
||||
}
|
||||
|
||||
bus->dmaTx = &dmaDescriptors[DMA_CHANNEL_TO_INDEX(channel_tx)];
|
||||
bus->dmaTx->channel = channel_tx;
|
||||
|
||||
bus->dmaRx = &dmaDescriptors[DMA_CHANNEL_TO_INDEX(channel_rx)];
|
||||
bus->dmaRx->channel = channel_rx;
|
||||
|
||||
// The transaction concludes when the data has been received which will be after transmission is complete
|
||||
dmaSetHandler(DMA_CHANNEL_TO_IDENTIFIER(bus->dmaRx->channel), spiRxIrqHandler, NVIC_PRIO_SPI_DMA, 0);
|
||||
|
||||
// We got the required resources, so we can use DMA on this bus
|
||||
bus->useDMA = true;
|
||||
}
|
||||
}
|
||||
|
||||
void spiInternalResetStream(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
//TODO: implement
|
||||
UNUSED(descriptor);
|
||||
}
|
||||
|
||||
bool spiInternalReadWriteBufPolled(SPI_TypeDef *instance, const uint8_t *txData, uint8_t *rxData, int len)
|
||||
{
|
||||
// TODO optimise with 16-bit transfers as per stm bus_spi_ll code
|
||||
int bytesProcessed = spi_write_read_blocking(SPI_INST(instance), txData, rxData, len);
|
||||
return bytesProcessed == len;
|
||||
}
|
||||
|
||||
// Initialise DMA before first segment transfer
|
||||
void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
||||
{
|
||||
#ifndef USE_DMA
|
||||
UNUSED(dev);
|
||||
UNUSED(preInit);
|
||||
#else
|
||||
UNUSED(preInit);
|
||||
|
||||
busDevice_t *bus = dev->bus;
|
||||
|
||||
volatile busSegment_t *segment = bus->curSegment;
|
||||
|
||||
const spiDevice_t *spi = &spiDevice[spiDeviceByInstance(dev->bus->busType_u.spi.instance)];
|
||||
dma_channel_config config = dma_channel_get_default_config(dev->bus->dmaTx->channel);
|
||||
channel_config_set_transfer_data_size(&config, DMA_SIZE_8);
|
||||
channel_config_set_read_increment(&config, true);
|
||||
channel_config_set_write_increment(&config, false);
|
||||
channel_config_set_dreq(&config, spi_get_dreq(SPI_INST(spi->dev), true));
|
||||
|
||||
dma_channel_configure(dev->bus->dmaTx->channel, &config, &spi_get_hw(SPI_INST(spi->dev))->dr, segment->u.buffers.txData, 0, false);
|
||||
|
||||
config = dma_channel_get_default_config(dev->bus->dmaRx->channel);
|
||||
channel_config_set_transfer_data_size(&config, DMA_SIZE_8);
|
||||
channel_config_set_read_increment(&config, false);
|
||||
channel_config_set_write_increment(&config, true);
|
||||
channel_config_set_dreq(&config, spi_get_dreq(SPI_INST(spi->dev), false));
|
||||
|
||||
dma_channel_configure(dev->bus->dmaRx->channel, &config, segment->u.buffers.rxData, &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
|
||||
dev->bus->dmaRx->userParam = (uint32_t)dev;
|
||||
|
||||
// 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_start_channel_mask((1 << dev->bus->dmaTx->channel) | (1 << dev->bus->dmaRx->channel));
|
||||
#endif
|
||||
}
|
||||
|
||||
// DMA transfer setup and start
|
||||
void spiSequenceStart(const extDevice_t *dev)
|
||||
{
|
||||
//TODO: implementation for PICO
|
||||
// base on STM32/bus_spi_ll.c
|
||||
|
||||
busDevice_t *bus = dev->bus;
|
||||
SPI_TypeDef *instance = bus->busType_u.spi.instance;
|
||||
spiDevice_t *spi = &spiDevice[spiDeviceByInstance(instance)];
|
||||
bool dmaSafe = dev->useDMA;
|
||||
#if TESTING_NO_DMA
|
||||
dmaSafe = false;
|
||||
#endif
|
||||
uint32_t xferLen = 0;
|
||||
uint32_t segmentCount = 0;
|
||||
|
||||
//
|
||||
bus->initSegment = true;
|
||||
|
||||
|
||||
// Switch bus speed
|
||||
if (dev->busType_u.spi.speed != bus->busType_u.spi.speed) {
|
||||
spiSetClockFromSpeed(SPI_INST(instance), dev->busType_u.spi.speed);
|
||||
bus->busType_u.spi.speed = dev->busType_u.spi.speed;
|
||||
}
|
||||
|
||||
// Switch SPI clock polarity/phase if necessary
|
||||
if (dev->busType_u.spi.leadingEdge != bus->busType_u.spi.leadingEdge) {
|
||||
uint8_t sckPin = IO_PINBYTAG(spi->sck);
|
||||
gpio_set_slew_rate(sckPin, GPIO_SLEW_RATE_FAST);
|
||||
// Betaflight busDevice / SPI supports modes 0 (leadingEdge True), 3 (leadingEdge False)
|
||||
// 0: (CPOL 0, CPHA 0)
|
||||
// 3: (CPOL 1, CPHA 1)
|
||||
if (dev->busType_u.spi.leadingEdge) {
|
||||
spi_set_format(SPI_INST(instance), SPI_DATAWIDTH, SPI_CPOL_0, SPI_CPHA_0, SPI_MSB_FIRST);
|
||||
}
|
||||
else {
|
||||
spi_set_format(SPI_INST(instance), SPI_DATAWIDTH, SPI_CPOL_1, SPI_CPHA_1, SPI_MSB_FIRST);
|
||||
}
|
||||
|
||||
bus->busType_u.spi.leadingEdge = dev->busType_u.spi.leadingEdge;
|
||||
}
|
||||
|
||||
// NB for RP2350 targets, heap and stack will be in SRAM (single-cycle),
|
||||
// so there are no cache issues with DMA.
|
||||
for (busSegment_t *checkSegment = (busSegment_t *)bus->curSegment; checkSegment->len; checkSegment++) {
|
||||
segmentCount++;
|
||||
xferLen += checkSegment->len;
|
||||
}
|
||||
|
||||
// Use DMA if possible
|
||||
// If there are more than one segments, or a single segment with negateCS negated in the list terminator then force DMA irrespective of length
|
||||
if (bus->useDMA && dmaSafe && ((segmentCount > 1) ||
|
||||
(xferLen >= SPI_DMA_THRESHOLD) ||
|
||||
!bus->curSegment[segmentCount].negateCS)) {
|
||||
spiProcessSegmentsDMA(dev);
|
||||
} else {
|
||||
spiProcessSegmentsPolled(dev);
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t spiCalculateDivider(uint32_t freq)
|
||||
{
|
||||
/*
|
||||
SPI clock is set in Betaflight code by calling spiSetClkDivisor, which records a uint16_t value into a .speed field.
|
||||
In order to maintain this code (for simplicity), record the prescale and postdiv numbers as calculated in
|
||||
pico-sdk/src/rp2_common/hardware_spi.c: spi_set_baudrate()
|
||||
|
||||
prescale and postdiv are in range 1..255 and are packed into the return value.
|
||||
*/
|
||||
|
||||
uint32_t spiClock = clock_get_hz(clk_peri);
|
||||
uint32_t prescale, postdiv;
|
||||
// Find smallest prescale value which puts output frequency in range of
|
||||
// post-divide. Prescale is an even number from 2 to 254 inclusive.
|
||||
for (prescale = 2; prescale <= 254; prescale += 2) {
|
||||
if (spiClock < prescale * 256 * (uint64_t) freq)
|
||||
break;
|
||||
}
|
||||
if (prescale > 254) {
|
||||
prescale = 254;
|
||||
}
|
||||
|
||||
// Find largest post-divide which makes output <= freq. Post-divide is
|
||||
// an integer in the range 1 to 256 inclusive.
|
||||
for (postdiv = 256; postdiv > 1; --postdiv) {
|
||||
if (spiClock / (prescale * (postdiv - 1)) > freq)
|
||||
break;
|
||||
}
|
||||
|
||||
// Store prescale, (postdiv - 1), both in range 0 to 255.
|
||||
return (uint16_t)((prescale << 8) + (postdiv - 1));
|
||||
}
|
||||
|
||||
uint32_t spiCalculateClock(uint16_t speed)
|
||||
{
|
||||
/*
|
||||
speed contains packed values of prescale and postdiv.
|
||||
Retrieve a frequency which will recreate the same prescale and postdiv on a call to spi_set_baudrate().
|
||||
*/
|
||||
uint32_t spiClock = clock_get_hz(clk_peri);
|
||||
uint32_t prescale = speed >> 8;
|
||||
uint32_t postdivMinusOne = speed & 0xFF;
|
||||
|
||||
// Set freq to reverse the calculation, so that we would end up with the same prescale and postdiv,
|
||||
// hence the same frequency as if we had requested directly from spiCalculateDivider().
|
||||
uint32_t freq = 1 + (spiClock/prescale)/(postdivMinusOne + 1);
|
||||
|
||||
return freq;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
71
src/platform/PICO/config_flash.c
Normal file
71
src/platform/PICO/config_flash.c
Normal file
|
@ -0,0 +1,71 @@
|
|||
/*
|
||||
* 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 <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/system.h"
|
||||
#include "config/config_streamer.h"
|
||||
|
||||
#include "hardware/flash.h"
|
||||
#include "hardware/sync.h"
|
||||
|
||||
#if defined(CONFIG_IN_FLASH)
|
||||
|
||||
void configUnlock(void)
|
||||
{
|
||||
// NOOP
|
||||
}
|
||||
|
||||
void configLock(void)
|
||||
{
|
||||
// NOOP
|
||||
}
|
||||
|
||||
void configClearFlags(void)
|
||||
{
|
||||
// NOOP
|
||||
}
|
||||
|
||||
configStreamerResult_e configWriteWord(uintptr_t address, config_streamer_buffer_type_t *buffer)
|
||||
{
|
||||
// TODO: synchronise second core... see e.g. pico-examples flash_program, uses flash_safe_execute.
|
||||
|
||||
// pico-sdk flash_range functions use the offset from start of FLASH
|
||||
uint32_t flash_offs = address - XIP_BASE;
|
||||
|
||||
uint32_t interrupts = save_and_disable_interrupts();
|
||||
|
||||
if ((flash_offs % FLASH_SECTOR_SIZE) == 0) {
|
||||
// Erase the flash sector before writing
|
||||
flash_range_erase(flash_offs, FLASH_SECTOR_SIZE);
|
||||
}
|
||||
|
||||
STATIC_ASSERT(CONFIG_STREAMER_BUFFER_SIZE == sizeof(config_streamer_buffer_type_t) * CONFIG_STREAMER_BUFFER_SIZE, "CONFIG_STREAMER_BUFFER_SIZE does not match written size");
|
||||
|
||||
// Write data to flash
|
||||
flash_range_program(flash_offs, buffer, CONFIG_STREAMER_BUFFER_SIZE);
|
||||
|
||||
restore_interrupts(interrupts);
|
||||
return CONFIG_RESULT_SUCCESS;
|
||||
}
|
||||
|
||||
#endif // CONFIG_IN_FLASH
|
25
src/platform/PICO/debug_pico.c
Normal file
25
src/platform/PICO/debug_pico.c
Normal file
|
@ -0,0 +1,25 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
void debugInit(void)
|
||||
{
|
||||
// NOOP
|
||||
}
|
153
src/platform/PICO/dma_pico.c
Normal file
153
src/platform/PICO/dma_pico.c
Normal file
|
@ -0,0 +1,153 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_DMA
|
||||
|
||||
#include "drivers/dma.h"
|
||||
|
||||
#include "platform/dma.h"
|
||||
#include "pico/multicore.h"
|
||||
#include "hardware/dma.h"
|
||||
#include "hardware/irq.h"
|
||||
|
||||
dmaChannelDescriptor_t dmaDescriptors[DMA_LAST_HANDLER] = {
|
||||
DEFINE_DMA_CHANNEL(DMA_CH0_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH1_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH2_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH3_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH4_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH5_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH6_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH7_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH8_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH9_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH10_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH11_HANDLER),
|
||||
#ifdef RP2350
|
||||
DEFINE_DMA_CHANNEL(DMA_CH12_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH13_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH14_HANDLER),
|
||||
DEFINE_DMA_CHANNEL(DMA_CH15_HANDLER),
|
||||
#endif
|
||||
};
|
||||
|
||||
void dma_irq_handler(bool isIrq1)
|
||||
{
|
||||
uint32_t status = isIrq1 ? dma_hw->ints1 : dma_hw->ints0; // Read the status register once
|
||||
|
||||
// Iterate through all possible DMA channels that have triggered an interrupt
|
||||
// channel equates to index in the dmaDescriptors array
|
||||
for (uint8_t channel = 0; channel < DMA_LAST_HANDLER; channel++) {
|
||||
if (status & (1u << channel)) {
|
||||
uint8_t index = DMA_CHANNEL_TO_INDEX(channel);
|
||||
// Call the handler if it is set
|
||||
if (dmaDescriptors[index].irqHandlerCallback) {
|
||||
dmaDescriptors[index].irqHandlerCallback(&dmaDescriptors[index]);
|
||||
}
|
||||
|
||||
// Acknowledge the interrupt for this channel
|
||||
if (isIrq1) {
|
||||
dma_channel_acknowledge_irq1(channel);
|
||||
} else {
|
||||
dma_channel_acknowledge_irq0(channel);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
void dma_irq0_handler(void)
|
||||
{
|
||||
dma_irq_handler(false);
|
||||
}
|
||||
|
||||
void dma_irq1_handler(void)
|
||||
{
|
||||
dma_irq_handler(true);
|
||||
}
|
||||
|
||||
dmaIdentifier_e dmaGetFreeIdentifier(void)
|
||||
{
|
||||
const int channel = dma_claim_unused_channel(false);
|
||||
// NOTE: dma_claim_unused_channel returns -1 if no channel is available
|
||||
if (channel == -1) {
|
||||
return DMA_NONE; // No free channel available
|
||||
}
|
||||
return DMA_CHANNEL_TO_IDENTIFIER(channel);
|
||||
}
|
||||
|
||||
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||
{
|
||||
if (identifier < DMA_FIRST_HANDLER || identifier > DMA_LAST_HANDLER) {
|
||||
return; // Invalid identifier
|
||||
}
|
||||
|
||||
UNUSED(priority);
|
||||
/*
|
||||
Assign the interrupt handler for the DMA channel based on the core
|
||||
this is to minimise contention on the DMA IRQs.
|
||||
|
||||
Each core has its own DMA IRQ:
|
||||
- CORE 0 uses DMA_IRQ_0
|
||||
- CORE 1 uses DMA_IRQ_1
|
||||
|
||||
If we specify a core to be used for interrupts we will use the corresponding DMA IRQ.
|
||||
*/
|
||||
#if defined(USE_MULTICORE) && defined(DMA_IRQ_CORE_NUM)
|
||||
const uint8_t core = DMA_IRQ_CORE_NUM;
|
||||
#elif defined(USE_MULTICORE)
|
||||
// Get the current core number
|
||||
const uint8_t core = get_core_num();
|
||||
#else
|
||||
const uint8_t core = 0;
|
||||
#endif
|
||||
|
||||
const int index = DMA_IDENTIFIER_TO_INDEX(identifier);
|
||||
const uint32_t channel = dmaDescriptors[index].channel;
|
||||
static bool dma_irqN_handler_registered[2];
|
||||
|
||||
if (!dma_irqN_handler_registered[core]) {
|
||||
// Register the DMA IRQ handler if needed
|
||||
dmaDescriptors[index].irqN = core ? DMA_IRQ_1_IRQn : DMA_IRQ_0_IRQn;
|
||||
irq_handler_t irq_handler = core ? dma_irq1_handler : dma_irq0_handler;
|
||||
|
||||
|
||||
irq_set_exclusive_handler(dmaDescriptors[index].irqN, irq_handler);
|
||||
irq_set_enabled(dmaDescriptors[index].irqN, true);
|
||||
|
||||
dma_irqN_handler_registered[core] = true;
|
||||
}
|
||||
|
||||
if (core) {
|
||||
dma_channel_set_irq1_enabled(channel, true);
|
||||
} else {
|
||||
dma_channel_set_irq0_enabled(channel, true);
|
||||
}
|
||||
|
||||
dmaDescriptors[index].irqHandlerCallback = callback;
|
||||
dmaDescriptors[index].userParam = userParam;
|
||||
}
|
||||
|
||||
#endif
|
108
src/platform/PICO/dma_reqmap_mcu.c
Normal file
108
src/platform/PICO/dma_reqmap_mcu.c
Normal file
|
@ -0,0 +1,108 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
|
||||
#include "timer_def.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
#include "pg/timerio.h"
|
||||
|
||||
#define DMA(c) { (c), (dmaResource_t *) dma_hw->ch[c] , 0 }
|
||||
|
||||
static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = {
|
||||
DMA(1),
|
||||
DMA(2),
|
||||
DMA(3),
|
||||
DMA(4),
|
||||
DMA(5),
|
||||
DMA(6),
|
||||
DMA(7),
|
||||
DMA(8),
|
||||
DMA(9),
|
||||
DMA(10),
|
||||
DMA(11),
|
||||
DMA(12),
|
||||
#ifdef RP2350
|
||||
DMA(13),
|
||||
DMA(14),
|
||||
DMA(15),
|
||||
DMA(16),
|
||||
#endif
|
||||
};
|
||||
|
||||
#undef DMA
|
||||
|
||||
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
|
||||
{
|
||||
UNUSED(device);
|
||||
UNUSED(index);
|
||||
UNUSED(opt);
|
||||
//TODO : Implementation for PICO
|
||||
return NULL;
|
||||
}
|
||||
|
||||
dmaoptValue_t dmaoptByTag(ioTag_t ioTag)
|
||||
{
|
||||
UNUSED(ioTag);
|
||||
//TODO : Implementation for PICO
|
||||
return DMA_OPT_UNUSED;
|
||||
}
|
||||
|
||||
const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t channel, dmaoptValue_t dmaopt)
|
||||
{
|
||||
//TODO : Implementation for PICO
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const dmaChannelSpec_t *dmaGetChannelSpecByTimer(const timerHardware_t *timer)
|
||||
{
|
||||
if (!timer) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
//TODO : Implementation for PICO
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// dmaGetOptionByTimer is called by pgResetFn_timerIOConfig to find out dmaopt for pre-configured timer.
|
||||
dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
|
||||
{
|
||||
//TODO : Implementation for PICO
|
||||
return DMA_OPT_UNUSED;
|
||||
}
|
||||
|
||||
// A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef
|
||||
dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer)
|
||||
{
|
||||
//TODO : Implementation for PICO
|
||||
return DMA_OPT_UNUSED;
|
||||
}
|
||||
|
||||
#endif // USE_DMA_SPEC
|
27
src/platform/PICO/dma_reqmap_mcu.h
Normal file
27
src/platform/PICO/dma_reqmap_mcu.h
Normal file
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define MAX_PERIPHERAL_DMA_OPTIONS 14
|
||||
#define MAX_TIMER_DMA_OPTIONS 22
|
||||
|
||||
#define USE_DMA_MUX
|
87
src/platform/PICO/dshot.pio
Normal file
87
src/platform/PICO/dshot.pio
Normal 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;
|
||||
}
|
||||
*/
|
||||
|
54
src/platform/PICO/dshot.pio.programs
Normal file
54
src/platform/PICO/dshot.pio.programs
Normal 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
|
||||
|
660
src/platform/PICO/dshot_pico.c
Normal file
660
src/platform/PICO/dshot_pico.c
Normal file
|
@ -0,0 +1,660 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "build/debug_pin.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/dshot.h"
|
||||
#include "drivers/dshot_command.h"
|
||||
#include "drivers/dshot_command.h"
|
||||
#include "drivers/motor_types.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "pg/motor.h"
|
||||
|
||||
#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
|
||||
|
||||
// TODO use with TELEMETRY for cli report (or not)
|
||||
FAST_DATA_ZERO_INIT dshotTelemetryCycleCounters_t dshotDMAHandlerCycleCounters;
|
||||
#endif
|
||||
|
||||
typedef struct motorOutput_s {
|
||||
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
|
||||
bool configured;
|
||||
bool enabled;
|
||||
PIO pio;
|
||||
uint16_t pio_sm;
|
||||
} motorOutput_t;
|
||||
|
||||
typedef struct picoDshotTelemetryBuffer_s {
|
||||
union {
|
||||
uint32_t u32[2];
|
||||
uint16_t u16[4];
|
||||
};
|
||||
} picoDshotTelemetryBuffer_t;
|
||||
|
||||
static motorProtocolTypes_e motorProtocol;
|
||||
//uint8_t dshotMotorCount = 0;
|
||||
static motorOutput_t dshotMotors[MAX_SUPPORTED_MOTORS];
|
||||
bool useDshotTelemetry = false;
|
||||
|
||||
static float getPeriodTiming(void)
|
||||
{
|
||||
switch(motorProtocol) {
|
||||
case MOTOR_PROTOCOL_DSHOT600:
|
||||
return 1.67f;
|
||||
case MOTOR_PROTOCOL_DSHOT300:
|
||||
return 3.33f;
|
||||
default:
|
||||
case MOTOR_PROTOCOL_DSHOT150:
|
||||
return 6.66f;
|
||||
}
|
||||
}
|
||||
|
||||
#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_program_bidir_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_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); // 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;
|
||||
const timeUs_t startTimeUs = micros();
|
||||
|
||||
do {
|
||||
telemetryPending = false;
|
||||
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; // TODO Current program outputs two words. Should this be <2 ?
|
||||
}
|
||||
|
||||
telemetryWait |= telemetryPending;
|
||||
|
||||
if (cmpTimeUs(micros(), startTimeUs) > DSHOT_TELEMETRY_TIMEOUT) {
|
||||
break;
|
||||
}
|
||||
} while (telemetryPending); // TODO logic here? supposed to block until all telemetry available?
|
||||
|
||||
if (telemetryWait) {
|
||||
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 2, debug[2] + 1);
|
||||
}
|
||||
|
||||
#endif
|
||||
return telemetryWait; // TODO what should the return value be? (don't think it's used)
|
||||
}
|
||||
|
||||
static void dshotUpdateInit(void)
|
||||
{
|
||||
// NO OP as no buffer needed for PIO
|
||||
}
|
||||
|
||||
static bool dshotDecodeTelemetry(void)
|
||||
{
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (!useDshotTelemetry) {
|
||||
return true;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
#endif
|
||||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||
const motorOutput_t *motor = &dshotMotors[motorIndex];
|
||||
|
||||
if (dshotTelemetryState.rawValueState == DSHOT_RAW_VALUE_STATE_NOT_PROCESSED) {
|
||||
int fifo_words = pio_sm_get_rx_fifo_level(motor->pio, motor->pio_sm);
|
||||
if (fifo_words < 2) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const uint32_t rawOne = pio_sm_get_blocking(motor->pio, motor->pio_sm);
|
||||
const uint32_t rawTwo = pio_sm_get_blocking(motor->pio, motor->pio_sm);
|
||||
|
||||
uint32_t rawValue = decodeTelemetry(rawOne, rawTwo);
|
||||
|
||||
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 0, debug[0] + 1);
|
||||
dshotTelemetryState.readCount++;
|
||||
|
||||
if (rawValue != DSHOT_TELEMETRY_INVALID) {
|
||||
// Check EDT enable or store raw value
|
||||
if ((rawValue == 0x0E00) && (dshotCommandGetCurrent(motorIndex) == DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE)) {
|
||||
dshotTelemetryState.motorState[motorIndex].telemetryTypes = 1 << DSHOT_TELEMETRY_TYPE_STATE_EVENTS;
|
||||
} else {
|
||||
dshotTelemetryState.motorState[motorIndex].rawValue = rawValue;
|
||||
}
|
||||
} else {
|
||||
dshotTelemetryState.invalidPacketCount++;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
updateDshotTelemetryQuality(&dshotTelemetryQuality[motorIndex], rawValue != DSHOT_TELEMETRY_INVALID, currentTimeMs);
|
||||
#endif
|
||||
}
|
||||
|
||||
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED;
|
||||
}
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static void dshotWriteInt(uint8_t motorIndex, uint16_t value)
|
||||
{
|
||||
motorOutput_t *const motor = &dshotMotors[motorIndex];
|
||||
|
||||
if (!motor->configured) {
|
||||
return;
|
||||
}
|
||||
|
||||
/*If there is a command ready to go overwrite the value and send that instead*/
|
||||
if (dshotCommandIsProcessing()) {
|
||||
value = dshotCommandGetCurrent(motorIndex);
|
||||
if (value) {
|
||||
// Request telemetry on other return wire (this isn't DSHOT bidir)
|
||||
motor->protocolControl.requestTelemetry = true;
|
||||
}
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
dshotWriteInt(motorIndex, lrintf(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)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool dshotEnableMotors(void)
|
||||
{
|
||||
for (int i = 0; i < dshotMotorCount; i++) {
|
||||
const motorOutput_t *motor = &dshotMotors[i];
|
||||
if (motor->configured) {
|
||||
// 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;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
static bool dshotIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return dshotMotors[index].enabled;
|
||||
}
|
||||
|
||||
static void dshotPostInit(void)
|
||||
{
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||
dshotMotors[motorIndex].enabled = true;
|
||||
}
|
||||
}
|
||||
|
||||
static bool dshotIsMotorIdle(unsigned motorIndex)
|
||||
{
|
||||
if (motorIndex >= ARRAYLEN(dshotMotors)) {
|
||||
return false;
|
||||
}
|
||||
return dshotMotors[motorIndex].protocolControl.value == 0;
|
||||
}
|
||||
|
||||
static void dshotRequestTelemetry(unsigned index)
|
||||
{
|
||||
#ifndef USE_DSHOT_TELEMETRY
|
||||
UNUSED(index);
|
||||
#else
|
||||
if (index < dshotMotorCount) {
|
||||
dshotMotors[index].protocolControl.requestTelemetry = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
static motorVTable_t dshotVTable = {
|
||||
.postInit = dshotPostInit,
|
||||
.enable = dshotEnableMotors,
|
||||
.disable = dshotDisableMotors,
|
||||
.isMotorEnabled = dshotIsMotorEnabled,
|
||||
.telemetryWait = dshotTelemetryWait,
|
||||
.decodeTelemetry = dshotDecodeTelemetry,
|
||||
.updateInit = dshotUpdateInit,
|
||||
.write = dshotWrite,
|
||||
.writeInt = dshotWriteInt,
|
||||
.updateComplete = dshotUpdateComplete,
|
||||
.convertExternalToMotor = dshotConvertFromExternal,
|
||||
.convertMotorToExternal = dshotConvertToExternal,
|
||||
.shutdown = dshotShutdown,
|
||||
.isMotorIdle = dshotIsMotorIdle,
|
||||
.requestTelemetry = dshotRequestTelemetry,
|
||||
};
|
||||
|
||||
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;
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
||||
#endif
|
||||
|
||||
// TODO somehow configure which PIO block to use for dshot? pio0 for now.
|
||||
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 (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;
|
||||
|
||||
IOInit(io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
// 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
|
||||
|
||||
// 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;
|
||||
}
|
||||
|
||||
// TODO do we just undef USE_DSHOT_BITBANG ?
|
||||
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
|
||||
{
|
||||
/* DSHOT BIT BANG not required for PICO */
|
||||
UNUSED(motorDevConfig);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||
{
|
||||
// TODO: not required
|
||||
UNUSED(device);
|
||||
UNUSED(motorConfig);
|
||||
return false;
|
||||
}
|
||||
|
||||
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||
{
|
||||
// TODO: not required
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif // USE_DSHOT
|
101
src/platform/PICO/exti_pico.c
Normal file
101
src/platform/PICO/exti_pico.c
Normal file
|
@ -0,0 +1,101 @@
|
|||
/*
|
||||
* 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 <string.h>
|
||||
#include "drivers/exti.h"
|
||||
#include "common/utils.h"
|
||||
#include "drivers/io_impl.h"
|
||||
|
||||
#include "hardware/gpio.h"
|
||||
|
||||
typedef struct {
|
||||
extiCallbackRec_t* handler;
|
||||
} extiChannelRec_t;
|
||||
|
||||
static extiChannelRec_t extiChannelRecs[DEFIO_USED_COUNT];
|
||||
static uint32_t extiEventMask[DEFIO_USED_COUNT];
|
||||
|
||||
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config, extiTrigger_t trigger)
|
||||
{
|
||||
uint32_t gpio = IO_Pin(io);
|
||||
|
||||
UNUSED(irqPriority); // Just stick with default GPIO irq priority for now
|
||||
UNUSED(config); // TODO consider pullup/pulldown etc. Needs fixing first in platform.h
|
||||
|
||||
// Ensure the GPIO is initialised and not being used for some other function
|
||||
gpio_init(gpio);
|
||||
|
||||
extiChannelRec_t *rec = &extiChannelRecs[gpio];
|
||||
rec->handler = cb;
|
||||
|
||||
switch(trigger) {
|
||||
case BETAFLIGHT_EXTI_TRIGGER_RISING:
|
||||
default:
|
||||
extiEventMask[gpio] = GPIO_IRQ_EDGE_RISE;
|
||||
break;
|
||||
|
||||
case BETAFLIGHT_EXTI_TRIGGER_FALLING:
|
||||
extiEventMask[gpio] = GPIO_IRQ_EDGE_FALL;
|
||||
break;
|
||||
|
||||
case BETAFLIGHT_EXTI_TRIGGER_BOTH:
|
||||
extiEventMask[gpio] = GPIO_IRQ_EDGE_RISE | GPIO_IRQ_EDGE_FALL;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static void EXTI_IRQHandler(uint gpio, uint32_t event_mask)
|
||||
{
|
||||
// Call the registered handler for this GPIO
|
||||
if (extiChannelRecs[gpio].handler) {
|
||||
extiChannelRecs[gpio].handler->fn(extiChannelRecs[gpio].handler);
|
||||
}
|
||||
|
||||
// Acknowledge the interrupt
|
||||
gpio_acknowledge_irq(gpio, event_mask);
|
||||
}
|
||||
|
||||
void EXTIInit(void)
|
||||
{
|
||||
// Clear all the callbacks
|
||||
memset(extiChannelRecs, 0, sizeof(extiChannelRecs));
|
||||
|
||||
// Register the shared handler for GPIO interrupts
|
||||
gpio_set_irq_callback(EXTI_IRQHandler);
|
||||
|
||||
// Enable the interrupt
|
||||
irq_set_enabled(IO_IRQ_BANK0, true);
|
||||
}
|
||||
|
||||
void EXTIHandlerInit(extiCallbackRec_t *self, extiHandlerCallback *fn)
|
||||
{
|
||||
self->fn = fn;
|
||||
}
|
||||
|
||||
void EXTIEnable(IO_t io)
|
||||
{
|
||||
gpio_set_irq_enabled(IO_Pin(io), extiEventMask[IO_Pin(io)], true);
|
||||
}
|
||||
|
||||
void EXTIDisable(IO_t io)
|
||||
{
|
||||
gpio_set_irq_enabled(IO_Pin(io), 0, false);
|
||||
}
|
75
src/platform/PICO/include/platform/dma.h
Normal file
75
src/platform/PICO/include/platform/dma.h
Normal file
|
@ -0,0 +1,75 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
typedef enum {
|
||||
DMA_INVALID = -1,
|
||||
DMA_NONE = 0,
|
||||
DMA_FIRST_HANDLER = 1,
|
||||
DMA_CH0_HANDLER = DMA_FIRST_HANDLER,
|
||||
DMA_CH1_HANDLER,
|
||||
DMA_CH2_HANDLER,
|
||||
DMA_CH3_HANDLER,
|
||||
DMA_CH4_HANDLER,
|
||||
DMA_CH5_HANDLER,
|
||||
DMA_CH6_HANDLER,
|
||||
DMA_CH7_HANDLER,
|
||||
DMA_CH8_HANDLER,
|
||||
DMA_CH9_HANDLER,
|
||||
DMA_CH10_HANDLER,
|
||||
DMA_CH11_HANDLER,
|
||||
#ifdef RP2350
|
||||
DMA_CH12_HANDLER,
|
||||
DMA_CH13_HANDLER,
|
||||
DMA_CH14_HANDLER,
|
||||
DMA_CH15_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA_CH15_HANDLER
|
||||
#else
|
||||
DMA_LAST_HANDLER = DMA_CH11_HANDLER
|
||||
#endif
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) (0)
|
||||
#define DMA_DEVICE_INDEX(x) ((x)-1)
|
||||
#define DMA_OUTPUT_INDEX 0
|
||||
#define DMA_OUTPUT_STRING "DMA%d Channel %d:"
|
||||
#define DMA_INPUT_STRING "DMA%d_CH%d"
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(c) { \
|
||||
.dma = NULL, \
|
||||
.ref = NULL, \
|
||||
.channel = c-1, \
|
||||
.irqHandlerCallback = NULL, \
|
||||
.flagsShift = 0, \
|
||||
.irqN = 0, \
|
||||
.userParam = 0, \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DMA_IDENTIFIER_TO_CHANNEL(identifier) ((identifier) - DMA_FIRST_HANDLER)
|
||||
#define DMA_CHANNEL_TO_IDENTIFIER(channel) ((dmaIdentifier_e)((channel) + DMA_FIRST_HANDLER))
|
||||
#define DMA_CHANNEL_TO_INDEX(channel) (channel)
|
||||
|
||||
dmaIdentifier_e dmaGetFreeIdentifier(void);
|
39
src/platform/PICO/include/platform/multicore.h
Normal file
39
src/platform/PICO/include/platform/multicore.h
Normal file
|
@ -0,0 +1,39 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "pico/multicore.h"
|
||||
|
||||
typedef enum multicoreCommand_e {
|
||||
MULTICORE_CMD_NONE = 0,
|
||||
MULTICORE_CMD_FUNC,
|
||||
MULTICORE_CMD_FUNC_BLOCKING, // Command to execute a function on the second core and wait for completion
|
||||
MULTICORE_CMD_STOP, // Command to stop the second core
|
||||
} multicoreCommand_e;
|
||||
|
||||
// Define function types for clarity
|
||||
typedef void core1_func_t(void);
|
||||
|
||||
void multicoreStart(void);
|
||||
void multicoreStop(void);
|
||||
void multicoreExecute(core1_func_t *func);
|
||||
void multicoreExecuteBlocking(core1_func_t *func);
|
127
src/platform/PICO/include/platform/platform.h
Normal file
127
src/platform/PICO/include/platform/platform.h
Normal file
|
@ -0,0 +1,127 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "RP2350.h"
|
||||
|
||||
#include "pico.h"
|
||||
#include "pico/stdlib.h"
|
||||
#include "hardware/i2c.h"
|
||||
#include "hardware/spi.h"
|
||||
#include "hardware/dma.h"
|
||||
#include "hardware/flash.h"
|
||||
|
||||
#define NVIC_PriorityGroup_2 0x500
|
||||
#define PLATFORM_NO_LIBC 0
|
||||
#define DEFIO_PORT_PINS 64
|
||||
|
||||
#ifdef RP2350
|
||||
|
||||
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||
|
||||
#define I2C_TypeDef i2c_inst_t
|
||||
#define I2C_INST(i2c) (i2c)
|
||||
|
||||
#define GPIO_TypeDef io_bank0_hw_t
|
||||
//#define GPIO_InitTypeDef
|
||||
#define TIM_TypeDef void*
|
||||
//#define TIM_OCInitTypeDef
|
||||
#define DMA_TypeDef void*
|
||||
#define DMA_InitTypeDef void*
|
||||
//#define DMA_Channel_TypeDef
|
||||
|
||||
#define ADC_TypeDef void*
|
||||
#define USART_TypeDef uart_inst_t
|
||||
#define TIM_OCInitTypeDef void*
|
||||
#define TIM_ICInitTypeDef void*
|
||||
//#define TIM_OCStructInit
|
||||
//#define TIM_Cmd
|
||||
//#define TIM_CtrlPWMOutputs
|
||||
//#define TIM_TimeBaseInit
|
||||
//#define TIM_ARRPreloadConfig
|
||||
//#define SystemCoreClock
|
||||
//#define EXTI_TypeDef
|
||||
//#define EXTI_InitTypeDef
|
||||
|
||||
// We have to use SPI0_Type (or void) because config will pass in SPI0, SPI1,
|
||||
// which are defined in pico-sdk as SPI0_Type*.
|
||||
// SPI_INST converts to the correct type for use in pico-sdk functions.
|
||||
#define SPI_TypeDef SPI0_Type
|
||||
#define SPI_INST(spi) ((spi_inst_t *)(spi))
|
||||
|
||||
#endif
|
||||
|
||||
#define DMA_DATA_ZERO_INIT
|
||||
#define DMA_DATA
|
||||
#define STATIC_DMA_DATA_AUTO static
|
||||
#define FAST_IRQ_HANDLER
|
||||
|
||||
#define DEFAULT_CPU_OVERCLOCK 0
|
||||
|
||||
#ifdef TEST_SLOW_SCHEDULE
|
||||
// (testing) allow time for more / all tasks
|
||||
// 1000 // 50000 // 125 // 125us = 8kHz
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 30000
|
||||
#else
|
||||
// 125us = 8kHz
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 125
|
||||
#endif
|
||||
|
||||
#define SCHEDULER_DELAY_LIMIT 10
|
||||
|
||||
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
|
||||
|
||||
// TODO update these and IOConfigGPIO
|
||||
#define IOCFG_OUT_PP IO_CONFIG(GPIO_OUT, 0, 0)
|
||||
#define IOCFG_OUT_OD IO_CONFIG(GPIO_OUT, 0, 0)
|
||||
#define IOCFG_AF_PP 0
|
||||
#define IOCFG_AF_OD 0
|
||||
#define IOCFG_IPD IO_CONFIG(GPIO_IN, 0, 0)
|
||||
#define IOCFG_IPU IO_CONFIG(GPIO_IN, 0, 0)
|
||||
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_IN, 0, 0)
|
||||
|
||||
// TODO update these and IOConfigGPIO
|
||||
#define SPI_IO_AF_CFG 0
|
||||
#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 IO_CONFIG(GPIO_OUT, 0, 0) // todo pullup/down etc.
|
||||
|
||||
|
||||
#define SERIAL_UART_FIRST_INDEX 0
|
||||
|
||||
extern uint32_t systemUniqueId[3];
|
||||
|
||||
// PICOs have an 8 byte unique identifier.
|
||||
#define U_ID_0 (systemUniqueId[0])
|
||||
#define U_ID_1 (systemUniqueId[1])
|
||||
#define U_ID_2 (systemUniqueId[2])
|
||||
|
||||
#define UART_TX_BUFFER_ATTRIBUTE
|
||||
#define UART_RX_BUFFER_ATTRIBUTE
|
||||
|
||||
#define SERIAL_TRAIT_PIN_CONFIG 1
|
||||
|
||||
#define xDMA_GetCurrDataCounter(dma_resource) (((dma_channel_hw_t *)(dma_resource))->transfer_count)
|
||||
|
||||
#define USE_LATE_TASK_STATISTICS
|
||||
|
224
src/platform/PICO/io_def_generated.h
Normal file
224
src/platform/PICO/io_def_generated.h
Normal file
|
@ -0,0 +1,224 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// DEFIO_PORT_<port>_USED_MASK is bitmask of used pins on target
|
||||
// DEFIO_PORT_<port>_USED_COUNT is count of used pins on target
|
||||
|
||||
#if defined(RP2350A)
|
||||
#define DEFIO_USED_COUNT 30
|
||||
#elif defined(RP2350B)
|
||||
#define DEFIO_USED_COUNT 48
|
||||
#else
|
||||
#error "Unsupported target MCU type for PICO"
|
||||
#endif
|
||||
|
||||
#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__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__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__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__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__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__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
|
||||
#if defined(RP2350A)
|
||||
#define DEFIO_IO_USED_COUNT DEFIO_USED_COUNT
|
||||
#elif defined(RP2350B)
|
||||
#define DEFIO_IO_USED_COUNT DEFIO_USED_COUNT
|
||||
#endif
|
||||
|
||||
// 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
|
||||
#define DEFIO_PIN_USED_COUNT DEFIO_USED_COUNT
|
187
src/platform/PICO/io_pico.c
Normal file
187
src/platform/PICO/io_pico.c
Normal file
|
@ -0,0 +1,187 @@
|
|||
/*
|
||||
* 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 "platform.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "hardware/gpio.h"
|
||||
|
||||
#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;
|
||||
|
||||
for (unsigned pin = 0; pin < DEFIO_PIN_USED_COUNT; pin++) {
|
||||
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
|
||||
|
||||
// Some boards (e.g. Laurel) require a pin to be held low in order to generate a 5V / 9V
|
||||
// power supply from the main battery.
|
||||
// (TODO: should we manage a list of pins that we want to send low or high?)
|
||||
#ifdef PICO_BEC_5V_ENABLE_PIN
|
||||
const int pin5 = IO_PINBYTAG(IO_TAG(PICO_BEC_5V_ENABLE_PIN));
|
||||
gpio_init(pin5);
|
||||
gpio_set_dir(pin5, 1);
|
||||
gpio_put(pin5, 0);
|
||||
ioRecs[pin5].owner = OWNER_SYSTEM;
|
||||
#endif
|
||||
|
||||
#ifdef PICO_BEC_9V_ENABLE_PIN
|
||||
const int pin9 = IO_PINBYTAG(IO_TAG(PICO_BEC_9V_ENABLE_PIN));
|
||||
gpio_init(pin9);
|
||||
gpio_set_dir(pin9, 1);
|
||||
gpio_put(pin9, 0);
|
||||
ioRecs[pin9].owner = OWNER_SYSTEM;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t IO_EXTI_Line(IO_t io)
|
||||
{
|
||||
UNUSED(io);
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool IORead(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return false;
|
||||
}
|
||||
return gpio_get(IO_Pin(io));
|
||||
}
|
||||
|
||||
void IOWrite(IO_t io, bool hi)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
gpio_put(IO_Pin(io), hi);
|
||||
}
|
||||
|
||||
void IOHi(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
gpio_put(IO_Pin(io), 1);
|
||||
}
|
||||
|
||||
void IOLo(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
gpio_put(IO_Pin(io), 0);
|
||||
}
|
||||
|
||||
void IOToggle(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
gpio_put(IO_Pin(io), !gpio_get(IO_Pin(io)));
|
||||
}
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
/*
|
||||
TODO: update to support the following
|
||||
IOCFG_AF_PP
|
||||
IOCFG_IN_FLOATING
|
||||
IOCFG_IPD
|
||||
IOCFG_IPU
|
||||
IOCFG_OUT_OD
|
||||
IOCFG_OUT_PP
|
||||
IO_RESET_CFG
|
||||
|
||||
SPI_IO_CS_CFG (as defined)
|
||||
SPI_IO_CS_HIGH_CFG (as defined)
|
||||
*/
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint16_t ioPin = IO_Pin(io);
|
||||
if (gpio_get_function(ioPin) == GPIO_FUNC_NULL) {
|
||||
gpio_init(ioPin);
|
||||
}
|
||||
gpio_set_dir(ioPin, (cfg & 0x01)); // 0 = in, 1 = out
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t tag)
|
||||
{
|
||||
const int portIdx = DEFIO_TAG_GPIOID(tag);
|
||||
const int pinIdx = DEFIO_TAG_PIN(tag);
|
||||
|
||||
if (portIdx < 0 || portIdx >= DEFIO_PORT_USED_COUNT) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (pinIdx >= DEFIO_PIN_USED_COUNT) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
345
src/platform/PICO/link/pico_rp2350_RunFromFLASH.ld
Normal file
345
src/platform/PICO/link/pico_rp2350_RunFromFLASH.ld
Normal file
|
@ -0,0 +1,345 @@
|
|||
/* Based on GCC ARM embedded samples.
|
||||
Defines the following symbols for use by code:
|
||||
__exidx_start
|
||||
__exidx_end
|
||||
__etext
|
||||
__data_start__
|
||||
__preinit_array_start
|
||||
__preinit_array_end
|
||||
__init_array_start
|
||||
__init_array_end
|
||||
__fini_array_start
|
||||
__fini_array_end
|
||||
__data_end__
|
||||
__bss_start__
|
||||
__bss_end__
|
||||
__end__
|
||||
end
|
||||
__HeapLimit
|
||||
__StackLimit
|
||||
__StackTop
|
||||
__stack (== StackTop)
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
/* TODO: Assuming for now that target has >= 4MB boot flash */
|
||||
FLASH (rx) : ORIGIN = 0x10000000, LENGTH = 4032K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x103F0000, LENGTH = 64K
|
||||
RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512k
|
||||
SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k
|
||||
SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k
|
||||
}
|
||||
|
||||
ENTRY(_entry_point)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.flash_begin : {
|
||||
__flash_binary_start = .;
|
||||
} > FLASH
|
||||
|
||||
/* The bootrom will enter the image at the point indicated in your
|
||||
IMAGE_DEF, which is usually the reset handler of your vector table.
|
||||
|
||||
The debugger will use the ELF entry point, which is the _entry_point
|
||||
symbol, and in our case is *different from the bootrom's entry point.*
|
||||
This is used to go back through the bootrom on debugger launches only,
|
||||
to perform the same initial flash setup that would be performed on a
|
||||
cold boot.
|
||||
*/
|
||||
|
||||
.text : {
|
||||
__logical_binary_start = .;
|
||||
KEEP (*(.vectors))
|
||||
KEEP (*(.binary_info_header))
|
||||
__binary_info_header_end = .;
|
||||
KEEP (*(.embedded_block))
|
||||
__embedded_block_end = .;
|
||||
KEEP (*(.reset))
|
||||
/* TODO revisit this now memset/memcpy/float in ROM */
|
||||
/* bit of a hack right now to exclude all floating point and time critical (e.g. memset, memcpy) code from
|
||||
* FLASH ... we will include any thing excluded here in .data below by default */
|
||||
*(.init)
|
||||
*libgcc.a:cmse_nonsecure_call.o
|
||||
*(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .text*)
|
||||
*(.fini)
|
||||
/* Pull all c'tors into .text */
|
||||
*crtbegin.o(.ctors)
|
||||
*crtbegin?.o(.ctors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
|
||||
*(SORT(.ctors.*))
|
||||
*(.ctors)
|
||||
/* Followed by destructors */
|
||||
*crtbegin.o(.dtors)
|
||||
*crtbegin?.o(.dtors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
|
||||
*(SORT(.dtors.*))
|
||||
*(.dtors)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP(*(SORT(.preinit_array.*)))
|
||||
KEEP(*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(.init_array))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* finit data */
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
*(SORT(.fini_array.*))
|
||||
*(.fini_array)
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
|
||||
*(.eh_frame*)
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
/* Note the boot2 section is optional, and should be discarded if there is
|
||||
no reference to it *inside* the binary, as it is not called by the
|
||||
bootrom. (The bootrom performs a simple best-effort XIP setup and
|
||||
leaves it to the binary to do anything more sophisticated.) However
|
||||
there is still a size limit of 256 bytes, to ensure the boot2 can be
|
||||
stored in boot RAM.
|
||||
|
||||
Really this is a "XIP setup function" -- the name boot2 is historic and
|
||||
refers to its dual-purpose on RP2040, where it also handled vectoring
|
||||
from the bootrom into the user image.
|
||||
*/
|
||||
|
||||
.boot2 : {
|
||||
__boot2_start__ = .;
|
||||
*(.boot2)
|
||||
__boot2_end__ = .;
|
||||
} > FLASH
|
||||
|
||||
ASSERT(__boot2_end__ - __boot2_start__ <= 256,
|
||||
"ERROR: Pico second stage bootloader must be no more than 256 bytes in size")
|
||||
|
||||
.rodata : {
|
||||
*(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .rodata*)
|
||||
*(.srodata*)
|
||||
. = ALIGN(4);
|
||||
*(SORT_BY_ALIGNMENT(SORT_BY_NAME(.flashdata*)))
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > FLASH
|
||||
__exidx_end = .;
|
||||
|
||||
/* Machine inspectable binary information */
|
||||
. = ALIGN(4);
|
||||
__binary_info_start = .;
|
||||
.binary_info :
|
||||
{
|
||||
KEEP(*(.binary_info.keep.*))
|
||||
*(.binary_info.*)
|
||||
} > FLASH
|
||||
__binary_info_end = .;
|
||||
. = ALIGN(4);
|
||||
|
||||
.ram_vector_table (NOLOAD): {
|
||||
*(.ram_vector_table)
|
||||
} > RAM
|
||||
|
||||
.uninitialized_data (NOLOAD): {
|
||||
. = ALIGN(4);
|
||||
*(.uninitialized_data*)
|
||||
} > RAM
|
||||
|
||||
.data : {
|
||||
__data_start__ = .;
|
||||
*(vtable)
|
||||
|
||||
*(.time_critical*)
|
||||
|
||||
/* remaining .text and .rodata; i.e. stuff we exclude above because we want it in RAM */
|
||||
*(.text*)
|
||||
. = ALIGN(4);
|
||||
*(.rodata*)
|
||||
. = ALIGN(4);
|
||||
|
||||
*(.data*)
|
||||
*(.sdata*)
|
||||
|
||||
. = ALIGN(4);
|
||||
*(.after_data.*)
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__mutex_array_start = .);
|
||||
KEEP(*(SORT(.mutex_array.*)))
|
||||
KEEP(*(.mutex_array))
|
||||
PROVIDE_HIDDEN (__mutex_array_end = .);
|
||||
|
||||
*(.jcr)
|
||||
. = ALIGN(4);
|
||||
} > RAM AT> FLASH
|
||||
|
||||
.tdata : {
|
||||
. = ALIGN(4);
|
||||
*(.tdata .tdata.* .gnu.linkonce.td.*)
|
||||
/* All data end */
|
||||
__tdata_end = .;
|
||||
} > RAM AT> FLASH
|
||||
PROVIDE(__data_end__ = .);
|
||||
|
||||
/* __etext is (for backwards compatibility) the name of the .data init source pointer (...) */
|
||||
__etext = LOADADDR(.data);
|
||||
|
||||
.tbss (NOLOAD) : {
|
||||
. = ALIGN(4);
|
||||
__bss_start__ = .;
|
||||
__tls_base = .;
|
||||
*(.tbss .tbss.* .gnu.linkonce.tb.*)
|
||||
*(.tcommon)
|
||||
|
||||
__tls_end = .;
|
||||
} > RAM
|
||||
|
||||
.bss (NOLOAD) : {
|
||||
. = ALIGN(4);
|
||||
__tbss_end = .;
|
||||
|
||||
*(SORT_BY_ALIGNMENT(SORT_BY_NAME(.bss*)))
|
||||
*(COMMON)
|
||||
PROVIDE(__global_pointer$ = . + 2K);
|
||||
*(.sbss*)
|
||||
. = ALIGN(4);
|
||||
__bss_end__ = .;
|
||||
} > RAM
|
||||
|
||||
.heap (NOLOAD):
|
||||
{
|
||||
__end__ = .;
|
||||
end = __end__;
|
||||
KEEP(*(.heap*))
|
||||
} > RAM
|
||||
/* historically on GCC sbrk was growing past __HeapLimit to __StackLimit, however
|
||||
to be more compatible, we now set __HeapLimit explicitly to where the end of the heap is */
|
||||
__HeapLimit = ORIGIN(RAM) + LENGTH(RAM);
|
||||
|
||||
/* Start and end symbols must be word-aligned */
|
||||
.scratch_x : {
|
||||
__scratch_x_start__ = .;
|
||||
*(.scratch_x.*)
|
||||
. = ALIGN(4);
|
||||
__scratch_x_end__ = .;
|
||||
} > SCRATCH_X AT > FLASH
|
||||
__scratch_x_source__ = LOADADDR(.scratch_x);
|
||||
|
||||
.scratch_y : {
|
||||
__scratch_y_start__ = .;
|
||||
*(.scratch_y.*)
|
||||
. = ALIGN(4);
|
||||
__scratch_y_end__ = .;
|
||||
} > 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
|
||||
* used for linker to calculate size of stack sections, and assign
|
||||
* values to stack symbols later
|
||||
*
|
||||
* stack1 section may be empty/missing if platform_launch_core1 is not used */
|
||||
|
||||
/* by default we put core 0 stack at the end of scratch Y, so that if core 1
|
||||
* stack is not used then all of SCRATCH_X is free.
|
||||
*/
|
||||
.stack1_dummy (NOLOAD):
|
||||
{
|
||||
*(.stack1*)
|
||||
} > SCRATCH_X
|
||||
.stack_dummy (NOLOAD):
|
||||
{
|
||||
KEEP(*(.stack*))
|
||||
} > SCRATCH_Y
|
||||
|
||||
/* keep embedded end block as final entry into FLASH
|
||||
* - helps protect against partial/corrupt load into flash
|
||||
*/
|
||||
.flash_end : {
|
||||
KEEP(*(.embedded_end_block*))
|
||||
PROVIDE(__flash_binary_end = .);
|
||||
} > FLASH =0xaa
|
||||
|
||||
|
||||
/* Base address where the config is stored. */
|
||||
__config_start = ORIGIN(FLASH_CONFIG);
|
||||
__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG);
|
||||
|
||||
.pg_registry :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_registry_start = .);
|
||||
KEEP (*(.pg_registry))
|
||||
KEEP (*(SORT(.pg_registry.*)))
|
||||
PROVIDE_HIDDEN (__pg_registry_end = .);
|
||||
} >FLASH
|
||||
|
||||
.pg_resetdata :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_resetdata_start = .);
|
||||
KEEP (*(.pg_resetdata))
|
||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||
} >FLASH
|
||||
|
||||
|
||||
/* stack limit is poorly named, but historically is maximum heap ptr */
|
||||
__StackLimit = ORIGIN(RAM) + LENGTH(RAM);
|
||||
__StackOneTop = ORIGIN(SCRATCH_X) + LENGTH(SCRATCH_X);
|
||||
__StackTop = ORIGIN(SCRATCH_Y) + LENGTH(SCRATCH_Y);
|
||||
__StackOneBottom = __StackOneTop - SIZEOF(.stack1_dummy);
|
||||
__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);
|
||||
PROVIDE( __tls_align = MAX(ALIGNOF(.tdata), ALIGNOF(.tbss)) );
|
||||
PROVIDE( __tls_size_align = (__tls_size + __tls_align - 1) & ~(__tls_align - 1));
|
||||
PROVIDE( __arm32_tls_tcb_offset = MAX(8, __tls_align) );
|
||||
|
||||
/* llvm-libc */
|
||||
PROVIDE (_end = __end__);
|
||||
PROVIDE (__llvm_libc_heap_limit = __HeapLimit);
|
||||
|
||||
/* Check if data + heap + stack exceeds RAM limit */
|
||||
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed")
|
||||
|
||||
ASSERT( __binary_info_header_end - __logical_binary_start <= 1024, "Binary info must be in first 1024 bytes of the binary")
|
||||
ASSERT( __embedded_block_end - __logical_binary_start <= 4096, "Embedded block must be in first 4096 bytes of the binary")
|
||||
|
||||
/* todo assert on extra code */
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
}
|
||||
|
352
src/platform/PICO/link/pico_rp2350_RunFromRAM.ld
Normal file
352
src/platform/PICO/link/pico_rp2350_RunFromRAM.ld
Normal file
|
@ -0,0 +1,352 @@
|
|||
/*
|
||||
Copy to and run from SRAM
|
||||
Based on pico-sdk rp2_common/pico_crt0/rp2350/memmap_copy_to_ram.ld
|
||||
*/
|
||||
|
||||
/* Based on GCC ARM embedded samples.
|
||||
Defines the following symbols for use by code:
|
||||
__exidx_start
|
||||
__exidx_end
|
||||
__etext
|
||||
__data_start__
|
||||
__preinit_array_start
|
||||
__preinit_array_end
|
||||
__init_array_start
|
||||
__init_array_end
|
||||
__fini_array_start
|
||||
__fini_array_end
|
||||
__data_end__
|
||||
__bss_start__
|
||||
__bss_end__
|
||||
__end__
|
||||
end
|
||||
__HeapLimit
|
||||
__StackLimit
|
||||
__StackTop
|
||||
__stack (== StackTop)
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
/* TODO: Assuming for now that target has >= 4MB boot flash */
|
||||
FLASH (rx) : ORIGIN = 0x10000000, LENGTH = 4032K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x103F0000, LENGTH = 64K
|
||||
RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512k
|
||||
SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k
|
||||
SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k
|
||||
}
|
||||
|
||||
ENTRY(_entry_point)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.flash_begin : {
|
||||
__flash_binary_start = .;
|
||||
} > FLASH
|
||||
|
||||
/* The bootrom will enter the image at the point indicated in your
|
||||
IMAGE_DEF, which is usually the reset handler of your vector table.
|
||||
|
||||
The debugger will use the ELF entry point, which is the _entry_point
|
||||
symbol, and in our case is *different from the bootrom's entry point.*
|
||||
This is used to go back through the bootrom on debugger launches only,
|
||||
to perform the same initial flash setup that would be performed on a
|
||||
cold boot.
|
||||
*/
|
||||
|
||||
.flashtext : {
|
||||
__logical_binary_start = .;
|
||||
KEEP (*(.vectors))
|
||||
KEEP (*(.binary_info_header))
|
||||
__binary_info_header_end = .;
|
||||
KEEP (*(.embedded_block))
|
||||
__embedded_block_end = .;
|
||||
KEEP (*(.reset))
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
/* Note the boot2 section is optional, and should be discarded if there is
|
||||
no reference to it *inside* the binary, as it is not called by the
|
||||
bootrom. (The bootrom performs a simple best-effort XIP setup and
|
||||
leaves it to the binary to do anything more sophisticated.) However
|
||||
there is still a size limit of 256 bytes, to ensure the boot2 can be
|
||||
stored in boot RAM.
|
||||
|
||||
Really this is a "XIP setup function" -- the name boot2 is historic and
|
||||
refers to its dual-purpose on RP2040, where it also handled vectoring
|
||||
from the bootrom into the user image.
|
||||
*/
|
||||
|
||||
.boot2 : {
|
||||
__boot2_start__ = .;
|
||||
*(.boot2)
|
||||
__boot2_end__ = .;
|
||||
} > FLASH
|
||||
|
||||
ASSERT(__boot2_end__ - __boot2_start__ <= 256,
|
||||
"ERROR: Pico second stage bootloader must be no more than 256 bytes in size")
|
||||
|
||||
.rodata : {
|
||||
/* segments not marked as .flashdata are instead pulled into .data (in RAM) to avoid accidental flash accesses */
|
||||
*(SORT_BY_ALIGNMENT(SORT_BY_NAME(.flashdata*)))
|
||||
. = ALIGN(4);
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > FLASH
|
||||
__exidx_end = .;
|
||||
|
||||
/* Machine inspectable binary information */
|
||||
. = ALIGN(4);
|
||||
__binary_info_start = .;
|
||||
.binary_info :
|
||||
{
|
||||
KEEP(*(.binary_info.keep.*))
|
||||
*(.binary_info.*)
|
||||
} > FLASH
|
||||
__binary_info_end = .;
|
||||
. = ALIGN(4);
|
||||
|
||||
/* Vector table goes first in RAM, to avoid large alignment hole */
|
||||
.ram_vector_table (NOLOAD): {
|
||||
*(.ram_vector_table)
|
||||
} > RAM
|
||||
|
||||
.uninitialized_data (NOLOAD): {
|
||||
. = ALIGN(4);
|
||||
*(.uninitialized_data*)
|
||||
} > RAM
|
||||
|
||||
.text : {
|
||||
__ram_text_start__ = .;
|
||||
*(.init)
|
||||
*(.text*)
|
||||
*(.fini)
|
||||
/* Pull all c'tors into .text */
|
||||
*crtbegin.o(.ctors)
|
||||
*crtbegin?.o(.ctors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
|
||||
*(SORT(.ctors.*))
|
||||
*(.ctors)
|
||||
/* Followed by destructors */
|
||||
*crtbegin.o(.dtors)
|
||||
*crtbegin?.o(.dtors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
|
||||
*(SORT(.dtors.*))
|
||||
*(.dtors)
|
||||
|
||||
*(.eh_frame*)
|
||||
. = ALIGN(4);
|
||||
__ram_text_end__ = .;
|
||||
} > RAM AT> FLASH
|
||||
__ram_text_source__ = LOADADDR(.text);
|
||||
. = ALIGN(4);
|
||||
|
||||
.data : {
|
||||
__data_start__ = .;
|
||||
*(vtable)
|
||||
|
||||
*(.time_critical*)
|
||||
|
||||
. = ALIGN(4);
|
||||
*(.rodata*)
|
||||
*(.srodata*)
|
||||
. = ALIGN(4);
|
||||
|
||||
*(.data*)
|
||||
*(.sdata*)
|
||||
|
||||
. = ALIGN(4);
|
||||
*(.after_data.*)
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__mutex_array_start = .);
|
||||
KEEP(*(SORT(.mutex_array.*)))
|
||||
KEEP(*(.mutex_array))
|
||||
PROVIDE_HIDDEN (__mutex_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP(*(SORT(.preinit_array.*)))
|
||||
KEEP(*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(.init_array))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* finit data */
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
*(SORT(.fini_array.*))
|
||||
*(.fini_array)
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
|
||||
*(.jcr)
|
||||
. = ALIGN(4);
|
||||
} > RAM AT> FLASH
|
||||
|
||||
.tdata : {
|
||||
. = ALIGN(4);
|
||||
*(.tdata .tdata.* .gnu.linkonce.td.*)
|
||||
/* All data end */
|
||||
__tdata_end = .;
|
||||
} > RAM AT> FLASH
|
||||
PROVIDE(__data_end__ = .);
|
||||
|
||||
/* __etext is (for backwards compatibility) the name of the .data init source pointer (...) */
|
||||
__etext = LOADADDR(.data);
|
||||
|
||||
.tbss (NOLOAD) : {
|
||||
. = ALIGN(4);
|
||||
__bss_start__ = .;
|
||||
__tls_base = .;
|
||||
*(.tbss .tbss.* .gnu.linkonce.tb.*)
|
||||
*(.tcommon)
|
||||
|
||||
__tls_end = .;
|
||||
} > RAM
|
||||
|
||||
.bss : {
|
||||
. = ALIGN(4);
|
||||
__tbss_end = .;
|
||||
|
||||
*(SORT_BY_ALIGNMENT(SORT_BY_NAME(.bss*)))
|
||||
*(COMMON)
|
||||
PROVIDE(__global_pointer$ = . + 2K);
|
||||
*(.sbss*)
|
||||
. = ALIGN(4);
|
||||
__bss_end__ = .;
|
||||
} > RAM
|
||||
|
||||
.heap (NOLOAD):
|
||||
{
|
||||
__end__ = .;
|
||||
end = __end__;
|
||||
KEEP(*(.heap*))
|
||||
} > RAM
|
||||
/* historically on GCC sbrk was growing past __HeapLimit to __StackLimit, however
|
||||
to be more compatible, we now set __HeapLimit explicitly to where the end of the heap is */
|
||||
__HeapLimit = ORIGIN(RAM) + LENGTH(RAM);
|
||||
|
||||
/* Start and end symbols must be word-aligned */
|
||||
.scratch_x : {
|
||||
__scratch_x_start__ = .;
|
||||
*(.scratch_x.*)
|
||||
. = ALIGN(4);
|
||||
__scratch_x_end__ = .;
|
||||
} > SCRATCH_X AT > FLASH
|
||||
__scratch_x_source__ = LOADADDR(.scratch_x);
|
||||
|
||||
.scratch_y : {
|
||||
__scratch_y_start__ = .;
|
||||
*(.scratch_y.*)
|
||||
. = ALIGN(4);
|
||||
__scratch_y_end__ = .;
|
||||
} > SCRATCH_Y AT > FLASH /*=0xa5a5a5a5*/ /* BF: TODO 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
|
||||
* used for linker to calculate size of stack sections, and assign
|
||||
* values to stack symbols later
|
||||
*
|
||||
* stack1 section may be empty/missing if platform_launch_core1 is not used */
|
||||
|
||||
/* by default we put core 0 stack at the end of scratch Y, so that if core 1
|
||||
* stack is not used then all of SCRATCH_X is free.
|
||||
*/
|
||||
.stack1_dummy (NOLOAD):
|
||||
{
|
||||
*(.stack1*)
|
||||
} > SCRATCH_X
|
||||
.stack_dummy (NOLOAD):
|
||||
{
|
||||
KEEP(*(.stack*))
|
||||
} > SCRATCH_Y
|
||||
|
||||
/* keep embedded end block as final entry into FLASH
|
||||
* - helps protect against partial/corrupt load into flash
|
||||
*/
|
||||
.flash_end : {
|
||||
KEEP(*(.embedded_end_block*))
|
||||
PROVIDE(__flash_binary_end = .);
|
||||
} > FLASH =0xaa
|
||||
|
||||
|
||||
/* Base address where the config is stored. */
|
||||
__config_start = ORIGIN(FLASH_CONFIG);
|
||||
__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG);
|
||||
|
||||
.pg_registry :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_registry_start = .);
|
||||
KEEP (*(.pg_registry))
|
||||
KEEP (*(SORT(.pg_registry.*)))
|
||||
PROVIDE_HIDDEN (__pg_registry_end = .);
|
||||
} >FLASH
|
||||
|
||||
.pg_resetdata :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_resetdata_start = .);
|
||||
KEEP (*(.pg_resetdata))
|
||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||
} >FLASH
|
||||
|
||||
|
||||
/* stack limit is poorly named, but historically is maximum heap ptr */
|
||||
__StackLimit = ORIGIN(RAM) + LENGTH(RAM);
|
||||
__StackOneTop = ORIGIN(SCRATCH_X) + LENGTH(SCRATCH_X);
|
||||
__StackTop = ORIGIN(SCRATCH_Y) + LENGTH(SCRATCH_Y);
|
||||
__StackOneBottom = __StackOneTop - SIZEOF(.stack1_dummy);
|
||||
__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);
|
||||
PROVIDE( __tls_align = MAX(ALIGNOF(.tdata), ALIGNOF(.tbss)) );
|
||||
PROVIDE( __tls_size_align = (__tls_size + __tls_align - 1) & ~(__tls_align - 1));
|
||||
PROVIDE( __arm32_tls_tcb_offset = MAX(8, __tls_align) );
|
||||
|
||||
/* llvm-libc */
|
||||
PROVIDE (_end = __end__);
|
||||
PROVIDE (__llvm_libc_heap_limit = __HeapLimit);
|
||||
|
||||
/* Check if data + heap + stack exceeds RAM limit */
|
||||
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed")
|
||||
|
||||
ASSERT( __binary_info_header_end - __logical_binary_start <= 1024, "Binary info must be in first 1024 bytes of the binary")
|
||||
ASSERT( __embedded_block_end - __logical_binary_start <= 4096, "Embedded block must be in first 4096 bytes of the binary")
|
||||
|
||||
/* todo assert on extra code */
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
}
|
||||
|
12
src/platform/PICO/mk/PICO_trace.mk
Normal file
12
src/platform/PICO/mk/PICO_trace.mk
Normal file
|
@ -0,0 +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 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
|
427
src/platform/PICO/mk/RP2350.mk
Normal file
427
src/platform/PICO/mk/RP2350.mk
Normal file
|
@ -0,0 +1,427 @@
|
|||
#
|
||||
# Raspberry PICO Make file include
|
||||
#
|
||||
# The top level Makefile adds $(MCU_COMMON_SRC) and $(DEVICE_STDPERIPH_SRC) to SRC collection.
|
||||
#
|
||||
|
||||
# PICO_TRACE = 1
|
||||
DEFAULT_OUTPUT := uf2
|
||||
|
||||
# Run from SRAM. To disable, set environment variable RUN_FROM_RAM=0
|
||||
ifeq ($(RUN_FROM_RAM),)
|
||||
RUN_FROM_RAM = 1
|
||||
endif
|
||||
|
||||
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
|
||||
PICO_MK_DIR = $(TARGET_PLATFORM_DIR)/mk
|
||||
|
||||
ifneq ($(PICO_TRACE),)
|
||||
include $(PICO_MK_DIR)/PICO_trace.mk
|
||||
endif
|
||||
|
||||
RP2350_TARGETS = RP2350A RP2350B
|
||||
ifneq ($(filter $(TARGET_MCU), $(RP2350_TARGETS)),)
|
||||
RP2350_TARGET = $(TARGET_MCU)
|
||||
endif
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),PICO)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
SDK_DIR = $(LIB_MAIN_DIR)/pico-sdk/src
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR := $(SDK_DIR)
|
||||
|
||||
PICO_LIB_SRC = \
|
||||
rp2_common/pico_crt0/crt0.S \
|
||||
rp2_common/hardware_sync_spin_lock/sync_spin_lock.c \
|
||||
rp2_common/hardware_gpio/gpio.c \
|
||||
rp2_common/hardware_uart/uart.c \
|
||||
rp2_common/hardware_irq/irq.c \
|
||||
rp2_common/hardware_irq/irq_handler_chain.S \
|
||||
rp2_common/hardware_timer/timer.c \
|
||||
rp2_common/hardware_clocks/clocks.c \
|
||||
rp2_common/hardware_pll/pll.c \
|
||||
rp2_common/hardware_dma/dma.c \
|
||||
rp2_common/hardware_spi/spi.c \
|
||||
rp2_common/hardware_i2c/i2c.c \
|
||||
rp2_common/hardware_adc/adc.c \
|
||||
rp2_common/hardware_pio/pio.c \
|
||||
rp2_common/hardware_watchdog/watchdog.c \
|
||||
rp2_common/hardware_flash/flash.c \
|
||||
rp2_common/pico_unique_id/unique_id.c \
|
||||
rp2_common/pico_platform_panic/panic.c \
|
||||
rp2_common/pico_multicore/multicore.c \
|
||||
common/pico_sync/mutex.c \
|
||||
common/pico_time/time.c \
|
||||
common/pico_sync/lock_core.c \
|
||||
common/hardware_claim/claim.c \
|
||||
common/pico_sync/critical_section.c \
|
||||
rp2_common/hardware_sync/sync.c \
|
||||
rp2_common/pico_bootrom/bootrom.c \
|
||||
rp2_common/pico_runtime_init/runtime_init.c \
|
||||
rp2_common/pico_runtime_init/runtime_init_clocks.c \
|
||||
rp2_common/pico_runtime_init/runtime_init_stack_guard.c \
|
||||
rp2_common/pico_runtime/runtime.c \
|
||||
rp2_common/hardware_ticks/ticks.c \
|
||||
rp2_common/hardware_xosc/xosc.c \
|
||||
common/pico_sync/sem.c \
|
||||
common/pico_time/timeout_helper.c \
|
||||
common/pico_util/datetime.c \
|
||||
common/pico_util/pheap.c \
|
||||
common/pico_util/queue.c \
|
||||
rp2350/pico_platform/platform.c \
|
||||
rp2_common/pico_atomic/atomic.c \
|
||||
rp2_common/pico_bootrom/bootrom.c \
|
||||
rp2_common/pico_bootrom/bootrom_lock.c \
|
||||
rp2_common/pico_divider/divider_compiler.c \
|
||||
rp2_common/pico_double/double_math.c \
|
||||
rp2_common/pico_flash/flash.c \
|
||||
rp2_common/pico_float/float_math.c \
|
||||
rp2_common/hardware_divider/divider.c \
|
||||
rp2_common/hardware_vreg/vreg.c \
|
||||
rp2_common/hardware_xip_cache/xip_cache.c \
|
||||
rp2_common/pico_standard_binary_info/standard_binary_info.c \
|
||||
rp2_common/pico_clib_interface/newlib_interface.c \
|
||||
rp2_common/pico_malloc/malloc.c \
|
||||
rp2_common/pico_stdlib/stdlib.c
|
||||
|
||||
TINY_USB_SRC_DIR = $(LIB_MAIN_DIR)/pico-sdk/lib/tinyusb/src
|
||||
TINYUSB_SRC := \
|
||||
$(TINY_USB_SRC_DIR)/tusb.c \
|
||||
$(TINY_USB_SRC_DIR)/class/cdc/cdc_device.c \
|
||||
$(TINY_USB_SRC_DIR)/common/tusb_fifo.c \
|
||||
$(TINY_USB_SRC_DIR)/device/usbd.c \
|
||||
$(TINY_USB_SRC_DIR)/device/usbd_control.c \
|
||||
$(TINY_USB_SRC_DIR)/portable/raspberrypi/rp2040/dcd_rp2040.c \
|
||||
$(TINY_USB_SRC_DIR)/portable/raspberrypi/rp2040/rp2040_usb.c
|
||||
|
||||
# TODO which of these do we need?
|
||||
TINYUSB_SRC += \
|
||||
$(TINY_USB_SRC_DIR)/class/vendor/vendor_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/net/ecm_rndis_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/net/ncm_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/dfu/dfu_rt_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/dfu/dfu_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/msc/msc_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/midi/midi_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/video/video_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/hid/hid_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/usbtmc/usbtmc_device.c \
|
||||
$(TINY_USB_SRC_DIR)/class/audio/audio_device.c
|
||||
|
||||
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)
|
||||
|
||||
ifdef RP2350_TARGET
|
||||
TARGET_MCU_LIB_LOWER = rp2350
|
||||
TARGET_MCU_LIB_UPPER = RP2350
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU_LIB_UPPER)/Include
|
||||
CMSIS_SRC :=
|
||||
|
||||
INCLUDE_DIRS += \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/usb \
|
||||
$(TARGET_PLATFORM_DIR)/startup
|
||||
|
||||
SYS_INCLUDE_DIRS = \
|
||||
$(SDK_DIR)/common/pico_bit_ops_headers/include \
|
||||
$(SDK_DIR)/common/pico_base_headers/include \
|
||||
$(SDK_DIR)/common/boot_picoboot_headers/include \
|
||||
$(SDK_DIR)/common/pico_usb_reset_interface_headers/include \
|
||||
$(SDK_DIR)/common/pico_time/include \
|
||||
$(SDK_DIR)/common/boot_uf2_headers/include \
|
||||
$(SDK_DIR)/common/pico_divider_headers/include \
|
||||
$(SDK_DIR)/common/boot_picobin_headers/include \
|
||||
$(SDK_DIR)/common/pico_util/include \
|
||||
$(SDK_DIR)/common/pico_stdlib_headers/include \
|
||||
$(SDK_DIR)/common/hardware_claim/include \
|
||||
$(SDK_DIR)/common/pico_binary_info/include \
|
||||
$(SDK_DIR)/common/pico_sync/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_uart/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_usb/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_rtt/include \
|
||||
$(SDK_DIR)/rp2_common/tinyusb/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_rtc/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_boot_lock/include \
|
||||
$(SDK_DIR)/rp2_common/pico_mem_ops/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_exception/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_sync_spin_lock/include \
|
||||
$(SDK_DIR)/rp2_common/pico_runtime_init/include \
|
||||
$(SDK_DIR)/rp2_common/pico_standard_link/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_pio/include \
|
||||
$(SDK_DIR)/rp2_common/pico_platform_compiler/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_divider/include \
|
||||
$(SDK_DIR)/rp2_common/pico_bootsel_via_double_reset/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_powman/include \
|
||||
$(SDK_DIR)/rp2_common/pico_btstack/include \
|
||||
$(SDK_DIR)/rp2_common/pico_cyw43_driver/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_flash/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_ticks/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_dma/include \
|
||||
$(SDK_DIR)/rp2_common/pico_bit_ops/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_clocks/include \
|
||||
$(SDK_DIR)/rp2_common/pico_unique_id/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_dcp/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_watchdog/include \
|
||||
$(SDK_DIR)/rp2_common/pico_rand/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_hazard3/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_uart/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_interp/include \
|
||||
$(SDK_DIR)/rp2_common/pico_printf/include \
|
||||
$(SDK_DIR)/rp2_common/pico_aon_timer/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_riscv_platform_timer/include \
|
||||
$(SDK_DIR)/rp2_common/pico_double/include \
|
||||
$(SDK_DIR)/rp2_common/pico_cyw43_arch/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_vreg/include \
|
||||
$(SDK_DIR)/rp2_common/pico_mbedtls/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_spi/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_rcp/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_riscv/include \
|
||||
$(SDK_DIR)/rp2_common/pico_standard_binary_info/include \
|
||||
$(SDK_DIR)/rp2_common/pico_i2c_slave/include \
|
||||
$(SDK_DIR)/rp2_common/pico_int64_ops/include \
|
||||
$(SDK_DIR)/rp2_common/pico_sha256/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_irq/include \
|
||||
$(SDK_DIR)/rp2_common/pico_divider/include \
|
||||
$(SDK_DIR)/rp2_common/pico_flash/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_sync/include \
|
||||
$(SDK_DIR)/rp2_common/pico_bootrom/include \
|
||||
$(SDK_DIR)/rp2_common/pico_crt0/include \
|
||||
$(SDK_DIR)/rp2_common/pico_clib_interface/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio/include \
|
||||
$(SDK_DIR)/rp2_common/pico_runtime/include \
|
||||
$(SDK_DIR)/rp2_common/pico_time_adapter/include \
|
||||
$(SDK_DIR)/rp2_common/pico_platform_panic/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_adc/include \
|
||||
$(SDK_DIR)/rp2_common/cmsis/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_pll/include \
|
||||
$(SDK_DIR)/rp2_common/pico_platform_sections/include \
|
||||
$(SDK_DIR)/rp2_common/boot_bootrom_headers/include \
|
||||
$(SDK_DIR)/rp2_common/pico_fix/include \
|
||||
$(SDK_DIR)/rp2_common/pico_lwip/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_base/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_xosc/include \
|
||||
$(SDK_DIR)/rp2_common/pico_async_context/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_pwm/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdio_semihosting/include \
|
||||
$(SDK_DIR)/rp2_common/pico_float/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_resets/include \
|
||||
$(SDK_DIR)/rp2_common/pico_cxx_options/include \
|
||||
$(SDK_DIR)/rp2_common/pico_stdlib/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_sha256/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_i2c/include \
|
||||
$(SDK_DIR)/rp2_common/pico_atomic/include \
|
||||
$(SDK_DIR)/rp2_common/pico_multicore/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_gpio/include \
|
||||
$(SDK_DIR)/rp2_common/pico_malloc/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_timer/include \
|
||||
$(SDK_DIR)/rp2_common/hardware_xip_cache/include \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(CMSIS_DIR)/Device/$(TARGET_MCU_LIB_UPPER)/Include \
|
||||
$(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/pico_platform/include \
|
||||
$(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/hardware_regs/include \
|
||||
$(SDK_DIR)/$(TARGET_MCU_LIB_LOWER)/hardware_structs/include \
|
||||
$(LIB_MAIN_DIR)/pico-sdk/lib/tinyusb/src
|
||||
|
||||
SYS_INCLUDE_DIRS += \
|
||||
$(SDK_DIR)/rp2350/boot_stage2/include
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mcmse -mfloat-abi=softfp
|
||||
ARCH_FLAGS += -DPICO_COPY_TO_RAM=$(RUN_FROM_RAM)
|
||||
|
||||
# Automatically treating constants as single-precision breaks pico-sdk (-Werror=double-promotion)
|
||||
# We should go through BF code and explicitly declare constants as single rather than double as required,
|
||||
# rather than relying on this flag.
|
||||
# ARCH_FLAGS += -fsingle-precision-constant
|
||||
|
||||
PICO_STDIO_USB_FLAGS = \
|
||||
-DLIB_PICO_PRINTF=1 \
|
||||
-DLIB_PICO_PRINTF_PICO=1 \
|
||||
-DLIB_PICO_STDIO=1 \
|
||||
-DLIB_PICO_STDIO_USB=1 \
|
||||
-DCFG_TUSB_DEBUG=0 \
|
||||
-DCFG_TUSB_MCU=OPT_MCU_RP2040 \
|
||||
-DCFG_TUSB_OS=OPT_OS_PICO \
|
||||
-DLIB_PICO_FIX_RP2040_USB_DEVICE_ENUMERATION=1 \
|
||||
-DPICO_RP2040_USB_DEVICE_UFRAME_FIX=1 \
|
||||
-DPICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS=3000 \
|
||||
-DLIB_PICO_UNIQUEID=1
|
||||
|
||||
PICO_STDIO_LD_FLAGS = \
|
||||
-Wl,--wrap=sprintf \
|
||||
-Wl,--wrap=snprintf \
|
||||
-Wl,--wrap=vsnprintf \
|
||||
-Wl,--wrap=printf \
|
||||
-Wl,--wrap=vprintf \
|
||||
-Wl,--wrap=puts \
|
||||
-Wl,--wrap=putchar \
|
||||
-Wl,--wrap=getchar
|
||||
|
||||
EXTRA_LD_FLAGS += $(PICO_STDIO_LD_FLAGS) $(PICO_TRACE_LD_FLAGS)
|
||||
|
||||
ifdef RP2350_TARGET
|
||||
|
||||
# Q. do we need LIB_BOOT_STAGE_2_HEADERS?
|
||||
# TODO review LIB_PICO options
|
||||
DEVICE_FLAGS += \
|
||||
-D$(RP2350_TARGET) \
|
||||
-DPICO_RP2350_A2_SUPPORTED=1 \
|
||||
-DLIB_BOOT_STAGE2_HEADERS=1 \
|
||||
-DLIB_PICO_ATOMIC=1 \
|
||||
-DLIB_PICO_BIT_OPS=1 \
|
||||
-DLIB_PICO_BIT_OPS_PICO=1 \
|
||||
-DLIB_PICO_CLIB_INTERFACE=1 \
|
||||
-DLIB_PICO_CRT0=1 \
|
||||
-DLIB_PICO_CXX_OPTIONS=1 \
|
||||
-DLIB_PICO_DIVIDER=1 \
|
||||
-DLIB_PICO_DIVIDER_COMPILER=1 \
|
||||
-DLIB_PICO_DOUBLE=1 \
|
||||
-DLIB_PICO_DOUBLE_PICO=1 \
|
||||
-DLIB_PICO_FLOAT=1 \
|
||||
-DLIB_PICO_FLOAT_PICO=1 \
|
||||
-DLIB_PICO_FLOAT_PICO_VFP=1 \
|
||||
-DLIB_PICO_INT64_OPS=1 \
|
||||
-DLIB_PICO_INT64_OPS_COMPILER=1 \
|
||||
-DLIB_PICO_MALLOC=1 \
|
||||
-DLIB_PICO_MEM_OPS=1 \
|
||||
-DLIB_PICO_MEM_OPS_COMPILER=1 \
|
||||
-DLIB_PICO_NEWLIB_INTERFACE=1 \
|
||||
-DLIB_PICO_PLATFORM=1 \
|
||||
-DLIB_PICO_PLATFORM_COMPILER=1 \
|
||||
-DLIB_PICO_PLATFORM_PANIC=1 \
|
||||
-DLIB_PICO_PLATFORM_SECTIONS=1 \
|
||||
-DLIB_PICO_PRINTF=1 \
|
||||
-DLIB_PICO_PRINTF_PICO=1 \
|
||||
-DLIB_PICO_RUNTIME=1 \
|
||||
-DLIB_PICO_RUNTIME_INIT=1 \
|
||||
-DLIB_PICO_STANDARD_BINARY_INFO=1 \
|
||||
-DLIB_PICO_STANDARD_LINK=1 \
|
||||
-DLIB_PICO_STDIO=1 \
|
||||
-DLIB_PICO_STDIO_UART=1 \
|
||||
-DLIB_PICO_STDLIB=1 \
|
||||
-DLIB_PICO_SYNC=1 \
|
||||
-DLIB_PICO_SYNC_CRITICAL_SECTION=1 \
|
||||
-DLIB_PICO_SYNC_MUTEX=1 \
|
||||
-DLIB_PICO_SYNC_SEM=1 \
|
||||
-DLIB_PICO_TIME=1 \
|
||||
-DLIB_PICO_TIME_ADAPTER=1 \
|
||||
-DLIB_PICO_UTIL=1 \
|
||||
-DPICO_32BIT=1 \
|
||||
-DPICO_BUILD=1 \
|
||||
-DPICO_CXX_ENABLE_EXCEPTIONS=0 \
|
||||
-DPICO_NO_FLASH=0 \
|
||||
-DPICO_NO_HARDWARE=0 \
|
||||
-DPICO_ON_DEVICE=1 \
|
||||
-DPICO_RP2350=1 \
|
||||
-DPICO_USE_BLOCKED_RAM=0
|
||||
|
||||
ifeq ($(RUN_FROM_RAM),1)
|
||||
LD_SCRIPT = $(LINKER_DIR)/pico_rp2350_RunFromRAM.ld
|
||||
else
|
||||
LD_SCRIPT = $(LINKER_DIR)/pico_rp2350_RunFromFLASH.ld
|
||||
endif
|
||||
|
||||
STARTUP_SRC = PICO/startup/bs2_default_padded_checksummed.S
|
||||
|
||||
# Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets.
|
||||
# Performance is only slightly affected but around 50 kB of flash are saved.
|
||||
OPTIMISE_SPEED = -O2
|
||||
|
||||
# TODO tidy up -
|
||||
# we might lose some/all of pico_stdio_*, pico_printf if not using PICO_TRACE
|
||||
PICO_LIB_SRC += \
|
||||
rp2_common/pico_stdio/stdio.c \
|
||||
rp2_common/pico_printf/printf.c
|
||||
|
||||
ifneq ($(PICO_TRACE),)
|
||||
PICO_LIB_SRC += \
|
||||
rp2_common/pico_stdio_uart/stdio_uart.c
|
||||
endif
|
||||
|
||||
# TODO review
|
||||
# rp2_common/pico_stdio_usb/stdio_usb.c \
|
||||
|
||||
PICO_STDIO_USB_SRC = \
|
||||
rp2_common/pico_stdio_usb/reset_interface.c \
|
||||
rp2_common/pico_fix/rp2040_usb_device_enumeration/rp2040_usb_device_enumeration.c \
|
||||
rp2_common/pico_bit_ops/bit_ops_aeabi.S \
|
||||
rp2_common/pico_stdio_usb/stdio_usb_descriptors.c
|
||||
|
||||
# TODO check
|
||||
# rp2_common/pico_stdio_usb/stdio_usb_descriptors.c \
|
||||
# vs PICO/usb/usb_descriptors.c
|
||||
|
||||
PICO_LIB_SRC += $(PICO_STDIO_USB_SRC)
|
||||
|
||||
# Work around https://github.com/raspberrypi/pico-sdk/issues/2451
|
||||
# by using system headers, which are more tolerant of macro redefinitions.
|
||||
|
||||
SYS_INCLUDE_DIRS += \
|
||||
$(SDK_DIR)/rp2_common/pico_fix/rp2040_usb_device_enumeration/include
|
||||
|
||||
# TODO use system_RP2350.c instead of writing into PICO/system.c
|
||||
# MCU_COMMON_SRC += \
|
||||
# system_RP2350.c
|
||||
|
||||
else
|
||||
$(error Unknown MCU for Raspberry PICO target)
|
||||
endif
|
||||
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO
|
||||
|
||||
DEVICE_FLAGS += $(PICO_STDIO_USB_FLAGS)
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/inverter.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/bus_spi_config.c \
|
||||
drivers/bus_i2c_utils.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/usb_io.c \
|
||||
drivers/dshot.c \
|
||||
PICO/bus_i2c_pico.c \
|
||||
PICO/bus_spi_pico.c \
|
||||
PICO/config_flash.c \
|
||||
PICO/debug_pico.c \
|
||||
PICO/dma_pico.c \
|
||||
PICO/dshot_pico.c \
|
||||
PICO/exti_pico.c \
|
||||
PICO/io_pico.c \
|
||||
PICO/persistent.c \
|
||||
PICO/pwm_pico.c \
|
||||
PICO/pwm_beeper_pico.c \
|
||||
PICO/serial_uart_pico.c \
|
||||
PICO/serial_usb_vcp_pico.c \
|
||||
PICO/system.c \
|
||||
PICO/usb/usb_cdc.c \
|
||||
PICO/multicore.c
|
||||
|
||||
DEVICE_STDPERIPH_SRC := \
|
||||
$(PICO_LIB_SRC) \
|
||||
$(STDPERIPH_SRC) \
|
||||
$(TINYUSB_SRC) \
|
||||
$(PICO_TRACE_SRC)
|
||||
|
||||
# Add a target-specific definition for PICO_LIB_TARGETS in order
|
||||
# to remove -flto=auto for pico-sdk file compilation
|
||||
# (to avoid problem of interaction with wrapping -Wl,wrap=...).
|
||||
# Place this at the end because we require PICO_LIB_TARGETS to be expanded before setting the target
|
||||
|
||||
PICO_LIB_OBJS = $(addsuffix .o, $(basename $(PICO_LIB_SRC)))
|
||||
PICO_LIB_OBJS += $(addsuffix .o, $(basename $(PICO_TRACE_SRC)))
|
||||
PICO_LIB_TARGETS := $(foreach pobj, $(PICO_LIB_OBJS), %/$(pobj))
|
||||
$(PICO_LIB_TARGETS): CC_DEFAULT_OPTIMISATION := $(PICO_LIB_OPTIMISATION)
|
132
src/platform/PICO/multicore.c
Normal file
132
src/platform/PICO/multicore.c
Normal file
|
@ -0,0 +1,132 @@
|
|||
/*
|
||||
* 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 "platform.h"
|
||||
#include "platform/multicore.h"
|
||||
#include "pico/multicore.h"
|
||||
#include "pico/util/queue.h"
|
||||
|
||||
#ifdef USE_MULTICORE
|
||||
|
||||
// Define a structure for the message we'll pass through the queue
|
||||
typedef struct {
|
||||
multicoreCommand_e command;
|
||||
core1_func_t *func;
|
||||
} core_message_t;
|
||||
|
||||
// Define the queue
|
||||
static queue_t core0_queue;
|
||||
static queue_t core1_queue;
|
||||
|
||||
static void core1_main(void)
|
||||
{
|
||||
// This loop is run on the second core
|
||||
while (true) {
|
||||
|
||||
core_message_t msg;
|
||||
queue_remove_blocking(&core1_queue, &msg);
|
||||
|
||||
switch (msg.command) {
|
||||
case MULTICORE_CMD_FUNC:
|
||||
if (msg.func) {
|
||||
msg.func();
|
||||
}
|
||||
break;
|
||||
case MULTICORE_CMD_FUNC_BLOCKING:
|
||||
if (msg.func) {
|
||||
msg.func();
|
||||
|
||||
// Send the result back to core0 (it will be blocking until this is done)
|
||||
bool result = true;
|
||||
queue_add_blocking(&core0_queue, &result);
|
||||
}
|
||||
break;
|
||||
case MULTICORE_CMD_STOP:
|
||||
multicore_reset_core1();
|
||||
return; // Exit the core1_main function
|
||||
default:
|
||||
// unknown command or none
|
||||
break;
|
||||
}
|
||||
|
||||
tight_loop_contents();
|
||||
}
|
||||
}
|
||||
|
||||
void multicoreStart(void)
|
||||
{
|
||||
// Initialize the queue with a size of 4 (to be determined based on expected load)
|
||||
queue_init(&core1_queue, sizeof(core_message_t), 4);
|
||||
|
||||
// Initialize the queue with a size of 1 (only needed for blocking results)
|
||||
queue_init(&core0_queue, sizeof(bool), 1);
|
||||
|
||||
// Start core 1
|
||||
multicore_launch_core1(core1_main);
|
||||
}
|
||||
|
||||
void multicoreStop(void)
|
||||
{
|
||||
core_message_t msg;
|
||||
msg.command = MULTICORE_CMD_STOP;
|
||||
msg.func = NULL;
|
||||
|
||||
queue_add_blocking(&core1_queue, &msg);
|
||||
}
|
||||
#endif // USE_MULTICORE
|
||||
|
||||
|
||||
void multicoreExecuteBlocking(core1_func_t *func)
|
||||
{
|
||||
#ifdef USE_MULTICORE
|
||||
core_message_t msg;
|
||||
msg.command = MULTICORE_CMD_FUNC_BLOCKING;
|
||||
msg.func = func;
|
||||
|
||||
bool result;
|
||||
|
||||
queue_add_blocking(&core1_queue, &msg);
|
||||
// Wait for the command to complete
|
||||
queue_remove_blocking(&core0_queue, &result);
|
||||
#else
|
||||
// If multicore is not used, execute the command directly
|
||||
if (func) {
|
||||
func();
|
||||
}
|
||||
#endif // USE_MULTICORE
|
||||
}
|
||||
|
||||
void multicoreExecute(core1_func_t *func)
|
||||
{
|
||||
#ifdef USE_MULTICORE
|
||||
core_message_t msg;
|
||||
msg.command = MULTICORE_CMD_FUNC;
|
||||
msg.func = func;
|
||||
|
||||
queue_add_blocking(&core1_queue, &msg);
|
||||
#else
|
||||
// If multicore is not used, execute the command directly
|
||||
if (func) {
|
||||
func();
|
||||
}
|
||||
#endif // USE_MULTICORE
|
||||
}
|
||||
|
170
src/platform/PICO/persistent.c
Normal file
170
src/platform/PICO/persistent.c
Normal file
|
@ -0,0 +1,170 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are 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.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
* An implementation of persistent data storage utilizing RTC backup data register.
|
||||
* Retains values written across software resets and some boot loader activities.
|
||||
* - won't retain if FLASH is wiped.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/persistent.h"
|
||||
|
||||
void persistentObjectInit(void)
|
||||
{
|
||||
// TODO implement
|
||||
}
|
||||
|
||||
uint32_t persistentObjectRead(persistentObjectId_e id)
|
||||
{
|
||||
UNUSED(id);
|
||||
// TODO implement
|
||||
return 0;
|
||||
}
|
||||
|
||||
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
|
||||
{
|
||||
UNUSED(id);
|
||||
UNUSED(value);
|
||||
// TODO implement
|
||||
}
|
||||
|
||||
#if 0
|
||||
for reference...
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#define PERSISTENT_OBJECT_MAGIC_VALUE (('B' << 24)|('e' << 16)|('f' << 8)|('1' << 0))
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
|
||||
uint32_t persistentObjectRead(persistentObjectId_e id)
|
||||
{
|
||||
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
|
||||
|
||||
uint32_t value = HAL_RTCEx_BKUPRead(&rtcHandle, id);
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
|
||||
{
|
||||
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
|
||||
|
||||
HAL_RTCEx_BKUPWrite(&rtcHandle, id, value);
|
||||
|
||||
#ifdef USE_SPRACING_PERSISTENT_RTC_WORKAROUND
|
||||
// Also write the persistent location used by the bootloader to support DFU etc.
|
||||
if (id == PERSISTENT_OBJECT_RESET_REASON) {
|
||||
// SPRACING firmware sometimes enters DFU mode when MSC mode is requested
|
||||
if (value == RESET_MSC_REQUEST) {
|
||||
value = RESET_NONE;
|
||||
}
|
||||
HAL_RTCEx_BKUPWrite(&rtcHandle, PERSISTENT_OBJECT_RESET_REASON_FWONLY, value);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void persistentObjectRTCEnable(void)
|
||||
{
|
||||
#if !defined(STM32G4)
|
||||
// G4 library V1.0.0 __HAL_RTC_WRITEPROTECTION_ENABLE/DISABLE macro does not use handle parameter
|
||||
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
|
||||
#endif
|
||||
|
||||
#if !defined(STM32H7)
|
||||
__HAL_RCC_PWR_CLK_ENABLE(); // Enable Access to PWR
|
||||
#endif
|
||||
|
||||
HAL_PWR_EnableBkUpAccess(); // Disable backup domain protection
|
||||
|
||||
#if defined(STM32G4)
|
||||
/* Enable RTC APB clock */
|
||||
__HAL_RCC_RTCAPB_CLK_ENABLE();
|
||||
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_RTC_ENABLE();
|
||||
|
||||
#else // !STM32G4, F7 and H7 case
|
||||
|
||||
#if defined(__HAL_RCC_RTC_CLK_ENABLE)
|
||||
// For those MCUs with RTCAPBEN bit in RCC clock enable register, turn it on.
|
||||
__HAL_RCC_RTC_CLK_ENABLE(); // Enable RTC module
|
||||
#endif
|
||||
|
||||
#endif // STM32G4
|
||||
|
||||
// We don't need a clock source for RTC itself. Skip it.
|
||||
|
||||
__HAL_RTC_WRITEPROTECTION_ENABLE(&rtcHandle); // Reset sequence
|
||||
__HAL_RTC_WRITEPROTECTION_DISABLE(&rtcHandle); // Apply sequence
|
||||
}
|
||||
|
||||
#else
|
||||
uint32_t persistentObjectRead(persistentObjectId_e id)
|
||||
{
|
||||
uint32_t value = RTC_ReadBackupRegister(id);
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
|
||||
{
|
||||
RTC_WriteBackupRegister(id, value);
|
||||
}
|
||||
|
||||
void persistentObjectRTCEnable(void)
|
||||
{
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); // Enable Access to PWR
|
||||
PWR_BackupAccessCmd(ENABLE); // Disable backup domain protection
|
||||
|
||||
// We don't need a clock source for RTC itself. Skip it.
|
||||
|
||||
RTC_WriteProtectionCmd(ENABLE); // Reset sequence
|
||||
RTC_WriteProtectionCmd(DISABLE); // Apply sequence
|
||||
}
|
||||
#endif
|
||||
|
||||
void persistentObjectInit(void)
|
||||
{
|
||||
// Configure and enable RTC for backup register access
|
||||
|
||||
persistentObjectRTCEnable();
|
||||
|
||||
// XXX Magic value checking may be sufficient
|
||||
|
||||
uint32_t wasSoftReset;
|
||||
|
||||
#ifdef STM32H7
|
||||
wasSoftReset = RCC->RSR & RCC_RSR_SFTRSTF;
|
||||
#else
|
||||
wasSoftReset = RCC->CSR & RCC_CSR_SFTRSTF;
|
||||
#endif
|
||||
|
||||
if (!wasSoftReset || (persistentObjectRead(PERSISTENT_OBJECT_MAGIC) != PERSISTENT_OBJECT_MAGIC_VALUE)) {
|
||||
for (int i = 1; i < PERSISTENT_OBJECT_COUNT; i++) {
|
||||
persistentObjectWrite(i, 0);
|
||||
}
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_MAGIC, PERSISTENT_OBJECT_MAGIC_VALUE);
|
||||
}
|
||||
}
|
||||
#endif
|
9
src/platform/PICO/pico/config_autogen.h
Normal file
9
src/platform/PICO/pico/config_autogen.h
Normal file
|
@ -0,0 +1,9 @@
|
|||
// AUTOGENERATED FROM PICO_CONFIG_HEADER_FILES and then PICO_<PLATFORM>_CONFIG_HEADER_FILES
|
||||
// DO NOT EDIT!
|
||||
|
||||
|
||||
// based on PICO_CONFIG_HEADER_FILES:
|
||||
|
||||
#include "cmsis/rename_exceptions.h"
|
||||
|
||||
// based on PICO_RP2350_ARM_S_CONFIG_HEADER_FILES:
|
19
src/platform/PICO/pico/version.h
Normal file
19
src/platform/PICO/pico/version.h
Normal file
|
@ -0,0 +1,19 @@
|
|||
/*
|
||||
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
|
||||
*
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
*/
|
||||
|
||||
// ---------------------------------------
|
||||
// THIS FILE IS AUTOGENERATED; DO NOT EDIT
|
||||
// ---------------------------------------
|
||||
|
||||
#ifndef _PICO_VERSION_H
|
||||
#define _PICO_VERSION_H
|
||||
|
||||
#define PICO_SDK_VERSION_MAJOR 2
|
||||
#define PICO_SDK_VERSION_MINOR 1
|
||||
#define PICO_SDK_VERSION_REVISION 0
|
||||
#define PICO_SDK_VERSION_STRING "2.1.0"
|
||||
|
||||
#endif
|
102
src/platform/PICO/pico_trace.c
Normal file
102
src/platform/PICO/pico_trace.c
Normal file
|
@ -0,0 +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();
|
||||
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 ""); \
|
||||
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(writeUnmodifiedConfigToEEPROM)
|
||||
TRACEboolvoid(resetEEPROM)
|
||||
TRACEvoidvoid(resetConfig)
|
||||
TRACEvoidvoid(pgResetAll)
|
||||
TRACEvoidbool(serialInit)
|
10
src/platform/PICO/pico_trace.h
Normal file
10
src/platform/PICO/pico_trace.h
Normal file
|
@ -0,0 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
extern void picotrace_prefix(void);
|
||||
|
||||
#define tprintf(fmt,...) do { \
|
||||
picotrace_prefix(); \
|
||||
stdio_printf(fmt, ## __VA_ARGS__); \
|
||||
stdio_printf("\n"); \
|
||||
} while (0)
|
||||
|
83
src/platform/PICO/pwm_beeper_pico.c
Normal file
83
src/platform/PICO/pwm_beeper_pico.c
Normal file
|
@ -0,0 +1,83 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_BEEPER) && defined(USE_PWM_OUTPUT)
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "hardware/gpio.h"
|
||||
#include "hardware/pwm.h"
|
||||
|
||||
static bool beeperConfigured;
|
||||
static bool beeperEnabled;
|
||||
static int beeperGPIO;
|
||||
static uint pwmSlice;
|
||||
|
||||
void pwmWriteBeeper(bool on)
|
||||
{
|
||||
if (beeperConfigured) {
|
||||
gpio_set_outover(beeperGPIO, on ? GPIO_OVERRIDE_NORMAL : GPIO_OVERRIDE_LOW);
|
||||
pwm_set_enabled(pwmSlice, on);
|
||||
beeperEnabled = on;
|
||||
}
|
||||
}
|
||||
|
||||
void pwmToggleBeeper(void)
|
||||
{
|
||||
pwmWriteBeeper(!beeperEnabled);
|
||||
}
|
||||
|
||||
void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
|
||||
{
|
||||
// frequency should be non-zero when calling beeperPwmInit.
|
||||
IO_t beeperIO = IOGetByTag(tag);
|
||||
if (beeperIO && frequency) {
|
||||
beeperGPIO = IO_GPIOPinIdx(beeperIO);
|
||||
IOInit(beeperIO, OWNER_BEEPER, 0);
|
||||
|
||||
// f = sysclk / div / wrap
|
||||
// Max clock divide is just under 256.
|
||||
uint16_t wrap;
|
||||
uint32_t clock_divide = (SystemCoreClock / frequency + 0xfffe) / 0xffff; // round up
|
||||
if (clock_divide > 255) {
|
||||
clock_divide = 255;
|
||||
wrap = 0xffff;
|
||||
} else {
|
||||
wrap = SystemCoreClock / frequency / clock_divide;
|
||||
}
|
||||
|
||||
pwm_config cfg = pwm_get_default_config();
|
||||
pwm_config_set_clkdiv_int(&cfg, clock_divide);
|
||||
pwm_config_set_wrap(&cfg, wrap);
|
||||
pwmSlice = pwm_gpio_to_slice_num(beeperGPIO);
|
||||
pwm_init(pwmSlice, &cfg, false);
|
||||
gpio_set_function(beeperGPIO, GPIO_FUNC_PWM);
|
||||
pwm_set_gpio_level(beeperGPIO, wrap >> 1); // 50% square wave
|
||||
beeperEnabled = false;
|
||||
beeperConfigured = true;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
217
src/platform/PICO/pwm_pico.c
Normal file
217
src/platform/PICO/pwm_pico.c
Normal file
|
@ -0,0 +1,217 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_PWM_OUTPUT
|
||||
|
||||
#include "build/debug.h"
|
||||
#include "build/debug_pin.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_output_impl.h"
|
||||
#include "drivers/motor_types.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "pg/motor.h"
|
||||
|
||||
#include "hardware/gpio.h"
|
||||
#include "hardware/pwm.h"
|
||||
#include "hardware/clocks.h"
|
||||
|
||||
typedef struct picoPwmMotors_s {
|
||||
uint16_t slice;
|
||||
uint16_t channel;
|
||||
} picoPwmMotors_t;
|
||||
|
||||
static picoPwmMotors_t picoPwmMotors[MAX_SUPPORTED_MOTORS];
|
||||
static bool useContinuousUpdate = false;
|
||||
|
||||
void pwmShutdownPulsesForAllMotors(void)
|
||||
{
|
||||
for (int index = 0; index < pwmMotorCount; index++) {
|
||||
pwm_set_chan_level(picoPwmMotors[index].slice, picoPwmMotors[index].channel, 0);
|
||||
}
|
||||
}
|
||||
|
||||
void pwmDisableMotors(void)
|
||||
{
|
||||
pwmShutdownPulsesForAllMotors();
|
||||
}
|
||||
|
||||
static void pwmWriteStandard(uint8_t index, float value)
|
||||
{
|
||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
||||
pwm_set_chan_level(picoPwmMotors[index].slice, picoPwmMotors[index].channel, lrintf((value * pwmMotors[index].pulseScale) + pwmMotors[index].pulseOffset));
|
||||
}
|
||||
|
||||
static void pwmCompleteMotorUpdate(void)
|
||||
{
|
||||
if (useContinuousUpdate) {
|
||||
return;
|
||||
}
|
||||
|
||||
for (int index = 0; index < pwmMotorCount; index++) {
|
||||
pwm_set_chan_level(picoPwmMotors[index].slice, picoPwmMotors[index].channel, 0);
|
||||
}
|
||||
}
|
||||
|
||||
static float pwmConvertFromExternal(uint16_t externalValue)
|
||||
{
|
||||
return (float)externalValue;
|
||||
}
|
||||
|
||||
static uint16_t pwmConvertToExternal(float motorValue)
|
||||
{
|
||||
return (uint16_t)motorValue;
|
||||
}
|
||||
|
||||
static motorVTable_t motorPwmVTable = {
|
||||
.postInit = NULL,
|
||||
.enable = pwmEnableMotors,
|
||||
.disable = pwmDisableMotors,
|
||||
.isMotorEnabled = pwmIsMotorEnabled,
|
||||
.shutdown = pwmShutdownPulsesForAllMotors,
|
||||
.convertExternalToMotor = pwmConvertFromExternal,
|
||||
.convertMotorToExternal = pwmConvertToExternal,
|
||||
.write = pwmWriteStandard,
|
||||
.decodeTelemetry = NULL,
|
||||
.updateComplete = pwmCompleteMotorUpdate,
|
||||
.requestTelemetry = NULL,
|
||||
.isMotorIdle = NULL,
|
||||
};
|
||||
|
||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||
{
|
||||
UNUSED(idlePulse);
|
||||
|
||||
if (!device) {
|
||||
return false;
|
||||
}
|
||||
|
||||
pwmMotorCount = device->count;
|
||||
|
||||
memset(pwmMotors, 0, sizeof(pwmMotors));
|
||||
|
||||
if (!device || !motorConfig) {
|
||||
return false;
|
||||
}
|
||||
|
||||
pwmMotorCount = device->count;
|
||||
device->vTable = &motorPwmVTable;
|
||||
|
||||
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
||||
|
||||
float sMin = 0;
|
||||
float sLen = 0;
|
||||
switch (motorConfig->motorProtocol) {
|
||||
default:
|
||||
case MOTOR_PROTOCOL_ONESHOT125:
|
||||
sMin = 125e-6f;
|
||||
sLen = 125e-6f;
|
||||
break;
|
||||
case MOTOR_PROTOCOL_ONESHOT42:
|
||||
sMin = 42e-6f;
|
||||
sLen = 42e-6f;
|
||||
break;
|
||||
case MOTOR_PROTOCOL_MULTISHOT:
|
||||
sMin = 5e-6f;
|
||||
sLen = 20e-6f;
|
||||
break;
|
||||
case MOTOR_PROTOCOL_BRUSHED:
|
||||
sMin = 0;
|
||||
useContinuousUpdate = true;
|
||||
break;
|
||||
case MOTOR_PROTOCOL_PWM :
|
||||
sMin = 1e-3f;
|
||||
sLen = 1e-3f;
|
||||
useContinuousUpdate = true;
|
||||
break;
|
||||
}
|
||||
|
||||
for (unsigned motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < pwmMotorCount; motorIndex++) {
|
||||
|
||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
||||
|
||||
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||
uint8_t pin = IO_PINBYTAG(tag);
|
||||
|
||||
const uint16_t slice = pwm_gpio_to_slice_num(pin);
|
||||
const uint16_t channel = pwm_gpio_to_channel(pin);
|
||||
|
||||
IOInit(pwmMotors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
picoPwmMotors[motorIndex].slice = slice;
|
||||
picoPwmMotors[motorIndex].channel = channel;
|
||||
|
||||
/* standard PWM outputs */
|
||||
// margin of safety is 4 periods when not continuous
|
||||
const unsigned pwmRateHz = useContinuousUpdate ? motorConfig->motorPwmRate : ceilf(1 / ((sMin + sLen) * 4));
|
||||
|
||||
/*
|
||||
PWM Frequency = clock / (interval * (wrap + 1))
|
||||
|
||||
Wrap is when the counter resets to zero.
|
||||
Interval (divider) will determine the resolution.
|
||||
*/
|
||||
const uint32_t clock = clock_get_hz(clk_sys); // PICO timer clock is the CPU clock.
|
||||
|
||||
/* used to find the desired timer frequency for max resolution */
|
||||
const unsigned prescaler = ceilf(clock / pwmRateHz); /* rounding up */
|
||||
const uint32_t hz = clock / prescaler;
|
||||
const unsigned period = useContinuousUpdate ? hz / pwmRateHz : 0xffff;
|
||||
|
||||
pwm_config config = pwm_get_default_config();
|
||||
|
||||
const uint8_t interval = (uint8_t)(clock / period);
|
||||
const uint8_t fraction = (uint8_t)(((clock / period) - interval) * (0x01 << 4));
|
||||
pwm_config_set_clkdiv_int_frac(&config, interval, fraction);
|
||||
pwm_config_set_wrap(&config, period);
|
||||
|
||||
gpio_set_function(pin, GPIO_FUNC_PWM);
|
||||
|
||||
pwm_set_chan_level(slice, channel, 0);
|
||||
pwm_init(slice, &config, true);
|
||||
|
||||
/*
|
||||
if brushed then it is the entire length of the period.
|
||||
TODO: this can be moved back to periodMin and periodLen
|
||||
once mixer outputs a 0..1 float value.
|
||||
*/
|
||||
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
pwmMotors[motorIndex].pulseOffset = (sMin * hz) - (pwmMotors[motorIndex].pulseScale * 1000);
|
||||
pwmMotors[motorIndex].enabled = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // USE_PWM_OUTPUT
|
407
src/platform/PICO/serial_uart_pico.c
Normal file
407
src/platform/PICO/serial_uart_pico.c
Normal file
|
@ -0,0 +1,407 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_UART
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_impl.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
|
||||
#include "hardware/uart.h"
|
||||
#include "hardware/irq.h"
|
||||
#include "platform/multicore.h"
|
||||
|
||||
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||
#ifdef USE_UART0
|
||||
{
|
||||
.identifier = SERIAL_PORT_UART0,
|
||||
.reg = uart0,
|
||||
.rxPins = {
|
||||
{ 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(PA31) },
|
||||
{ DEFIO_TAG_E(PA33) },
|
||||
{ DEFIO_TAG_E(PA35) },
|
||||
{ DEFIO_TAG_E(PA45) },
|
||||
{ DEFIO_TAG_E(PA47) },
|
||||
#endif
|
||||
},
|
||||
.txPins = {
|
||||
{ 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(PA30) },
|
||||
{ DEFIO_TAG_E(PA32) },
|
||||
{ DEFIO_TAG_E(PA34) },
|
||||
{ DEFIO_TAG_E(PA44) },
|
||||
{ DEFIO_TAG_E(PA46) },
|
||||
#endif
|
||||
},
|
||||
.irqn = UART0_IRQ,
|
||||
.txBuffer = uart0TxBuffer,
|
||||
.rxBuffer = uart0RxBuffer,
|
||||
.txBufferSize = sizeof(uart0TxBuffer),
|
||||
.rxBufferSize = sizeof(uart0RxBuffer),
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART1
|
||||
{
|
||||
.identifier = SERIAL_PORT_UART1,
|
||||
.reg = uart1,
|
||||
.rxPins = {
|
||||
{ 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(PA37) },
|
||||
{ DEFIO_TAG_E(PA39) },
|
||||
{ DEFIO_TAG_E(PA41) },
|
||||
{ DEFIO_TAG_E(PA43) },
|
||||
#endif
|
||||
},
|
||||
.txPins = {
|
||||
{ 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(PA36) },
|
||||
{ DEFIO_TAG_E(PA38) },
|
||||
{ DEFIO_TAG_E(PA40) },
|
||||
{ DEFIO_TAG_E(PA42) },
|
||||
#endif
|
||||
},
|
||||
.irqn = UART1_IRQ,
|
||||
.txBuffer = uart1TxBuffer,
|
||||
.rxBuffer = uart1RxBuffer,
|
||||
.txBufferSize = sizeof(uart1TxBuffer),
|
||||
.rxBufferSize = sizeof(uart1RxBuffer),
|
||||
},
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
void uartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
//// bprintf("uartIrqHandler");
|
||||
if ((uart_get_hw(s->USARTx)->imsc & (UART_UARTIMSC_RXIM_BITS | UART_UARTIMSC_RTIM_BITS)) != 0) {
|
||||
//bprintf("uartIrqHandler RX");
|
||||
while (uart_is_readable(s->USARTx)) {
|
||||
const uint8_t ch = uart_getc(s->USARTx);
|
||||
//bprintf("uartIrqHandler RX %x", ch);
|
||||
if (s->port.rxCallback) {
|
||||
s->port.rxCallback(ch, s->port.rxCallbackData);
|
||||
} else {
|
||||
bprintf("RX %x -> buffer",ch);
|
||||
s->port.rxBuffer[s->port.rxBufferHead] = ch;
|
||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if ((uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_TXIM_BITS) != 0) {
|
||||
/// bprintf("uartIrqHandler TX");
|
||||
#ifdef PICO_TRACE
|
||||
int c = s->port.txBufferTail - s->port.txBufferHead;
|
||||
#endif
|
||||
while (uart_is_writable(s->USARTx)) {
|
||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||
///bprintf("uartIrqHandler TX put %x", s->port.txBuffer[s->port.txBufferTail]);
|
||||
uart_putc(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||
} else {
|
||||
// TODO check, RX enabled based on mode?
|
||||
bprintf("uart done put %d, disabling tx interrupt",c);
|
||||
uart_set_irqs_enabled(s->USARTx, s->port.mode & MODE_RX, false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void on_uart0(void)
|
||||
{
|
||||
uartIrqHandler(&uartDevice[UARTDEV_0].port);
|
||||
}
|
||||
|
||||
static void on_uart1(void)
|
||||
{
|
||||
uartIrqHandler(&uartDevice[UARTDEV_1].port);
|
||||
}
|
||||
|
||||
static void uart0_irq_init(void)
|
||||
{
|
||||
irq_set_exclusive_handler(UART0_IRQ, on_uart0);
|
||||
irq_set_enabled(UART0_IRQ, true);
|
||||
}
|
||||
|
||||
static void uart1_irq_init(void)
|
||||
{
|
||||
irq_set_exclusive_handler(UART1_IRQ, on_uart1);
|
||||
irq_set_enabled(UART1_IRQ, true);
|
||||
}
|
||||
|
||||
uartPort_t *serialUART(uartDevice_t *uartdev, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
{
|
||||
UNUSED(options);
|
||||
|
||||
uartPort_t *s = &uartdev->port;
|
||||
|
||||
const uartHardware_t *hardware = uartdev->hardware;
|
||||
|
||||
s->port.vTable = uartVTable;
|
||||
s->port.baudRate = baudRate; // TODO set by caller?
|
||||
s->port.rxBuffer = hardware->rxBuffer;
|
||||
s->port.txBuffer = hardware->txBuffer;
|
||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||
s->port.txBufferSize = hardware->txBufferSize;
|
||||
|
||||
s->USARTx = hardware->reg;
|
||||
bprintf("====== setting USARTx to reg == %p", s->USARTx);
|
||||
|
||||
IO_t txIO = IOGetByTag(uartdev->tx.pin);
|
||||
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
||||
uint32_t txPin = IO_Pin(txIO);
|
||||
uint32_t rxPin = IO_Pin(rxIO);
|
||||
bprintf("serialUART retrieved recs tx,rx with pins %d, %d", txPin, rxPin);
|
||||
|
||||
const serialPortIdentifier_e identifier = s->port.identifier;
|
||||
|
||||
const int ownerIndex = serialOwnerIndex(identifier);
|
||||
const resourceOwner_e ownerTxRx = serialOwnerTxRx(identifier); // rx is always +1
|
||||
|
||||
if (txIO) {
|
||||
IOInit(txIO, ownerTxRx, ownerIndex);
|
||||
bprintf("gpio set function UART on tx pin %d", txPin);
|
||||
gpio_set_function(txPin, GPIO_FUNC_UART);
|
||||
}
|
||||
|
||||
if (rxIO) {
|
||||
IOInit(rxIO, ownerTxRx + 1, ownerIndex);
|
||||
gpio_set_function(rxPin, GPIO_FUNC_UART);
|
||||
gpio_set_pulls(rxPin, true, false); // Pull up
|
||||
}
|
||||
|
||||
if (!txIO && !rxIO) {
|
||||
bprintf("serialUART no pins mapped for device %p", s->USARTx);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bprintf("serialUART uart init %p baudrate %d", hardware->reg, baudRate);
|
||||
uart_init(hardware->reg, baudRate);
|
||||
|
||||
// TODO implement - use options here...
|
||||
uart_set_hw_flow(hardware->reg, false, false);
|
||||
uart_set_format(hardware->reg, 8, 1, UART_PARITY_NONE);
|
||||
|
||||
// TODO want fifos?
|
||||
//// uart_set_fifo_enabled(hardware->reg, false);
|
||||
uart_set_fifo_enabled(hardware->reg, true);
|
||||
|
||||
// Set up the IRQ handler for this UART
|
||||
if (hardware->irqn == UART0_IRQ) {
|
||||
multicoreExecuteBlocking(&uart0_irq_init);
|
||||
} else if (hardware->irqn == UART1_IRQ) {
|
||||
multicoreExecuteBlocking(&uart1_irq_init);
|
||||
}
|
||||
|
||||
// Don't enable any uart irq yet, wait until a call to uartReconfigure...
|
||||
// (with current code in serial_uart.c, this prevents irq callback before rxCallback has been set)
|
||||
UNUSED(mode); // TODO review serial_uart.c uartOpen()
|
||||
|
||||
return s;
|
||||
}
|
||||
|
||||
|
||||
// called from platform-specific uartReconfigure
|
||||
void uartConfigureExternalPinInversion(uartPort_t *uartPort)
|
||||
{
|
||||
#if !defined(USE_INVERTER)
|
||||
UNUSED(uartPort);
|
||||
#else
|
||||
const bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||
// TODO support INVERTER, not using enableInverter(= pin based)
|
||||
enableInverter(uartPort->port.identifier, inverted);
|
||||
#endif
|
||||
}
|
||||
|
||||
void uartEnableTxInterrupt(uartPort_t *uartPort)
|
||||
{
|
||||
// bprintf("uartEnableTxInterrupt");
|
||||
if (uartPort->port.txBufferTail == uartPort->port.txBufferHead) {
|
||||
return;
|
||||
}
|
||||
|
||||
// uart0TxBuffer has size 1024
|
||||
|
||||
#if 0
|
||||
bprintf("uartEnableTxInterrupt %d (head:0x%x, tail:0x%x)",
|
||||
uartPort->port.txBufferHead - uartPort->port.txBufferTail,
|
||||
uartPort->port.txBufferHead,
|
||||
uartPort->port.txBufferTail);
|
||||
bprintf("going to set interrupts for uart %p", uartPort->USARTx);
|
||||
#endif
|
||||
|
||||
// TODO Check: rx mask based on mode rather than RX interrupt pending?
|
||||
// uart_set_irqs_enabled(s->USARTx, uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_RXIM_BITS, true);
|
||||
uart_set_irqs_enabled(uartPort->USARTx, uartPort->port.mode & MODE_RX, true);
|
||||
}
|
||||
|
||||
#ifdef USE_DMA
|
||||
void uartTryStartTxDMA(uartPort_t *s)
|
||||
{
|
||||
UNUSED(s);
|
||||
//TODO: Implement
|
||||
}
|
||||
#endif
|
||||
|
||||
void uartReconfigure(uartPort_t *s)
|
||||
{
|
||||
uart_inst_t *uartInstance = s->USARTx;
|
||||
bprintf("uartReconfigure for port %p with USARTX %p", s, uartInstance);
|
||||
int achievedBaudrate = uart_init(uartInstance, s->port.baudRate);
|
||||
#ifdef PICO_TRACE
|
||||
bprintf("uartReconfigure h/w %p, requested baudRate %d, achieving %d", uartInstance, s->port.baudRate, achievedBaudrate);
|
||||
#else
|
||||
UNUSED(achievedBaudrate);
|
||||
#endif
|
||||
uart_set_format(uartInstance, 8, 1, UART_PARITY_NONE);
|
||||
|
||||
// TODO fifo or not to fifo?
|
||||
// uart_set_fifo_enabled(s->USARTx, false);
|
||||
uart_set_fifo_enabled(uartInstance, true);
|
||||
uartConfigureExternalPinInversion(s);
|
||||
uart_set_hw_flow(uartInstance, false, false);
|
||||
|
||||
// TODO would like to verify rx pin has been setup?
|
||||
// if ((s->mode & MODE_RX) && rxIO) {
|
||||
if (s->port.mode & MODE_RX) {
|
||||
bprintf("serialUART setting RX irq");
|
||||
uart_set_irqs_enabled(uartInstance, true, false);
|
||||
}
|
||||
|
||||
bprintf("uartReconfigure note port.mode = 0x%x", s->port.mode);
|
||||
// TODO should we care about MODE_TX ?
|
||||
|
||||
#if 0
|
||||
uint32_t uartFr = uart_get_hw(uartInstance)->fr;
|
||||
bprintf("uartReconfigure flag register 0x%x",uartFr);
|
||||
bprintf("uartReconfigure extra call to on_uart1");
|
||||
on_uart1();
|
||||
bprintf("put some in...");
|
||||
uart_putc(uartInstance, 'A');
|
||||
uart_putc(uartInstance, 'B');
|
||||
uart_putc(uartInstance, 'C');
|
||||
uartFr = uart_get_hw(uartInstance)->fr;
|
||||
bprintf("uartReconfigure flag register 0x%x",uartFr);
|
||||
bprintf("wait a mo");
|
||||
extern void delayMicroseconds(uint32_t);
|
||||
delayMicroseconds(123456);
|
||||
uartFr = uart_get_hw(uartInstance)->fr;
|
||||
bprintf("uartReconfigure flag register 0x%x",uartFr);
|
||||
bprintf("uartReconfigure extra special call to on_uart1");
|
||||
on_uart1();
|
||||
#endif
|
||||
}
|
||||
|
||||
// revert basic uartPinConfigure for PICO prior to updates for PIO UARTs
|
||||
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
||||
{
|
||||
bprintf("* uartPinConfigure");
|
||||
for (const uartHardware_t* hardware = uartHardware; hardware < ARRAYEND(uartHardware); hardware++) {
|
||||
const serialPortIdentifier_e identifier = hardware->identifier;
|
||||
uartDevice_t* uartdev = uartDeviceFromIdentifier(identifier);
|
||||
const int resourceIndex = serialResourceIndex(identifier);
|
||||
if (uartdev == NULL || resourceIndex < 0) {
|
||||
// malformed uartHardware
|
||||
bprintf("* uartPinConfigure %p malformed, uartdev %p, resourceIndex %d",hardware, uartdev, resourceIndex);
|
||||
continue;
|
||||
}
|
||||
const ioTag_t cfgRx = pSerialPinConfig->ioTagRx[resourceIndex];
|
||||
const ioTag_t cfgTx = pSerialPinConfig->ioTagTx[resourceIndex];
|
||||
bprintf("* uartPinConfigure hw = %p dev = %p, tags rx 0x%x, tx 0x%x", hardware, uartdev, cfgRx, cfgTx);
|
||||
|
||||
#if UART_TRAIT_PINSWAP
|
||||
bool swap = false;
|
||||
#endif
|
||||
for (unsigned pindex = 0; pindex < UARTHARDWARE_MAX_PINS; pindex++) {
|
||||
if (cfgRx && cfgRx == hardware->rxPins[pindex].pin) {
|
||||
uartdev->rx = hardware->rxPins[pindex];
|
||||
}
|
||||
|
||||
if (cfgTx && cfgTx == hardware->txPins[pindex].pin) {
|
||||
uartdev->tx = hardware->txPins[pindex];
|
||||
}
|
||||
#if UART_TRAIT_PINSWAP
|
||||
// Check for swapped pins
|
||||
if (cfgTx && cfgTx == hardware->rxPins[pindex].pin) {
|
||||
uartdev->tx = hardware->rxPins[pindex];
|
||||
swap = true;
|
||||
}
|
||||
|
||||
if (cfgRx && cfgRx == hardware->txPins[pindex].pin) {
|
||||
uartdev->rx = hardware->txPins[pindex];
|
||||
swap = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
if (uartdev->rx.pin || uartdev->tx.pin ) {
|
||||
uartdev->hardware = hardware;
|
||||
#if UART_TRAIT_PINSWAP
|
||||
uartdev->pinSwap = swap;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* USE_UART */
|
212
src/platform/PICO/serial_usb_vcp_pico.c
Normal file
212
src/platform/PICO/serial_usb_vcp_pico.c
Normal file
|
@ -0,0 +1,212 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_VCP
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "pg/usb.h"
|
||||
|
||||
#include "usb/usb_cdc.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_usb_vcp.h"
|
||||
#include "platform/multicore.h"
|
||||
|
||||
static vcpPort_t vcpPort = { 0 };
|
||||
|
||||
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||
{
|
||||
UNUSED(instance);
|
||||
UNUSED(baudRate);
|
||||
}
|
||||
|
||||
static void usbVcpSetMode(serialPort_t *instance, portMode_e mode)
|
||||
{
|
||||
UNUSED(instance);
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
static void usbVcpSetCtrlLineStateCb(serialPort_t *instance, void (*cb)(void *context, uint16_t ctrlLineState), void *context)
|
||||
{
|
||||
UNUSED(instance);
|
||||
UNUSED(cb);
|
||||
UNUSED(context);
|
||||
}
|
||||
|
||||
static void usbVcpSetBaudRateCb(serialPort_t *instance, void (*cb)(serialPort_t *context, uint32_t baud), serialPort_t *context)
|
||||
{
|
||||
UNUSED(instance);
|
||||
UNUSED(cb);
|
||||
UNUSED(context);
|
||||
}
|
||||
|
||||
static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return true;
|
||||
}
|
||||
|
||||
static uint32_t usbVcpRxBytesAvailable(const serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return cdc_usb_bytes_available();
|
||||
}
|
||||
|
||||
static uint8_t usbVcpRead(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
|
||||
uint8_t buf[1];
|
||||
|
||||
while (true) {
|
||||
if (cdc_usb_read(buf, 1)) {
|
||||
return buf[0];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void usbVcpWriteBuf(serialPort_t *instance, const void *data, int count)
|
||||
{
|
||||
UNUSED(instance);
|
||||
|
||||
if (!(cdc_usb_connected() && cdc_usb_configured())) {
|
||||
return;
|
||||
}
|
||||
|
||||
const uint8_t *p = data;
|
||||
while (count > 0) {
|
||||
int txed = cdc_usb_write(p, count);
|
||||
|
||||
if (txed <= 0) {
|
||||
break;
|
||||
}
|
||||
count -= txed;
|
||||
p += txed;
|
||||
}
|
||||
}
|
||||
|
||||
static bool usbVcpFlush(vcpPort_t *port)
|
||||
{
|
||||
uint32_t count = port->txAt;
|
||||
port->txAt = 0;
|
||||
|
||||
if (count == 0) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (!cdc_usb_connected() || !cdc_usb_configured()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint8_t *p = port->txBuf;
|
||||
while (count > 0) {
|
||||
int txed = cdc_usb_write(p, count);
|
||||
|
||||
if (txed <= 0) {
|
||||
break;
|
||||
}
|
||||
count -= txed;
|
||||
p += txed;
|
||||
}
|
||||
return count == 0;
|
||||
}
|
||||
|
||||
static void usbVcpWrite(serialPort_t *instance, uint8_t c)
|
||||
{
|
||||
vcpPort_t *port = container_of(instance, vcpPort_t, port);
|
||||
|
||||
port->txBuf[port->txAt++] = c;
|
||||
if (!port->buffering || port->txAt >= ARRAYLEN(port->txBuf)) {
|
||||
usbVcpFlush(port);
|
||||
}
|
||||
}
|
||||
|
||||
static void usbVcpBeginWrite(serialPort_t *instance)
|
||||
{
|
||||
vcpPort_t *port = container_of(instance, vcpPort_t, port);
|
||||
port->buffering = true;
|
||||
}
|
||||
|
||||
static uint32_t usbTxBytesFree(const serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return cdc_usb_tx_bytes_free();
|
||||
}
|
||||
|
||||
static void usbVcpEndWrite(serialPort_t *instance)
|
||||
{
|
||||
vcpPort_t *port = container_of(instance, vcpPort_t, port);
|
||||
port->buffering = false;
|
||||
usbVcpFlush(port);
|
||||
}
|
||||
|
||||
static const struct serialPortVTable usbVTable[] = {
|
||||
{
|
||||
.serialWrite = usbVcpWrite,
|
||||
.serialTotalRxWaiting = usbVcpRxBytesAvailable,
|
||||
.serialTotalTxFree = usbTxBytesFree,
|
||||
.serialRead = usbVcpRead,
|
||||
.serialSetBaudRate = usbVcpSetBaudRate,
|
||||
.isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty,
|
||||
.setMode = usbVcpSetMode,
|
||||
.setCtrlLineStateCb = usbVcpSetCtrlLineStateCb,
|
||||
.setBaudRateCb = usbVcpSetBaudRateCb,
|
||||
.writeBuf = usbVcpWriteBuf,
|
||||
.beginWrite = usbVcpBeginWrite,
|
||||
.endWrite = usbVcpEndWrite
|
||||
}
|
||||
};
|
||||
|
||||
serialPort_t *usbVcpOpen(void)
|
||||
{
|
||||
// initialise the USB CDC interface
|
||||
// potentially this could be done in a multicore task
|
||||
//multicoreExecuteBlocking(&cdc_usb_init);
|
||||
cdc_usb_init();
|
||||
|
||||
vcpPort_t *s = &vcpPort;
|
||||
s->port.vTable = usbVTable;
|
||||
return &s->port;
|
||||
}
|
||||
|
||||
uint32_t usbVcpGetBaudRate(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
return cdc_usb_baud_rate();
|
||||
}
|
||||
|
||||
uint8_t usbVcpIsConnected(void)
|
||||
{
|
||||
return cdc_usb_connected();
|
||||
}
|
||||
|
||||
#endif // USE_VCP
|
25
src/platform/PICO/startup/bs2_default_padded_checksummed.S
Normal file
25
src/platform/PICO/startup/bs2_default_padded_checksummed.S
Normal file
|
@ -0,0 +1,25 @@
|
|||
// Padded and checksummed version of: /home/black/src/pico/hello/build/pico-sdk/src/rp2350/boot_stage2/bs2_default.bin
|
||||
|
||||
.cpu cortex-m0plus
|
||||
.thumb
|
||||
|
||||
.section .boot2, "ax"
|
||||
|
||||
.global __boot2_entry_point
|
||||
__boot2_entry_point:
|
||||
.byte 0x00, 0xb5, 0x24, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x13, 0xf5, 0x40, 0x53, 0x02, 0x20, 0x98, 0x60
|
||||
.byte 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x13, 0xf5, 0x0d, 0x23, 0x1f, 0x49, 0x19, 0x60, 0x18, 0x68
|
||||
.byte 0x10, 0xf0, 0x02, 0x0f, 0xfb, 0xd1, 0x35, 0x20, 0x00, 0xf0, 0x2c, 0xf8, 0x02, 0x28, 0x14, 0xd0
|
||||
.byte 0x06, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x22, 0xf8, 0x98, 0x68, 0x01, 0x20, 0x58, 0x60, 0x00, 0x20
|
||||
.byte 0x58, 0x60, 0x02, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x19, 0xf8, 0x98, 0x68, 0x98, 0x68, 0x98, 0x68
|
||||
.byte 0x05, 0x20, 0x00, 0xf0, 0x17, 0xf8, 0x40, 0x08, 0xfa, 0xd2, 0x31, 0xf0, 0x01, 0x01, 0x19, 0x60
|
||||
.byte 0x0e, 0x48, 0xd8, 0x60, 0x4a, 0xf2, 0xeb, 0x00, 0x58, 0x61, 0x0d, 0x48, 0x18, 0x61, 0x4f, 0xf0
|
||||
.byte 0xa0, 0x51, 0x09, 0x78, 0x20, 0xf4, 0x80, 0x50, 0x18, 0x61, 0x00, 0xbd, 0x18, 0x68, 0x80, 0x08
|
||||
.byte 0xfc, 0xd2, 0x70, 0x47, 0x00, 0xb5, 0x58, 0x60, 0x58, 0x60, 0xff, 0xf7, 0xf7, 0xff, 0x98, 0x68
|
||||
.byte 0x98, 0x68, 0x00, 0xbd, 0x00, 0x00, 0x04, 0x40, 0x41, 0x00, 0x80, 0x07, 0x02, 0x02, 0x00, 0x40
|
||||
.byte 0xa8, 0x92, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
88
src/platform/PICO/stdio_pico_stub.c
Normal file
88
src/platform/PICO/stdio_pico_stub.c
Normal file
|
@ -0,0 +1,88 @@
|
|||
#if 0
|
||||
TODO remove this in favour of rp2_common/pico_clib_interface/newlib_interface.c
|
||||
/*
|
||||
* 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 "common/utils.h"
|
||||
|
||||
int _open(const char *fn, int oflag, ...)
|
||||
{
|
||||
UNUSED(fn);
|
||||
UNUSED(oflag);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _close(int fd)
|
||||
{
|
||||
UNUSED(fd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _lseek(int fd, int pos, int whence)
|
||||
{
|
||||
UNUSED(fd);
|
||||
UNUSED(pos);
|
||||
UNUSED(whence);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _fstat(int fd, char *buf)
|
||||
{
|
||||
UNUSED(fd);
|
||||
UNUSED(buf);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _isatty(int fd)
|
||||
{
|
||||
UNUSED(fd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _getpid(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
int _kill(int pid, int sig)
|
||||
{
|
||||
UNUSED(pid);
|
||||
UNUSED(sig);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _read(int handle, char *buffer, int length)
|
||||
{
|
||||
UNUSED(handle);
|
||||
UNUSED(buffer);
|
||||
UNUSED(length);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int _write(int handle, char *buffer, int length)
|
||||
{
|
||||
UNUSED(handle);
|
||||
UNUSED(buffer);
|
||||
UNUSED(length);
|
||||
return -1;
|
||||
}
|
||||
|
||||
#endif
|
249
src/platform/PICO/system.c
Normal file
249
src/platform/PICO/system.c
Normal file
|
@ -0,0 +1,249 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "platform/multicore.h"
|
||||
|
||||
#include "hardware/clocks.h"
|
||||
#include "hardware/timer.h"
|
||||
#include "hardware/watchdog.h"
|
||||
#include "pico/unique_id.h"
|
||||
|
||||
///////////////////////////////////////////////////
|
||||
|
||||
// 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)
|
||||
{
|
||||
SystemCoreClock = clock_get_hz(clk_sys);
|
||||
}
|
||||
|
||||
void __attribute__((constructor)) SystemInit (void)
|
||||
{
|
||||
SystemCoreClockUpdate();
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
bprintf("*** PICO systemReset ***");
|
||||
//TODO: check
|
||||
#if 1
|
||||
watchdog_reboot(0, 0, 0);
|
||||
#else
|
||||
// this might be fine
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t systemUniqueId[3] = { 0 };
|
||||
|
||||
// cycles per microsecond
|
||||
static uint32_t usTicks = 0;
|
||||
static float usTicksInv = 0.0f;
|
||||
|
||||
// These are defined in pico-sdk headers as volatile uint32_t types
|
||||
#define PICO_DWT_CTRL m33_hw->dwt_ctrl
|
||||
#define PICO_DWT_CYCCNT m33_hw->dwt_cyccnt
|
||||
#define PICO_DEMCR m33_hw->demcr
|
||||
|
||||
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);
|
||||
memcpy(&systemUniqueId, &id.id, MIN(sizeof(systemUniqueId), PICO_UNIQUE_BOARD_ID_SIZE_BYTES));
|
||||
|
||||
#ifdef USE_MULTICORE
|
||||
multicoreStart();
|
||||
#endif // USE_MULTICORE
|
||||
}
|
||||
|
||||
void systemResetToBootloader(bootloaderRequestType_e requestType)
|
||||
{
|
||||
UNUSED(requestType);
|
||||
//TODO: implement
|
||||
}
|
||||
|
||||
// Return system uptime in milliseconds (rollover in 49 days)
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return (uint32_t)(time_us_64() / 1000);
|
||||
}
|
||||
|
||||
// Return system uptime in micros (rollover in 71 mins)
|
||||
uint32_t micros(void)
|
||||
{
|
||||
return time_us_32();
|
||||
}
|
||||
|
||||
uint32_t microsISR(void)
|
||||
{
|
||||
return micros();
|
||||
}
|
||||
|
||||
void delayMicroseconds(uint32_t us)
|
||||
{
|
||||
sleep_us(us);
|
||||
}
|
||||
|
||||
void delay(uint32_t ms)
|
||||
{
|
||||
sleep_ms(ms);
|
||||
}
|
||||
|
||||
uint32_t getCycleCounter(void)
|
||||
{
|
||||
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)
|
||||
{
|
||||
return micros * usTicks;
|
||||
}
|
||||
|
||||
static void indicate(uint8_t count, uint16_t duration)
|
||||
{
|
||||
if (count) {
|
||||
LED1_ON;
|
||||
LED0_OFF;
|
||||
|
||||
while (count--) {
|
||||
LED1_TOGGLE;
|
||||
LED0_TOGGLE;
|
||||
BEEP_ON;
|
||||
delay(duration);
|
||||
|
||||
LED1_TOGGLE;
|
||||
LED0_TOGGLE;
|
||||
BEEP_OFF;
|
||||
delay(duration);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void indicateFailure(failureMode_e mode, int codeRepeatsRemaining)
|
||||
{
|
||||
while (codeRepeatsRemaining--) {
|
||||
indicate(WARNING_FLASH_COUNT, WARNING_FLASH_DURATION_MS);
|
||||
|
||||
delay(WARNING_PAUSE_DURATION_MS);
|
||||
|
||||
indicate(mode + 1, WARNING_CODE_DURATION_LONG_MS);
|
||||
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
void failureMode(failureMode_e mode)
|
||||
{
|
||||
indicateFailure(mode, 10);
|
||||
|
||||
#ifdef DEBUG
|
||||
systemReset();
|
||||
#else
|
||||
systemResetToBootloader(BOOTLOADER_REQUEST_ROM);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void unusedPinInit(IO_t io)
|
||||
{
|
||||
if (IOGetOwner(io) == OWNER_FREE) {
|
||||
IOConfigGPIO(io, 0);
|
||||
}
|
||||
}
|
||||
|
||||
void unusedPinsInit(void)
|
||||
{
|
||||
IOTraversePins(unusedPinInit);
|
||||
}
|
||||
|
||||
const mcuTypeInfo_t *getMcuTypeInfo(void)
|
||||
{
|
||||
static const mcuTypeInfo_t info = {
|
||||
#if defined(RP2350A)
|
||||
.id = MCU_TYPE_RP2350A, .name = "RP2350A"
|
||||
#elif defined(RP2350B)
|
||||
.id = MCU_TYPE_RP2350B, .name = "RP2350B"
|
||||
#else
|
||||
#error MCU Type info not defined for PICO / variant
|
||||
#endif
|
||||
};
|
||||
return &info;
|
||||
}
|
0
src/platform/PICO/target/RP2350A/.exclude
Normal file
0
src/platform/PICO/target/RP2350A/.exclude
Normal file
268
src/platform/PICO/target/RP2350A/target.h
Normal file
268
src/platform/PICO/target/RP2350A/target.h
Normal file
|
@ -0,0 +1,268 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#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)
|
||||
#include "pico_trace.h"
|
||||
#define bprintf tprintf
|
||||
//int __wrap_printf(const char * fmt, ...);
|
||||
//#define bprintf __wrap_printf
|
||||
#else
|
||||
#define bprintf(fmt,...)
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef RP2350A
|
||||
#define RP2350A
|
||||
#endif
|
||||
|
||||
#ifndef TARGET_BOARD_IDENTIFIER
|
||||
#define TARGET_BOARD_IDENTIFIER "235A"
|
||||
#endif
|
||||
|
||||
#ifndef USBD_PRODUCT_STRING
|
||||
#define USBD_PRODUCT_STRING "Betaflight RP2350A"
|
||||
// TODO
|
||||
#endif
|
||||
|
||||
#define USE_IO
|
||||
#define USE_UART0
|
||||
#define USE_UART1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_0
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_0
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
||||
// one of these ...
|
||||
// #define USE_SPI_DMA_ENABLE_EARLY
|
||||
#define USE_SPI_DMA_ENABLE_LATE
|
||||
|
||||
/* DMA Settings */
|
||||
//#undef USE_DMA
|
||||
#define DMA_IRQ_CORE_NUM 1 // Use core 1 for DMA IRQs
|
||||
#undef USE_DMA_SPEC // not yet required - possibly won't be used at all
|
||||
|
||||
#undef USE_SOFTSERIAL1
|
||||
#undef USE_SOFTSERIAL2
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#undef USE_TRANSPONDER
|
||||
#undef USE_FLASH
|
||||
#undef USE_FLASH_CHIP
|
||||
#undef USE_SDCARD
|
||||
|
||||
#undef USE_TIMER
|
||||
#undef USE_RCC
|
||||
|
||||
#undef USE_RX_PWM
|
||||
#undef USE_RX_PPM
|
||||
#undef USE_RX_SPI
|
||||
#undef USE_RX_CC2500
|
||||
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#undef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
#undef USE_MULTI_GYRO
|
||||
#undef USE_BARO
|
||||
#undef USE_SERIAL_PASSTHROUGH
|
||||
|
||||
#undef USE_RANGEFINDER_HCSR04
|
||||
#undef USE_CRSF
|
||||
#undef USE_TELEMETRY_CRSF
|
||||
#undef USE_RX_EXPRESSLRS
|
||||
#undef USE_MAX7456
|
||||
#undef USE_MAG
|
||||
#undef USE_MAG_HMC5883
|
||||
#undef USE_MAG_SPI_HMC5883
|
||||
#undef USE_VTX_RTC6705
|
||||
#undef USE_VTX_RTC6705_SOFTSPI
|
||||
#undef USE_RX_SX1280
|
||||
#undef USE_SRXL
|
||||
#undef USE_TELEMETRY
|
||||
#undef USE_OSD
|
||||
#undef USE_SPEKTRUM
|
||||
#undef USE_SPEKTRUM_BIND
|
||||
|
||||
#undef USE_MSP_UART
|
||||
#undef USE_MSP_DISPLAYPORT
|
||||
#undef USE_GPS
|
||||
#undef USE_GPS_UBLOX
|
||||
#undef USE_GPS_MTK
|
||||
#undef USE_GPS_NMEA
|
||||
#undef USE_GPS_SERIAL
|
||||
#undef USE_GPS_SONAR
|
||||
#undef USE_GPS_UBLOX7
|
||||
#undef USE_GPS_UBLOX8
|
||||
#undef USE_GPS_RESCUE
|
||||
|
||||
#undef USE_VTX
|
||||
#undef USE_VTX_TRAMP
|
||||
#undef USE_VTX_SMARTAUDIO
|
||||
#undef USE_SPEKTRUM_VTX_CONTROL
|
||||
#undef USE_VTX_COMMON
|
||||
#undef USE_FLASH
|
||||
#undef USE_FLASH_CHIP
|
||||
#undef USE_FLASH_M25P16
|
||||
#undef USE_FLASH_W25N01G
|
||||
#undef USE_FLASH_W25N02K
|
||||
#undef USE_FLASH_W25M
|
||||
#undef USE_FLASH_W25M512
|
||||
#undef USE_FLASH_W25M02G
|
||||
#undef USE_FLASH_W25Q128FV
|
||||
#undef USE_FLASH_PY25Q128HA
|
||||
#undef USE_FLASH_W25Q64FV
|
||||
|
||||
#undef USE_RPM_LIMIT
|
||||
|
||||
#undef USE_SERVOS
|
||||
#undef USE_LED_STRIP
|
||||
#undef USE_OSD
|
||||
#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
|
||||
#define CONFIG_IN_FLASH
|
||||
|
||||
// Pico flash writes are all aligned and in batches of FLASH_PAGE_SIZE (256)
|
||||
#define FLASH_CONFIG_STREAMER_BUFFER_SIZE FLASH_PAGE_SIZE
|
||||
#define FLASH_CONFIG_BUFFER_TYPE uint8_t
|
||||
|
||||
/* to be moved to a config file once target if working
|
||||
defaults as per Laurel board for now */
|
||||
|
||||
#define LED0_PIN PA25
|
||||
#undef LED1_PIN
|
||||
#undef LED2_PIN
|
||||
|
||||
// These pin selections are currently fairly arbitrary for RP2350A
|
||||
#define SPI0_SCK_PIN PA2
|
||||
#define SPI0_SDI_PIN PA4
|
||||
#define SPI0_SDO_PIN PA3
|
||||
|
||||
#define SPI1_SCK_PIN PA26
|
||||
#define SPI1_SDI_PIN PA24
|
||||
#define SPI1_SDO_PIN PA27
|
||||
|
||||
#define SDCARD_CS_PIN PA25
|
||||
#define FLASH_CS_PIN PA25
|
||||
#define MAX7456_SPI_CS_PIN PA17
|
||||
|
||||
#define GYRO_1_CS_PIN PA1
|
||||
#define GYRO_2_CS_PIN NONE
|
||||
|
||||
#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
|
||||
#define GYRO_1_SPI_INSTANCE SPI0
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_SPI_ICM42688P
|
||||
#define USE_ACC
|
||||
#define USE_ACC_SPI_ICM42688P
|
||||
//#define USE_FLASH
|
||||
//#define USE_FLASH_W25Q128FV
|
||||
//#define USE_MAX7456
|
||||
|
||||
/*
|
||||
|
||||
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 PA17
|
||||
|
||||
UART2_TX PA20
|
||||
UART2_RX PA21
|
||||
|
||||
GYRO_INT PA22
|
||||
|
||||
GYRO_CLK PA23
|
||||
|
||||
SPI1_CIPO PA24
|
||||
SPI1_CS PA25
|
||||
SPI1_SCLK PA26
|
||||
SPI1_COPI PA27
|
||||
|
||||
MOTOR1 PA28
|
||||
MOTOR2 PA29
|
||||
MOTOR3 PA30
|
||||
MOTOR4 PA31
|
||||
|
||||
SPARE1 PA32
|
||||
SPARE2 PA33
|
||||
|
||||
UART3_TX PA34
|
||||
UART3_RX PA35
|
||||
|
||||
DVTX_SBUS_RX PA36
|
||||
TELEM_RX PA37
|
||||
LED_STRIP PA38
|
||||
RGB_LED PA39
|
||||
|
||||
VBAT_SENSE PA40
|
||||
CURR_SENSE PA41
|
||||
ADC_SPARE PA42
|
||||
|
||||
I2C0_SDA PA44
|
||||
I2C0_SCL PA45
|
||||
|
||||
SPARE3 PA47
|
||||
|
||||
*/
|
||||
|
||||
#define SPIDEV_COUNT 2
|
||||
#define MAX_SPI_PIN_SEL 4
|
||||
|
||||
#define I2CDEV_COUNT 2
|
||||
#define MAX_I2C_PIN_SEL 4
|
||||
|
||||
#define UART_RX_BUFFER_SIZE 1024
|
||||
#define UART_TX_BUFFER_SIZE 1024
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 8
|
||||
#define UART_TRAIT_AF_PORT 1
|
||||
|
||||
#define I2CDEV_COUNT 2
|
30
src/platform/PICO/target/RP2350A/target.mk
Normal file
30
src/platform/PICO/target/RP2350A/target.mk
Normal file
|
@ -0,0 +1,30 @@
|
|||
TARGET_MCU := RP2350A
|
||||
TARGET_MCU_FAMILY := RP2350
|
||||
|
||||
MCU_FLASH_SIZE = 4096
|
||||
|
||||
DEVICE_FLAGS += -DPICO_RP2350A=1
|
||||
|
||||
# For pico-sdk, define flash-related attributes
|
||||
# 4194304 = 4 * 1024 * 1024
|
||||
DEVICE_FLAGS += \
|
||||
-DPICO_FLASH_SPI_CLKDIV=2 \
|
||||
-DPICO_FLASH_SIZE_BYTES=4194304 \
|
||||
-DPICO_BOOT_STAGE2_CHOOSE_W25Q080=1
|
||||
|
||||
# Define some default pins, so that we can debug/trace using pico_stdio (uart, usb)
|
||||
# or run some pico-examples programs.
|
||||
# These ones are suitable for a Pico2 board.
|
||||
DEVICE_FLAGS += \
|
||||
-DPICO_DEFAULT_UART=0 \
|
||||
-DPICO_DEFAULT_UART_TX_PIN=0 \
|
||||
-DPICO_DEFAULT_UART_RX_PIN=1 \
|
||||
-DPICO_DEFAULT_LED_PIN=25 \
|
||||
-DPICO_DEFAULT_I2C=0 \
|
||||
-DPICO_DEFAULT_I2C_SDA_PIN=4 \
|
||||
-DPICO_DEFAULT_I2C_SCL_PIN=5 \
|
||||
-DPICO_DEFAULT_SPI=0 \
|
||||
-DPICO_DEFAULT_SPI_SCK_PIN=18 \
|
||||
-DPICO_DEFAULT_SPI_TX_PIN=19 \
|
||||
-DPICO_DEFAULT_SPI_RX_PIN=16 \
|
||||
-DPICO_DEFAULT_SPI_CSN_PIN=17
|
0
src/platform/PICO/target/RP2350B/.exclude
Normal file
0
src/platform/PICO/target/RP2350B/.exclude
Normal file
364
src/platform/PICO/target/RP2350B/target.h
Normal file
364
src/platform/PICO/target/RP2350B/target.h
Normal file
|
@ -0,0 +1,364 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#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)
|
||||
#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
|
||||
|
||||
#ifndef TARGET_BOARD_IDENTIFIER
|
||||
#define TARGET_BOARD_IDENTIFIER "235B"
|
||||
#endif
|
||||
|
||||
#ifndef USBD_PRODUCT_STRING
|
||||
#define USBD_PRODUCT_STRING "Betaflight RP2350B"
|
||||
#endif
|
||||
|
||||
//#define USE_MULTICORE
|
||||
#define USE_IO
|
||||
#define USE_UART0
|
||||
#define USE_UART1
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_0
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_0
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
||||
// one of these ...
|
||||
// #define USE_SPI_DMA_ENABLE_EARLY
|
||||
#define USE_SPI_DMA_ENABLE_LATE
|
||||
|
||||
#undef USE_SOFTSERIAL1
|
||||
#undef USE_SOFTSERIAL2
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#undef USE_TRANSPONDER
|
||||
#undef USE_FLASH
|
||||
#undef USE_FLASH_CHIP
|
||||
#undef USE_SDCARD
|
||||
|
||||
#undef USE_TIMER
|
||||
#undef USE_RCC
|
||||
|
||||
//////////////////////////
|
||||
// Radio RX
|
||||
// TODO tidy up, introduce more possible options
|
||||
#undef USE_RX_SPI
|
||||
|
||||
#undef USE_RX_PWM
|
||||
#undef USE_RX_PPM
|
||||
#undef USE_RX_CC2500
|
||||
#undef USE_RX_EXPRESSLRS // <-- not this one, it's for SPI
|
||||
#undef USE_RX_SX1280 // no, it's for SPI
|
||||
|
||||
//#undef USE_CRSF <-- this one
|
||||
|
||||
// #undef USE_SERIALRX_CRSF // <-- this one
|
||||
#undef USE_SERIALRX_GHST
|
||||
#undef USE_SERIALRX_IBUS
|
||||
#undef USE_SERIALRX_JETIEXBUS
|
||||
#undef USE_SERIALRX_SBUS
|
||||
#undef USE_SERIALRX_SPEKTRUM
|
||||
#undef USE_SERIALRX_SUMD
|
||||
#undef USE_SERIALRX_SUMH
|
||||
#undef USE_SERIALRX_XBUS
|
||||
#undef USE_SERIALRX_FPORT
|
||||
|
||||
// TODO persistent objects -> crsfRxUpdateBaudRate -> crsf, telemetry
|
||||
//#undef USE_TELEMETRY_CRSF
|
||||
//#undef USE_TELEMETRY
|
||||
#undef USE_TELEMETRY_GHST
|
||||
#undef USE_TELEMETRY_FRSKY_HUB
|
||||
#undef USE_TELEMETRY_HOTT
|
||||
#undef USE_TELEMETRY_IBUS
|
||||
#undef USE_TELEMETRY_IBUS_EXTENDED
|
||||
#undef USE_TELEMETRY_JETIEXBUS
|
||||
#undef USE_TELEMETRY_LTM
|
||||
#undef USE_TELEMETRY_MAVLINK
|
||||
#undef USE_TELEMETRY_SMARTPORT
|
||||
#undef USE_TELEMETRY_SRXL
|
||||
|
||||
//////////////////////
|
||||
|
||||
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#undef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
#undef USE_MULTI_GYRO
|
||||
|
||||
#undef USE_RANGEFINDER_HCSR04
|
||||
#undef USE_MAX7456
|
||||
#undef USE_MAG
|
||||
#undef USE_MAG_HMC5883
|
||||
#undef USE_MAG_SPI_HMC5883
|
||||
#undef USE_VTX_RTC6705
|
||||
#undef USE_VTX_RTC6705_SOFTSPI
|
||||
#undef USE_SRXL
|
||||
#undef USE_OSD
|
||||
#undef USE_SPEKTRUM
|
||||
#undef USE_SPEKTRUM_BIND
|
||||
|
||||
// #undef USE_CLI
|
||||
#undef USE_SERIAL_PASSTHROUGH
|
||||
|
||||
// #undef USE_MSP
|
||||
#undef USE_MSP_UART
|
||||
#undef USE_MSP_DISPLAYPORT
|
||||
|
||||
/* DMA Settings */
|
||||
//#undef USE_DMA
|
||||
#define DMA_IRQ_CORE_NUM 1 // Use core 1 for DMA IRQs
|
||||
#undef USE_DMA_SPEC // not yet required - possibly won't be used at all
|
||||
|
||||
#undef USE_DSHOT_TELEMETRY
|
||||
#undef USE_ESC_SENSOR
|
||||
|
||||
#undef USE_PWM_OUTPUT
|
||||
|
||||
#undef USE_GPS
|
||||
#undef USE_GPS_UBLOX
|
||||
#undef USE_GPS_MTK
|
||||
#undef USE_GPS_NMEA
|
||||
#undef USE_GPS_SERIAL
|
||||
#undef USE_GPS_SONAR
|
||||
#undef USE_GPS_UBLOX7
|
||||
#undef USE_GPS_UBLOX8
|
||||
#undef USE_GPS_RESCUE
|
||||
|
||||
#undef USE_VTX
|
||||
#undef USE_VTX_TRAMP
|
||||
#undef USE_VTX_SMARTAUDIO
|
||||
#undef USE_SPEKTRUM_VTX_CONTROL
|
||||
#undef USE_VTX_COMMON
|
||||
#undef USE_FLASH
|
||||
#undef USE_FLASH_CHIP
|
||||
#undef USE_FLASH_M25P16
|
||||
#undef USE_FLASH_W25N01G
|
||||
#undef USE_FLASH_W25N02K
|
||||
#undef USE_FLASH_W25M
|
||||
#undef USE_FLASH_W25M512
|
||||
#undef USE_FLASH_W25M02G
|
||||
#undef USE_FLASH_W25Q128FV
|
||||
#undef USE_FLASH_PY25Q128HA
|
||||
#undef USE_FLASH_W25Q64FV
|
||||
|
||||
#undef USE_RPM_LIMIT
|
||||
|
||||
#undef USE_SERVOS
|
||||
#undef USE_LED_STRIP
|
||||
#undef USE_OSD
|
||||
#undef USE_OSD_SD
|
||||
#undef USE_OSD_HD
|
||||
#undef USE_OSD_QUICK_MENU
|
||||
#undef USE_POSITION_HOLD
|
||||
|
||||
//#define FLASH_PAGE_SIZE 0x1
|
||||
#define CONFIG_IN_FLASH
|
||||
|
||||
// Pico flash writes are all aligned and in batches of FLASH_PAGE_SIZE (256)
|
||||
#define FLASH_CONFIG_STREAMER_BUFFER_SIZE FLASH_PAGE_SIZE
|
||||
#define FLASH_CONFIG_BUFFER_TYPE uint8_t
|
||||
|
||||
// to be moved to a config file once target if working
|
||||
// defaults as per Laurel board for now
|
||||
|
||||
// Laurel to enable secondary voltage supplies from main battery
|
||||
#define PICO_BEC_5V_ENABLE_PIN PA14
|
||||
// Enable 9V if/when we need it (for DVTX?)
|
||||
// #define PICO_BEC_9V_ENABLE_PIN PA15
|
||||
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PWM_HZ 1971
|
||||
#define BEEPER_PIN PA5
|
||||
|
||||
//#undef USE_BARO
|
||||
#define USE_BARO_DPS310
|
||||
#undef USE_BARO_MS5611
|
||||
#undef USE_BARO_SPI_MS5611
|
||||
#undef USE_BARO_BMP280
|
||||
#undef USE_BARO_SPI_BMP280
|
||||
#undef USE_BARO_BMP388
|
||||
#undef USE_BARO_SPI_BMP388
|
||||
#undef USE_BARO_LPS
|
||||
#undef USE_BARO_SPI_LPS
|
||||
#undef USE_BARO_QMP6988
|
||||
#undef USE_BARO_SPI_QMP6988
|
||||
#undef USE_BARO_SPI_DPS310
|
||||
#undef USE_BARO_BMP085
|
||||
#undef USE_BARO_2SMBP_02B
|
||||
#undef USE_BARO_SPI_2SMBP_02B
|
||||
#undef USE_BARO_LPS22DF
|
||||
#undef USE_BARO_SPI_LPS22DF
|
||||
|
||||
#define BARO_I2C_INSTANCE I2CDEV_0
|
||||
#define I2C0_SDA_PIN PA44
|
||||
#define I2C0_SCL_PIN PA45
|
||||
|
||||
// PA20, PA21 on laurel are set aside for jumper to connect to Radio RX on UART2 (software PIO uart)
|
||||
// but let's assign them for h/w UART1 for now [UART1 TX at 20 and RX at 21 are available on RP2350]
|
||||
#define UART1_TX_PIN PA20
|
||||
#define UART1_RX_PIN PA21
|
||||
// [target.mk] Switch PICO_DEFAULT_UART to 0 and change PICO_DEFAULT_UART_TX,RX_PINs to 34, 35
|
||||
// which are available to UART0, and appear on spare UART connector J10
|
||||
|
||||
#define LED0_PIN PA6
|
||||
#define LED1_PIN PA7
|
||||
|
||||
#define SPI0_SCK_PIN PA2
|
||||
#define SPI0_SDI_PIN PA4
|
||||
#define SPI0_SDO_PIN PA3
|
||||
|
||||
#define SPI1_SCK_PIN PA26
|
||||
#define SPI1_SDI_PIN PA24
|
||||
#define SPI1_SDO_PIN PA27
|
||||
|
||||
#define SDCARD_CS_PIN PA25
|
||||
#define FLASH_CS_PIN PA25
|
||||
#define MAX7456_SPI_CS_PIN PA17
|
||||
|
||||
#define GYRO_1_CS_PIN PA1
|
||||
#define GYRO_1_EXTI_PIN PA22
|
||||
|
||||
#define GYRO_2_CS_PIN NONE
|
||||
|
||||
|
||||
#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
|
||||
#define GYRO_1_SPI_INSTANCE SPI0
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_SPI_ICM42688P
|
||||
#define USE_ACC
|
||||
#define USE_ACC_SPI_ICM42688P
|
||||
|
||||
#if 1 // TODO review
|
||||
#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 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 PA17
|
||||
|
||||
UART2_TX PA20
|
||||
UART2_RX PA21
|
||||
|
||||
GYRO_INT PA22
|
||||
|
||||
GYRO_CLK PA23
|
||||
|
||||
SPI1_CIPO PA24
|
||||
SPI1_CS PA25
|
||||
SPI1_SCLK PA26
|
||||
SPI1_COPI PA27
|
||||
|
||||
MOTOR1 PA28
|
||||
MOTOR2 PA29
|
||||
MOTOR3 PA30
|
||||
MOTOR4 PA31
|
||||
|
||||
SPARE1 PA32
|
||||
SPARE2 PA33
|
||||
|
||||
UART3_TX PA34
|
||||
UART3_RX PA35
|
||||
|
||||
DVTX_SBUS_RX PA36
|
||||
TELEM_RX PA37
|
||||
LED_STRIP PA38
|
||||
RGB_LED PA39
|
||||
|
||||
VBAT_SENSE PA40
|
||||
CURR_SENSE PA41
|
||||
ADC_SPARE PA42
|
||||
|
||||
I2C0_SDA PA44
|
||||
I2C0_SCL PA45
|
||||
|
||||
SPARE3 PA47
|
||||
|
||||
*/
|
||||
|
||||
#define SPIDEV_COUNT 2
|
||||
#define MAX_SPI_PIN_SEL 6
|
||||
|
||||
#define I2CDEV_COUNT 2
|
||||
|
||||
#define UART_RX_BUFFER_SIZE 1024
|
||||
#define UART_TX_BUFFER_SIZE 1024
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 12
|
||||
#define UART_TRAIT_AF_PORT 1
|
||||
|
||||
#define I2CDEV_COUNT 2
|
31
src/platform/PICO/target/RP2350B/target.mk
Normal file
31
src/platform/PICO/target/RP2350B/target.mk
Normal file
|
@ -0,0 +1,31 @@
|
|||
TARGET_MCU := RP2350B
|
||||
TARGET_MCU_FAMILY := RP2350
|
||||
|
||||
MCU_FLASH_SIZE = 8192
|
||||
|
||||
# In pico-sdk, PICO_RP2350A=0 means RP2350B family.
|
||||
DEVICE_FLAGS += -DPICO_RP2350A=0
|
||||
|
||||
# For pico-sdk, define flash-related attributes
|
||||
# 8388608 = 8 * 1024 * 1024
|
||||
DEVICE_FLAGS += \
|
||||
-DPICO_FLASH_SPI_CLKDIV=2 \
|
||||
-DPICO_FLASH_SIZE_BYTES=8388608 \
|
||||
-DPICO_BOOT_STAGE2_CHOOSE_W25Q080=1
|
||||
|
||||
# Define some default pins, so that we can debug/trace using pico_stdio (uart, usb)
|
||||
# or run some pico-examples programs.
|
||||
# These ones are suitable for a Laurel board, with UART1 for stdio.
|
||||
DEVICE_FLAGS += \
|
||||
-DPICO_DEFAULT_UART=0 \
|
||||
-DPICO_DEFAULT_UART_TX_PIN=34 \
|
||||
-DPICO_DEFAULT_UART_RX_PIN=35 \
|
||||
-DPICO_DEFAULT_LED_PIN=6 \
|
||||
-DPICO_DEFAULT_I2C=0 \
|
||||
-DPICO_DEFAULT_I2C_SDA_PIN=44 \
|
||||
-DPICO_DEFAULT_I2C_SCL_PIN=45 \
|
||||
-DPICO_DEFAULT_SPI=0 \
|
||||
-DPICO_DEFAULT_SPI_SCK_PIN=2 \
|
||||
-DPICO_DEFAULT_SPI_TX_PIN=3 \
|
||||
-DPICO_DEFAULT_SPI_RX_PIN=4 \
|
||||
-DPICO_DEFAULT_SPI_CSN_PIN=1
|
35
src/platform/PICO/usb/tusb_config.h
Normal file
35
src/platform/PICO/usb/tusb_config.h
Normal file
|
@ -0,0 +1,35 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define CFG_TUD_ENABLED 1
|
||||
#define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE
|
||||
#define CFG_TUD_CDC 1
|
||||
#define CFG_TUD_CDC_RX_BUFSIZE 256
|
||||
#define CFG_TUD_CDC_TX_BUFSIZE 256
|
||||
|
||||
#define TUP_DCD_EDPT_ISO_ALLOC
|
||||
#define TUP_DCD_ENDPOINT_MAX 16
|
||||
|
||||
#define TU_ATTR_FAST_FUNC __attribute__((section(".time_critical.tinyusb")))
|
||||
|
||||
#define CFG_TUSB_MCU OPT_MCU_RP2040
|
284
src/platform/PICO/usb/usb_cdc.c
Normal file
284
src/platform/PICO/usb/usb_cdc.c
Normal file
|
@ -0,0 +1,284 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
// TODO replace with stdio_usb from pico-sdk, with a few wrappers
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "tusb_config.h"
|
||||
|
||||
/*
|
||||
Make sure the tinyUSB common header includes don't
|
||||
bring in the poisoned sprintf, snprintf etc.
|
||||
*/
|
||||
#define _STDIO_H_
|
||||
|
||||
#include "tusb.h"
|
||||
#include "usb_cdc.h"
|
||||
|
||||
#include "pico/binary_info.h"
|
||||
#include "pico/time.h"
|
||||
#include "pico/mutex.h"
|
||||
#include "pico/critical_section.h"
|
||||
#include "hardware/irq.h"
|
||||
|
||||
#ifndef CDC_USB_TASK_INTERVAL_US
|
||||
#define CDC_USB_TASK_INTERVAL_US 1000
|
||||
#endif
|
||||
|
||||
#ifndef CDC_USB_WRITE_TIMEOUT_US
|
||||
#define CDC_USB_WRITE_TIMEOUT_US 1000
|
||||
#endif
|
||||
|
||||
#ifndef CDC_DEADLOCK_TIMEOUT_MS
|
||||
#define CDC_DEADLOCK_TIMEOUT_MS 1000
|
||||
#endif
|
||||
|
||||
#ifndef CDC_USB_BAUD_RATE
|
||||
#define CDC_USD_BAUD_RATE 115200
|
||||
#endif
|
||||
|
||||
static bool configured = false;
|
||||
static mutex_t cdc_usb_mutex;
|
||||
|
||||
// if this crit_sec is initialized, we are not in periodic timer mode, and must make sure
|
||||
// we don't either create multiple one shot timers, or miss creating one. this crit_sec
|
||||
// is used to protect the one_shot_timer_pending flag
|
||||
static critical_section_t one_shot_timer_crit_sec;
|
||||
static volatile bool one_shot_timer_pending;
|
||||
static uint8_t low_priority_irq_num;
|
||||
|
||||
static int64_t timer_task(alarm_id_t id, void *user_data)
|
||||
{
|
||||
UNUSED(id);
|
||||
UNUSED(user_data);
|
||||
|
||||
int64_t repeat_time;
|
||||
if (critical_section_is_initialized(&one_shot_timer_crit_sec)) {
|
||||
critical_section_enter_blocking(&one_shot_timer_crit_sec);
|
||||
one_shot_timer_pending = false;
|
||||
critical_section_exit(&one_shot_timer_crit_sec);
|
||||
repeat_time = 0; // don't repeat
|
||||
} else {
|
||||
repeat_time = CDC_USB_TASK_INTERVAL_US;
|
||||
}
|
||||
if (irq_is_enabled(low_priority_irq_num)) {
|
||||
irq_set_pending(low_priority_irq_num);
|
||||
return repeat_time;
|
||||
} else {
|
||||
return 0; // don't repeat
|
||||
}
|
||||
}
|
||||
|
||||
static void low_priority_worker_irq(void)
|
||||
{
|
||||
if (mutex_try_enter(&cdc_usb_mutex, NULL)) {
|
||||
tud_task();
|
||||
mutex_exit(&cdc_usb_mutex);
|
||||
} else {
|
||||
// if the mutex is already owned, then we are in non IRQ code in this file.
|
||||
//
|
||||
// it would seem simplest to just let that code call tud_task() at the end, however this
|
||||
// code might run during the call to tud_task() and we might miss a necessary tud_task() call
|
||||
//
|
||||
// if we are using a periodic timer (crit_sec is not initialized in this case),
|
||||
// then we are happy just to wait until the next tick, however when we are not using a periodic timer,
|
||||
// we must kick off a one-shot timer to make sure the tud_task() DOES run (this method
|
||||
// will be called again as a result, and will try the mutex_try_enter again, and if that fails
|
||||
// create another one shot timer again, and so on).
|
||||
if (critical_section_is_initialized(&one_shot_timer_crit_sec)) {
|
||||
bool need_timer;
|
||||
critical_section_enter_blocking(&one_shot_timer_crit_sec);
|
||||
need_timer = !one_shot_timer_pending;
|
||||
one_shot_timer_pending = true;
|
||||
critical_section_exit(&one_shot_timer_crit_sec);
|
||||
if (need_timer) {
|
||||
add_alarm_in_us(CDC_USB_TASK_INTERVAL_US, timer_task, NULL, true);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void usb_irq(void)
|
||||
{
|
||||
irq_set_pending(low_priority_irq_num);
|
||||
}
|
||||
|
||||
int cdc_usb_write(const uint8_t *buf, unsigned length)
|
||||
{
|
||||
static uint64_t last_avail_time;
|
||||
int written = 0;
|
||||
|
||||
if (!mutex_try_enter_block_until(&cdc_usb_mutex, make_timeout_time_ms(CDC_DEADLOCK_TIMEOUT_MS))) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (cdc_usb_connected()) {
|
||||
for (unsigned i = 0; i < length;) {
|
||||
unsigned n = length - i;
|
||||
uint32_t avail = tud_cdc_write_available();
|
||||
if (n > avail) n = avail;
|
||||
if (n) {
|
||||
uint32_t n2 = tud_cdc_write(buf + i, n);
|
||||
tud_task();
|
||||
tud_cdc_write_flush();
|
||||
i += n2;
|
||||
written = i;
|
||||
last_avail_time = time_us_64();
|
||||
} else {
|
||||
tud_task();
|
||||
tud_cdc_write_flush();
|
||||
if (!cdc_usb_connected() || (!tud_cdc_write_available() && time_us_64() > last_avail_time + CDC_USB_WRITE_TIMEOUT_US)) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// reset our timeout
|
||||
last_avail_time = 0;
|
||||
}
|
||||
mutex_exit(&cdc_usb_mutex);
|
||||
return written;
|
||||
}
|
||||
|
||||
void cdc_usb_write_flush(void)
|
||||
{
|
||||
if (!mutex_try_enter_block_until(&cdc_usb_mutex, make_timeout_time_ms(CDC_DEADLOCK_TIMEOUT_MS))) {
|
||||
return;
|
||||
}
|
||||
do {
|
||||
tud_task();
|
||||
} while (tud_cdc_write_flush());
|
||||
mutex_exit(&cdc_usb_mutex);
|
||||
}
|
||||
|
||||
int cdc_usb_read(uint8_t *buf, unsigned length)
|
||||
{
|
||||
// note we perform this check outside the lock, to try and prevent possible deadlock conditions
|
||||
// with printf in IRQs (which we will escape through timeouts elsewhere, but that would be less graceful).
|
||||
//
|
||||
// these are just checks of state, so we can call them while not holding the lock.
|
||||
// they may be wrong, but only if we are in the middle of a tud_task call, in which case at worst
|
||||
// we will mistakenly think we have data available when we do not (we will check again), or
|
||||
// tud_task will complete running and we will check the right values the next time.
|
||||
//
|
||||
int rc = PICO_ERROR_NO_DATA;
|
||||
if (cdc_usb_connected() && tud_cdc_available()) {
|
||||
if (!mutex_try_enter_block_until(&cdc_usb_mutex, make_timeout_time_ms(CDC_DEADLOCK_TIMEOUT_MS))) {
|
||||
return PICO_ERROR_NO_DATA; // would deadlock otherwise
|
||||
}
|
||||
if (cdc_usb_connected() && tud_cdc_available()) {
|
||||
uint32_t count = tud_cdc_read(buf, length);
|
||||
rc = count ? (int)count : PICO_ERROR_NO_DATA;
|
||||
} else {
|
||||
// because our mutex use may starve out the background task, run tud_task here (we own the mutex)
|
||||
tud_task();
|
||||
}
|
||||
mutex_exit(&cdc_usb_mutex);
|
||||
}
|
||||
return rc;
|
||||
}
|
||||
|
||||
void cdc_usb_init(void)
|
||||
{
|
||||
if (get_core_num() != alarm_pool_core_num(alarm_pool_get_default())) {
|
||||
// included an assertion here rather than just returning false, as this is likely
|
||||
// a coding bug, rather than anything else.
|
||||
assert(false);
|
||||
return;
|
||||
}
|
||||
|
||||
// initialize TinyUSB, as user hasn't explicitly linked it
|
||||
tusb_init();
|
||||
|
||||
if (!mutex_is_initialized(&cdc_usb_mutex)) {
|
||||
mutex_init(&cdc_usb_mutex);
|
||||
}
|
||||
bool rc = true;
|
||||
low_priority_irq_num = (uint8_t)user_irq_claim_unused(true);
|
||||
|
||||
irq_set_exclusive_handler(low_priority_irq_num, low_priority_worker_irq);
|
||||
irq_set_enabled(low_priority_irq_num, true);
|
||||
|
||||
if (irq_has_shared_handler(USBCTRL_IRQ)) {
|
||||
critical_section_init_with_lock_num(&one_shot_timer_crit_sec, spin_lock_claim_unused(true));
|
||||
// we can use a shared handler to notice when there may be work to do
|
||||
irq_add_shared_handler(USBCTRL_IRQ, usb_irq, PICO_SHARED_IRQ_HANDLER_LOWEST_ORDER_PRIORITY);
|
||||
} else {
|
||||
// we use initialization state of the one_shot_timer_critsec as a flag
|
||||
memset(&one_shot_timer_crit_sec, 0, sizeof(one_shot_timer_crit_sec));
|
||||
rc = add_alarm_in_us(CDC_USB_TASK_INTERVAL_US, timer_task, NULL, true) >= 0;
|
||||
}
|
||||
|
||||
configured = rc;
|
||||
}
|
||||
|
||||
bool cdc_usb_deinit(void)
|
||||
{
|
||||
if (get_core_num() != alarm_pool_core_num(alarm_pool_get_default())) {
|
||||
// included an assertion here rather than just returning false, as this is likely
|
||||
// a coding bug, rather than anything else.
|
||||
assert(false);
|
||||
return false;
|
||||
}
|
||||
|
||||
assert(tud_inited()); // we expect the caller to have initialized when calling sdio_usb_init
|
||||
|
||||
if (irq_has_shared_handler(USBCTRL_IRQ)) {
|
||||
spin_lock_unclaim(spin_lock_get_num(one_shot_timer_crit_sec.spin_lock));
|
||||
critical_section_deinit(&one_shot_timer_crit_sec);
|
||||
// we can use a shared handler to notice when there may be work to do
|
||||
irq_remove_handler(USBCTRL_IRQ, usb_irq);
|
||||
} else {
|
||||
// timer is disabled by disabling the irq
|
||||
}
|
||||
|
||||
irq_set_enabled(low_priority_irq_num, false);
|
||||
user_irq_unclaim(low_priority_irq_num);
|
||||
|
||||
configured = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool cdc_usb_configured(void)
|
||||
{
|
||||
return configured;
|
||||
}
|
||||
|
||||
bool cdc_usb_connected(void)
|
||||
{
|
||||
return tud_cdc_connected();
|
||||
}
|
||||
|
||||
bool cdc_usb_bytes_available(void)
|
||||
{
|
||||
return tud_cdc_available();
|
||||
}
|
||||
|
||||
uint32_t cdc_usb_baud_rate(void)
|
||||
{
|
||||
return CDC_USD_BAUD_RATE;
|
||||
}
|
||||
|
||||
uint32_t cdc_usb_tx_bytes_free(void)
|
||||
{
|
||||
return tud_cdc_write_available();
|
||||
}
|
38
src/platform/PICO/usb/usb_cdc.h
Normal file
38
src/platform/PICO/usb/usb_cdc.h
Normal file
|
@ -0,0 +1,38 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
void cdc_usb_write_flush(void);
|
||||
int cdc_usb_write(const uint8_t *buf, unsigned length);
|
||||
int cdc_usb_read(uint8_t *buf, unsigned length);
|
||||
void cdc_usb_init(void);
|
||||
bool cdc_usb_deinit(void);
|
||||
bool cdc_usb_configured(void);
|
||||
bool cdc_usb_connected(void);
|
||||
bool cdc_usb_bytes_available(void);
|
||||
uint32_t cdc_usb_baud_rate(void);
|
||||
uint32_t cdc_usb_tx_bytes_free(void);
|
0
src/platform/SIMULATOR/target/SITL/.exe
Normal file
0
src/platform/SIMULATOR/target/SITL/.exe
Normal file
|
@ -106,7 +106,7 @@ ifeq ($(TARGET_MCU),STM32F765xx)
|
|||
DEVICE_FLAGS += -DSTM32F765xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765.ld
|
||||
STARTUP_SRC = STM32/startup/startup_stm32f765xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
MCU_FLASH_SIZE := 2048
|
||||
else ifeq ($(TARGET_MCU),STM32F745xx)
|
||||
DEVICE_FLAGS += -DSTM32F745xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue