mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
PICO: UART for serial radio RX (#14442)
* PICO: work-in-progress serial_uart_pico and radio RX. * PICO systemReset. * RP2350B target changes for Laurel / uart / RadioRX / Gyro testing. * PICO extra in target.h for testing BARO on Laurel.
This commit is contained in:
parent
01ba378673
commit
093aebecc6
7 changed files with 404 additions and 66 deletions
|
@ -49,6 +49,25 @@ void IOInitGlobal(void)
|
|||
#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
|
||||
}
|
||||
|
||||
|
|
|
@ -349,8 +349,10 @@ 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/stdio_usb.c \
|
||||
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 \
|
||||
|
@ -391,19 +393,19 @@ MCU_COMMON_SRC = \
|
|||
drivers/serial_uart_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/pwm_pico.c \
|
||||
PICO/stdio_pico_stub.c \
|
||||
PICO/debug_pico.c \
|
||||
PICO/system.c \
|
||||
PICO/io_pico.c \
|
||||
PICO/bus_spi_pico.c \
|
||||
PICO/bus_i2c_pico.c \
|
||||
PICO/serial_uart_pico.c \
|
||||
PICO/exti_pico.c \
|
||||
PICO/config_flash.c \
|
||||
PICO/io_pico.c \
|
||||
PICO/persistent.c \
|
||||
PICO/pwm_pico.c \
|
||||
PICO/serial_uart_pico.c \
|
||||
PICO/serial_usb_vcp_pico.c \
|
||||
PICO/system.c \
|
||||
PICO/usb/usb_cdc.c
|
||||
|
||||
DEVICE_STDPERIPH_SRC := \
|
||||
|
|
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
|
|
@ -132,12 +132,16 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
|||
|
||||
void uartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
if ((uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_RXIM_BITS) != 0) {
|
||||
//// 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;
|
||||
}
|
||||
|
@ -145,12 +149,19 @@ void uartIrqHandler(uartPort_t *s)
|
|||
}
|
||||
|
||||
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 {
|
||||
uart_set_irqs_enabled(s->USARTx, true, false);
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
|
@ -176,52 +187,65 @@ uartPort_t *serialUART(uartDevice_t *uartdev, uint32_t baudRate, portMode_e mode
|
|||
const uartHardware_t *hardware = uartdev->hardware;
|
||||
|
||||
s->port.vTable = uartVTable;
|
||||
|
||||
s->port.baudRate = baudRate;
|
||||
|
||||
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
|
||||
|
||||
IOInit(txIO, ownerTxRx, ownerIndex);
|
||||
IOInit(rxIO, ownerTxRx, ownerIndex);
|
||||
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);
|
||||
|
||||
if ((mode & MODE_TX) && txIO) {
|
||||
IOInit(txIO, ownerTxRx, ownerIndex);
|
||||
gpio_set_function(IO_Pin(txIO), GPIO_FUNC_UART);
|
||||
}
|
||||
|
||||
if ((mode & MODE_RX) && rxIO) {
|
||||
IOInit(rxIO, ownerTxRx + 1, ownerIndex);
|
||||
gpio_set_function(IO_Pin(rxIO), GPIO_FUNC_UART);
|
||||
}
|
||||
|
||||
// TODO implement - use options here...
|
||||
uart_set_hw_flow(hardware->reg, false, false);
|
||||
uart_set_format(hardware->reg, 8, 1, UART_PARITY_NONE);
|
||||
uart_set_fifo_enabled(hardware->reg, false);
|
||||
|
||||
// TODO want fifos?
|
||||
//// uart_set_fifo_enabled(hardware->reg, false);
|
||||
uart_set_fifo_enabled(hardware->reg, true);
|
||||
|
||||
irq_set_exclusive_handler(hardware->irqn, hardware->irqn == UART0_IRQ ? on_uart0 : on_uart1);
|
||||
irq_set_enabled(hardware->irqn, true);
|
||||
if ((mode & MODE_RX) && rxIO) {
|
||||
uart_set_irqs_enabled(hardware->reg, true, false);
|
||||
}
|
||||
|
||||
// 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)
|
||||
{
|
||||
|
@ -229,31 +253,31 @@ void uartConfigureExternalPinInversion(uartPort_t *uartPort)
|
|||
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 uartTryStartTx(uartPort_t *s)
|
||||
{
|
||||
if (s->port.txBufferTail == s->port.txBufferHead) {
|
||||
return;
|
||||
}
|
||||
uart_set_irqs_enabled(s->USARTx, uart_get_hw(s->USARTx)->imsc & UART_UARTIMSC_RXIM_BITS, true);
|
||||
}
|
||||
|
||||
void uartReconfigure(uartPort_t *s)
|
||||
{
|
||||
uart_deinit(s->USARTx);
|
||||
uart_init(s->USARTx, s->port.baudRate);
|
||||
uart_set_format(s->USARTx, 8, 1, UART_PARITY_NONE);
|
||||
uart_set_fifo_enabled(s->USARTx, false);
|
||||
uartConfigureExternalPinInversion(s);
|
||||
}
|
||||
|
||||
void uartEnableTxInterrupt(uartPort_t *uartPort)
|
||||
{
|
||||
UNUSED(uartPort);
|
||||
//TODO: Implement
|
||||
// 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
|
||||
|
@ -264,4 +288,53 @@ void uartTryStartTxDMA(uartPort_t *s)
|
|||
}
|
||||
#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
|
||||
}
|
||||
|
||||
#endif /* USE_UART */
|
||||
|
|
|
@ -30,8 +30,9 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "hardware/timer.h"
|
||||
#include "hardware/clocks.h"
|
||||
#include "hardware/timer.h"
|
||||
#include "hardware/watchdog.h"
|
||||
#include "pico/unique_id.h"
|
||||
|
||||
///////////////////////////////////////////////////
|
||||
|
@ -55,7 +56,15 @@ void __attribute__((constructor)) SystemInit (void)
|
|||
|
||||
void systemReset(void)
|
||||
{
|
||||
//TODO: implement
|
||||
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 };
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#define USBD_PRODUCT_STRING "Betaflight RP2350B"
|
||||
#endif
|
||||
|
||||
|
||||
#define USE_IO
|
||||
#define USE_UART0
|
||||
#define USE_UART1
|
||||
|
@ -74,29 +75,59 @@
|
|||
#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_SPI
|
||||
#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_BARO
|
||||
|
||||
#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
|
||||
|
@ -162,8 +193,43 @@
|
|||
#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 */
|
||||
// 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
|
||||
|
||||
//#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
|
||||
|
@ -205,7 +271,7 @@
|
|||
#define USE_ACC
|
||||
#define USE_ACC_SPI_ICM42688P
|
||||
|
||||
#ifdef GYRO_ONLY_ICM42688
|
||||
#if 1 // TODO review
|
||||
#undef USE_ACCGYRO_LSM6DSV16X
|
||||
#undef USE_GYRO_SPI_ICM20689
|
||||
#undef USE_GYRO_SPI_MPU6000
|
||||
|
@ -281,7 +347,6 @@ SPARE3 PA47
|
|||
#define MAX_SPI_PIN_SEL 6
|
||||
|
||||
#define I2CDEV_COUNT 2
|
||||
#define MAX_I2C_PIN_SEL 6
|
||||
|
||||
#define UART_RX_BUFFER_SIZE 1024
|
||||
#define UART_TX_BUFFER_SIZE 1024
|
||||
|
|
|
@ -17,9 +17,9 @@ DEVICE_FLAGS += \
|
|||
# or run some pico-examples programs.
|
||||
# These ones are suitable for a Laurel board, with UART1 for stdio.
|
||||
DEVICE_FLAGS += \
|
||||
-DPICO_DEFAULT_UART=1 \
|
||||
-DPICO_DEFAULT_UART_TX_PIN=8 \
|
||||
-DPICO_DEFAULT_UART_RX_PIN=9 \
|
||||
-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 \
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue