mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
PICO: Update platform and target setup
- add a misc_todo.c stub file to manage what needs to be done / rectified.
This commit is contained in:
parent
f80df5c3d9
commit
610207eb2c
4 changed files with 109 additions and 10 deletions
73
src/platform/PICO/misc_todo.c
Normal file
73
src/platform/PICO/misc_todo.c
Normal file
|
@ -0,0 +1,73 @@
|
|||
#include "drivers/bus_spi.h"
|
||||
|
||||
void spiPinConfigure(const struct spiPinConfig_s *pConfig)
|
||||
{
|
||||
UNUSED(pConfig);
|
||||
}
|
||||
|
||||
void debugInit(void)
|
||||
{
|
||||
// NOOP
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
|
@ -14,7 +14,6 @@ CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS
|
|||
#STDPERIPH
|
||||
STDPERIPH_DIR := $(SDK_DIR)/rp2_common
|
||||
STDPERIPH_SRC := \
|
||||
pico_clib_interface/newlib_interface.c \
|
||||
hardware_sync_spin_lock/sync_spin_lock.c \
|
||||
hardware_gpio/gpio.c \
|
||||
pico_stdio/stdio.c \
|
||||
|
@ -28,7 +27,8 @@ STDPERIPH_SRC := \
|
|||
hardware_adc/adc.c \
|
||||
hardware_pio/pio.c \
|
||||
hardware_watchdog/watchdog.c \
|
||||
hardware_flash/flash.c
|
||||
hardware_flash/flash.c \
|
||||
pico_unique_id/unique_id.c
|
||||
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)
|
||||
|
||||
|
@ -180,10 +180,15 @@ MCU_COMMON_SRC = \
|
|||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/inverter.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/bus_spi_config.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/serial_uart_pinconfig.c \
|
||||
PICO/misc_todo.c \
|
||||
PICO/system.c \
|
||||
PICO/io_pico.c \
|
||||
PICO/bus_spi_pico.c \
|
||||
PICO/serial_uart_pico.c \
|
||||
PICO/exti_pico.c \
|
||||
PICO/config_flash.c
|
||||
|
||||
DEVICE_FLAGS +=
|
||||
|
|
|
@ -54,7 +54,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
|||
#define DMA_TypeDef void*
|
||||
//#define DMA_InitTypeDef
|
||||
//#define DMA_Channel_TypeDef
|
||||
#define SPI_TypeDef spi_inst_t
|
||||
#define SPI_TypeDef SPI0_Type
|
||||
#define ADC_TypeDef void*
|
||||
#define USART_TypeDef uart_inst_t
|
||||
#define TIM_OCInitTypeDef void*
|
||||
|
@ -99,3 +99,5 @@ extern uint32_t systemUniqueId[3];
|
|||
#define U_ID_1 (systemUniqueId[1])
|
||||
#define U_ID_2 (systemUniqueId[2])
|
||||
|
||||
#define UART_TX_BUFFER_ATTRIBUTE
|
||||
#define UART_RX_BUFFER_ATTRIBUTE
|
||||
|
|
|
@ -37,10 +37,10 @@
|
|||
#define USE_UART0
|
||||
#define USE_UART1
|
||||
|
||||
//#define USE_SPI
|
||||
//#define USE_SPI_DEVICE_0
|
||||
//#define USE_SPI_DEVICE_1
|
||||
#undef USE_SPI
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_0
|
||||
#define USE_SPI_DEVICE_1
|
||||
//#undef USE_SPI
|
||||
|
||||
#undef USE_SOFTSERIAL1
|
||||
#undef USE_SOFTSERIAL2
|
||||
|
@ -70,8 +70,6 @@
|
|||
#undef USE_MULTI_GYRO
|
||||
#undef USE_BARO
|
||||
|
||||
|
||||
|
||||
#undef USE_RANGEFINDER_HCSR04
|
||||
#undef USE_CRSF
|
||||
#undef USE_TELEMETRY_CRSF
|
||||
|
@ -117,6 +115,18 @@
|
|||
#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
|
||||
|
||||
|
@ -144,7 +154,7 @@
|
|||
|
||||
#define MAX7456_SPI_INSTANCE SPI1
|
||||
#define SDCARD_SPI_INSTANCE SPI1
|
||||
//#define GYRO_1_SPI_INSTANCE SPI0
|
||||
#define GYRO_1_SPI_INSTANCE SPI0
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_SPI_ICM42688P
|
||||
|
@ -210,3 +220,12 @@ I2C0_SCL P45
|
|||
SPARE3 P47
|
||||
|
||||
*/
|
||||
|
||||
#define SPIDEV_COUNT 2
|
||||
#define UART_RX_BUFFER_SIZE 1024
|
||||
#define UART_TX_BUFFER_SIZE 1024
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#define UART_TRAIT_AF_PORT 1
|
||||
|
||||
#define MAX_SPI_PIN_SEL 4
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue