Support for Raspberry PI RP2040 MCU (#18083)

This commit is contained in:
Vatsal Asitkumar Joshi
2021-11-03 11:14:30 -05:00
committed by GitHub
parent 8f6fd5f37b
commit ea1ae73526
60 changed files with 5725 additions and 1 deletions
+1
View File
@@ -79,6 +79,7 @@ pipeline {
"nxp_ucans32k146_canbootloader",
"nxp_ucans32k146_default",
"omnibus_f4sd_default",
"raspberrypi_pico_default",
"px4_fmu-v2_default",
"px4_fmu-v2_fixedwing",
"px4_fmu-v2_multicopter",
+1
View File
@@ -48,6 +48,7 @@ jobs:
nxp_fmurt1062-v1,
nxp_ucans32k146,
omnibus_f4sd,
raspberrypi_pico,
px4_fmu-v2,
px4_fmu-v3,
px4_fmu-v4,
+5
View File
@@ -221,3 +221,8 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: nxp_fmuk66-v3_default
raspberrypi_pico_default:
short: raspberrypi_pico
buildType: MinSizeRel
settings:
CONFIG: raspberrypi_pico_default
+2 -1
View File
@@ -136,5 +136,6 @@
"workbench.settings.enableNaturalLanguageSearch": false,
"yaml.schemas": {
"${workspaceFolder}/validation/module_schema.yaml": "${workspaceFolder}/src/modules/*/module.yaml"
}
},
"cortex-debug.openocdPath": "${env:PICO_SDK_PATH}/../openocd/src/openocd" // Added for rp2040
}
+52
View File
@@ -0,0 +1,52 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m0plus"
CONFIG_BOARD_CONSTRAINED_FLASH=y
CONFIG_BOARD_CONSTRAINED_MEMORY=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP280=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_ESC_CALIB=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
@@ -0,0 +1,13 @@
{
"board_id": 42,
"magic": "RASPBERRYPIPICO",
"description": "Firmware for the raspberry pi Pico board",
"image": "",
"build_time": 0,
"summary": "RaspberrypiPico",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1032192,
"git_identity": "",
"board_revision": 0
}
@@ -0,0 +1,18 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281
# Disable safety switch by default
param set-default CBRK_IO_SAFETY 22027
# use the Q attitude estimator, it works w/o mag or GPS.
# param set-default SYS_MC_EST_GROUP 3
# param set-default ATT_ACC_COMP 0
# param set-default ATT_W_ACC 0.4000
# param set-default ATT_W_GYRO_BIAS 0.0000
# param set-default SYS_HAS_MAG 0
@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific MAVLink startup script.
#------------------------------------------------------------------------------
# Start MAVLink on the USB port
mavlink start -d /dev/ttyACM0
@@ -0,0 +1,12 @@
#!/bin/sh
#
# board specific sensors init
#------------------------------------------------------------------------------
board_adc start
# try starting an mpu9250 IMU on external SPI
mpu9250 start -S
# try starting a bmp280 barometer on external SPI
bmp280 start -S
@@ -0,0 +1,25 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
config RP2040_FLASH_BOOT
bool "flash boot"
default y
---help---
If y, the built binary can be used for flash boot.
If not, the binary is for SRAM boot.
config RP2040_FLASH_CHIP
string "flash chip name"
default "w25q080"
---help---
Name of NOR flash device connected to RP2040 SoC.
(Used to choose the secondary boot loader.)
Basically this option should not be changed.
config RP2040_UF2_BINARY
bool "uf2 binary format"
default y
---help---
Create nuttx.uf2 binary format used on RP2040 based arch.
@@ -0,0 +1,129 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_BOARD_BOARD_H
#define __ARCH_BOARD_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
/* Clocking *****************************************************************/
#define MHZ 1000000
#define BOARD_XOSC_FREQ (12 * MHZ)
#define BOARD_PLL_SYS_FREQ (125 * MHZ)
#define BOARD_PLL_USB_FREQ (48 * MHZ)
#define BOARD_REF_FREQ (12 * MHZ)
#define BOARD_SYS_FREQ (125 * MHZ)
#define BOARD_PERI_FREQ (125 * MHZ)
#define BOARD_USB_FREQ (48 * MHZ)
#define BOARD_ADC_FREQ (48 * MHZ)
#define BOARD_RTC_FREQ 46875
#define BOARD_UART_BASEFREQ BOARD_PERI_FREQ
#define BOARD_TICK_CLOCK (1 * MHZ)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the
* omnibusf4sd. The following definitions describe how NuttX controls the LEDs:
*/
// #define LED_STARTED 0 /* LED1 */
// #define LED_HEAPALLOCATE 1 /* LED2 */
// #define LED_IRQSENABLED 2 /* LED1 */
// #define LED_STACKCREATED 3 /* LED1 + LED2 */
// #define LED_INIRQ 4 /* LED1 */
// #define LED_SIGNAL 5 /* LED2 */
// #define LED_ASSERTION 6 /* LED1 + LED2 */
// #define LED_PANIC 7 /* LED1 + LED2 */
/* Alternate function pin selections ************************************************/
/*
* UARTs.
* UART0TX: GPIO0
* UART0RX: GPIO1
* UART1TX: GPIO8
* UART1RX: GPIO9
*/
#define CONFIG_RP2040_UART0_GPIO 0 /* TELEM */
#define CONFIG_RP2040_UART1_GPIO 8 /* GPS */
/*
* I2C (external)
*
* I2C1SCL: GPIO7
* I2C1SDA: GPIO6
*
* TODO:
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*/
#define CONFIG_RP2040_I2C1_GPIO 6
/* SPI0:
* SPIDEV_FLASH (probably micro sd card)
* CS: GPIO5 -- should be configured in sec/spi.cpp (probably)
* CLK: GPIO2
* MISO: GPIO4
* MOSI: GPIO3
*/
#define GPIO_SPI0_SCLK ( 2 | GPIO_FUN(RP2040_GPIO_FUNC_SPI) )
#define GPIO_SPI0_MISO ( 4 | GPIO_FUN(RP2040_GPIO_FUNC_SPI) )
#define GPIO_SPI0_MOSI ( 3 | GPIO_FUN(RP2040_GPIO_FUNC_SPI) )
/* SPI1:
* MPU9250 and BMP280
* CS: GPIO13 for MPU9250, GPIO14 for BMP280 -- should be configured in sec/spi.cpp (probably)
* CLK: GPIO10
* MISO: GPIO12
* MOSI: GPIO11
*/
#define GPIO_SPI1_SCLK ( 10 | GPIO_FUN(RP2040_GPIO_FUNC_SPI) )
#define GPIO_SPI1_MISO ( 12 | GPIO_FUN(RP2040_GPIO_FUNC_SPI) )
#define GPIO_SPI1_MOSI ( 11 | GPIO_FUN(RP2040_GPIO_FUNC_SPI) )
#endif /* __ARCH_BOARD_BOARD_H */
@@ -0,0 +1,118 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DEV_CONSOLE is not set
# CONFIG_RP2040_SPI_DRIVER is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="rp2040"
CONFIG_ARCH_CHIP_RP2040=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_LOOPSPERMSEC=10450
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTSTR="PX4 RaspberryPi Pico"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=2000
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_REBOOT=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_FATDEVNO=0
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_READLINE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_USBCONSOLE=y
CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=270336
CONFIG_RAM_START=0x20000000
CONFIG_RAW_BINARY=y
CONFIG_RP2040_I2C1=y
CONFIG_RP2040_I2C=y
CONFIG_RP2040_SPI0=y
CONFIG_RP2040_SPI1=y
CONFIG_RP2040_SPI=y
CONFIG_RP2040_UART1=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
@@ -0,0 +1,113 @@
/****************************************************************************
* boards/arm/rp2040/raspberrypi-pico/scripts/raspberrypi-pico-flash.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
MEMORY
{
flash (rx) : ORIGIN = 0x10000000, LENGTH = 2048K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 264K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
EXTERN(bootStr)
SECTIONS
{
.flash_begin : {
__flash_binary_start = .;
} > flash
.boot2 : {
__boot2_start__ = .;
KEEP (*(.boot2))
__boot2_end__ = .;
} > flash
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : {
_sinit = ABSOLUTE(.);
KEEP (*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.ram_vectors (COPY) : {
*(.ram_vectors)
} > sram
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
@@ -0,0 +1,113 @@
/****************************************************************************
* boards/arm/rp2040/raspberrypi-pico/scripts/raspberrypi-pico-flash.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
MEMORY
{
flash (rx) : ORIGIN = 0x10000000, LENGTH = 2048K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 264K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
EXTERN(bootStr)
SECTIONS
{
.flash_begin : {
__flash_binary_start = .;
} > flash
.boot2 : {
__boot2_start__ = .;
KEEP (*(.boot2))
__boot2_end__ = .;
} > flash
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : {
_sinit = ABSOLUTE(.);
KEEP (*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.ram_vectors (COPY) : {
*(.ram_vectors)
} > sram
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
@@ -0,0 +1,52 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_library(drivers_board
boot_string.c
i2c.cpp
init.c
led.c
spi.cpp
timer_config.cpp
usb.c
)
target_link_libraries(drivers_board
PRIVATE
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
arch_io_pins
)
+140
View File
@@ -0,0 +1,140 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* board internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
/* LEDs */
// LED1 - GPIO 25 - Green
#define GPIO_LED1 PX4_MAKE_GPIO_OUTPUT_CLEAR(25) // Take a look at rpi_common micro_hal.h
#define GPIO_LED_BLUE GPIO_LED1
#define BOARD_OVERLOAD_LED LED_BLUE
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
*/
#define ADC_CHANNELS (1 << 0) | (1 << 1) | (1 << 2) | (1 << 3) // Change this later based on the adc channels actually used
#define ADC_BATTERY_VOLTAGE_CHANNEL 1 // Corresponding GPIO 27. Used in init.c for disabling GPIO_IE
#define ADC_BATTERY_CURRENT_CHANNEL 2 // Corresponding GPIO 28. Used in init.c for disabling GPIO_IE
#define ADC_RC_RSSI_CHANNEL 0
/* Define Battery 1 Voltage Divider and A per V. */
#define BOARD_BATTERY1_V_DIV (13.653333333f)
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* High-resolution timer */
#define HRT_TIMER 1
#define HRT_TIMER_CHANNEL 1
#define HRT_PPM_CHANNEL 1 // Number really doesn't matter for this board
#define GPIO_PPM_IN (16 | GPIO_FUN(RP2040_GPIO_FUNC_SIO))
#define RC_SERIAL_PORT "/dev/ttyS3"
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
/* This board provides a DMA pool and APIs */ // Needs to be figured out
#define BOARD_DMA_ALLOC_POOL_SIZE 2048
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*3)
/* USB
*
* VBUS detection is on 29 ADC_DPM0 and PTE8
*/
#define GPIO_USB_VBUS_VALID (24 | GPIO_FUN(RP2040_GPIO_FUNC_SIO)) // Used in usb.c
/* PWM
*
* Alternatively CH3/CH4 could be assigned to UART6_TX/RX
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 4
// Has pwm outputs
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/*
* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.
*/
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_USB_VBUS_VALID))
__BEGIN_DECLS
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Name: rp2040_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
****************************************************************************************************/
extern void rp2040_spiinitialize(void);
/****************************************************************************************************
* Name: rp2040_usbinitialize
*
* Description:
* Called to configure USB IO.
*
****************************************************************************************************/
extern void rp2040_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
+20
View File
@@ -0,0 +1,20 @@
#include <stdint.h>
__attribute__((section(".boot2")))
const char bootStr[256] = {0x00, 0xb5, 0x32, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x98, 0x68, 0x02, 0x21, 0x88, 0x43, 0x98, 0x60,
0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x2e, 0x4b, 0x00, 0x21, 0x99, 0x60, 0x02, 0x21, 0x59, 0x61,
0x01, 0x21, 0xf0, 0x22, 0x99, 0x50, 0x2b, 0x49, 0x19, 0x60, 0x01, 0x21, 0x99, 0x60, 0x35, 0x20,
0x00, 0xf0, 0x44, 0xf8, 0x02, 0x22, 0x90, 0x42, 0x14, 0xd0, 0x06, 0x21, 0x19, 0x66, 0x00, 0xf0,
0x34, 0xf8, 0x19, 0x6e, 0x01, 0x21, 0x19, 0x66, 0x00, 0x20, 0x18, 0x66, 0x1a, 0x66, 0x00, 0xf0,
0x2c, 0xf8, 0x19, 0x6e, 0x19, 0x6e, 0x19, 0x6e, 0x05, 0x20, 0x00, 0xf0, 0x2f, 0xf8, 0x01, 0x21,
0x08, 0x42, 0xf9, 0xd1, 0x00, 0x21, 0x99, 0x60, 0x1b, 0x49, 0x19, 0x60, 0x00, 0x21, 0x59, 0x60,
0x1a, 0x49, 0x1b, 0x48, 0x01, 0x60, 0x01, 0x21, 0x99, 0x60, 0xeb, 0x21, 0x19, 0x66, 0xa0, 0x21,
0x19, 0x66, 0x00, 0xf0, 0x12, 0xf8, 0x00, 0x21, 0x99, 0x60, 0x16, 0x49, 0x14, 0x48, 0x01, 0x60,
0x01, 0x21, 0x99, 0x60, 0x01, 0xbc, 0x00, 0x28, 0x00, 0xd0, 0x00, 0x47, 0x12, 0x48, 0x13, 0x49,
0x08, 0x60, 0x03, 0xc8, 0x80, 0xf3, 0x08, 0x88, 0x08, 0x47, 0x03, 0xb5, 0x99, 0x6a, 0x04, 0x20,
0x01, 0x42, 0xfb, 0xd0, 0x01, 0x20, 0x01, 0x42, 0xf8, 0xd1, 0x03, 0xbd, 0x02, 0xb5, 0x18, 0x66,
0x18, 0x66, 0xff, 0xf7, 0xf2, 0xff, 0x18, 0x6e, 0x18, 0x6e, 0x02, 0xbd, 0x00, 0x00, 0x02, 0x40,
0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x07, 0x00, 0x00, 0x03, 0x5f, 0x00, 0x21, 0x22, 0x00, 0x00,
0xf4, 0x00, 0x00, 0x18, 0x22, 0x20, 0x00, 0xa0, 0x00, 0x01, 0x00, 0x10, 0x08, 0xed, 0x00, 0xe0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x74, 0xb2, 0x4e, 0x7a
};
+38
View File
@@ -0,0 +1,38 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(2),
};
+399
View File
@@ -0,0 +1,399 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file init.c
*
* board specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include "board_config.h"
#include <rp2040_uart.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform/board_dma_alloc.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>
#endif
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/**
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/****************************************************************************
* Protected Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
UNUSED(ms);
}
/************************************************************************************
* Name: board_on_reset
*
* Description:
* Optionally provided function called on entry to board_system_reset
* It should perform any house keeping prior to the rest.
*
* status - 1 if resetting to boot loader
* 0 if just resetting
*
************************************************************************************/
__EXPORT void board_on_reset(int status)
{
// Configure the GPIO pins to outputs and keep them low.
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
px4_arch_configgpio(io_timer_channel_get_gpio_output(i));
}
/*
* On resets invoked from system (not boot) insure we establish a low
* output state (discharge the pins) on PWM pins before they become inputs.
*/
if (status >= 0) {
up_mdelay(400);
}
}
/************************************************************************************
* Name: board_read_VBUS_state
*
* Description:
* All boards must provide a way to read the state of VBUS, this my be simple
* digital input on a GPIO. Or something more complicated like a Analong input
* or reading a bit from a USB controller register.
*
* Returns - 0 if connected.
*
************************************************************************************/
int board_read_VBUS_state(void)
{
return BOARD_ADC_USB_CONNECTED ? 0 : 1;
}
/****************************************************************************
* Name: rp2040_boardearlyinitialize
*
* Description:
*
* This function is taken directly from nuttx's rp2040_boardinitialize.c
****************************************************************************/
void rp2040_boardearlyinitialize(void)
{
/* Set default UART pin */
#if defined(CONFIG_RP2040_UART0) && CONFIG_RP2040_UART0_GPIO >= 0
rp2040_gpio_set_function(CONFIG_RP2040_UART0_GPIO, RP2040_GPIO_FUNC_UART); /* TX */
rp2040_gpio_set_function(CONFIG_RP2040_UART0_GPIO + 1, RP2040_GPIO_FUNC_UART); /* RX */
# ifdef CONFIG_SERIAL_OFLOWCONTROL
rp2040_gpio_set_function(CONFIG_RP2040_UART0_GPIO + 2, RP2040_GPIO_FUNC_UART); /* CTS */
# endif /* CONFIG_SERIAL_OFLOWCONTROL */
# ifdef CONFIG_SERIAL_IFLOWCONTROL
rp2040_gpio_set_function(CONFIG_RP2040_UART0_GPIO + 3, RP2040_GPIO_FUNC_UART); /* RTS */
# endif /* CONFIG_SERIAL_IFLOWCONTROL */
#endif
#if defined(CONFIG_RP2040_UART1) && CONFIG_RP2040_UART1_GPIO >= 0
rp2040_gpio_set_function(CONFIG_RP2040_UART1_GPIO, RP2040_GPIO_FUNC_UART); /* TX */
rp2040_gpio_set_function(CONFIG_RP2040_UART1_GPIO + 1, RP2040_GPIO_FUNC_UART); /* RX */
# ifdef CONFIG_SERIAL_OFLOWCONTROL
rp2040_gpio_set_function(CONFIG_RP2040_UART1_GPIO + 2, RP2040_GPIO_FUNC_UART); /* CTS */
# endif /* CONFIG_SERIAL_OFLOWCONTROL */
# ifdef CONFIG_SERIAL_IFLOWCONTROL
rp2040_gpio_set_function(CONFIG_RP2040_UART1_GPIO + 3, RP2040_GPIO_FUNC_UART); /* RTS */
# endif /* CONFIG_SERIAL_IFLOWCONTROL */
#endif
}
/************************************************************************************
* Name: rp2040_boardinitialize
*
* Description:
* All architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
rp2040_boardinitialize(void)
{
// /* Reset all PWM to Low outputs */
// board_on_reset(-1);
// /* configure LEDs */
board_autoled_initialize();
// Disable IE and enable OD on GPIO 26-29 (These are ADC Pins)
// Do this only for the channels configured in board_config.h
rp2040_gpioconfig(27 | GPIO_FUN(RP2040_GPIO_FUNC_NULL)); /* BATT_VOLTAGE_SENS */
clrbits_reg32(RP2040_PADS_BANK0_GPIO_IE, RP2040_PADS_BANK0_GPIO(27)); /* BATT_VOLTAGE_SENS */
setbits_reg32(RP2040_PADS_BANK0_GPIO_OD, RP2040_PADS_BANK0_GPIO(27)); /* BATT_VOLTAGE_SENS */
rp2040_gpioconfig(28 | GPIO_FUN(RP2040_GPIO_FUNC_NULL)); /* BATT_VOLTAGE_SENS */
clrbits_reg32(RP2040_PADS_BANK0_GPIO_IE, RP2040_PADS_BANK0_GPIO(28)); /* BATT_CURRENT_SENS */
setbits_reg32(RP2040_PADS_BANK0_GPIO_OD, RP2040_PADS_BANK0_GPIO(28)); /* BATT_CURRENT_SENS */
/* Set default I2C pin */
#if defined(CONFIG_RP2040_I2C0) && CONFIG_RP2040_I2C0_GPIO >= 0
rp2040_gpio_set_function(CONFIG_RP2040_I2C0_GPIO, RP2040_GPIO_FUNC_I2C); /* SDA */
rp2040_gpio_set_function(CONFIG_RP2040_I2C0_GPIO + 1, RP2040_GPIO_FUNC_I2C); /* SCL */
rp2040_gpio_set_pulls(CONFIG_RP2040_I2C0_GPIO, true, false); /* Pull up */
rp2040_gpio_set_pulls(CONFIG_RP2040_I2C0_GPIO + 1, true, false);
#endif
#if defined(CONFIG_RP2040_I2C1) && CONFIG_RP2040_I2C1_GPIO >= 0
rp2040_gpio_set_function(CONFIG_RP2040_I2C1_GPIO, RP2040_GPIO_FUNC_I2C); /* SDA */
rp2040_gpio_set_function(CONFIG_RP2040_I2C1_GPIO + 1, RP2040_GPIO_FUNC_I2C); /* SCL */
rp2040_gpio_set_pulls(CONFIG_RP2040_I2C1_GPIO, true, false); /* Pull up */
rp2040_gpio_set_pulls(CONFIG_RP2040_I2C1_GPIO + 1, true, false);
#endif
// // TODO: power peripherals
// ///* configure power supply control/sense pins */
// //stm32_configgpio(GPIO_PERIPH_3V3_EN);
// //stm32_configgpio(GPIO_VDD_BRICK_VALID);
// //stm32_configgpio(GPIO_VDD_USB_VALID);
// // TODO: 3v3 Sensor?
// ///* Start with Sensor voltage off We will enable it
// // * in board_app_initialize
// // */
// //stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
// // TODO: SBUS inversion? SPEK power?
// //stm32_configgpio(GPIO_SBUS_INV);
// //stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
// // TODO: $$$ Unused?
// //stm32_configgpio(GPIO_8266_GPIO0);
// //stm32_configgpio(GPIO_8266_PD);
// //stm32_configgpio(GPIO_8266_RST);
// /* Safety - led don in led driver */
// // TODO: unused?
// //stm32_configgpio(GPIO_BTN_SAFETY);
// // TODO: RSSI
// //stm32_configgpio(GPIO_RSSI_IN);
// stm32_configgpio(GPIO_PPM_IN);
/* configure SPI all interfaces GPIO */
rp2040_spiinitialize();
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
// static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
__EXPORT int board_app_initialize(uintptr_t arg)
{
px4_platform_init();
/* configure the DMA allocator */ // Needs to be figured out
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "DMA alloc FAILED\n");
}
/* set up the serial DMA polling */ // RP2040 nuttx implementation doesn't have serial_dma_poll function yet.
// static struct hrt_call serial_dma_call;
// struct timespec ts;
// /*
// * Poll at 1ms intervals for received bytes that have not triggered
// * a DMA event.
// */
// ts.tv_sec = 0;
// ts.tv_nsec = 1000000;
// hrt_call_every(&serial_dma_call,
// ts_to_abstime(&ts),
// ts_to_abstime(&ts),
// (hrt_callout)stm32_serial_dma_poll,
// NULL);
/* initial LED state */
drv_led_start();
led_on(LED_BLUE);
// if (board_hardfault_init(2, true) != 0) { // Needs to be figured out as RP2040 doesn't have BBSRAM.
// led_off(LED_BLUE);
// }
/* Configure SPI-based devices */
// // SPI1: SDCard // Will be configured later
// /* Get the SPI port for the microSD slot */
// spi1 = rp2040_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO); // PX4_BUS_NUMBER_FROM_PX4(1)
// if (!spi1) {
// syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
// led_off(LED_BLUE);
// return -ENODEV;
// }
// /* Now bind the SPI interface to the MMCSD driver */
// int result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi1);
// if (result != OK) {
// led_off(LED_BLUE);
// syslog(LOG_ERR, "[boot] FAILED to bind SPI port 1 to the MMCSD driver\n");
// return -ENODEV;
// }
// up_udelay(20);
// SPI2: MPU9250 and BMP280
spi2 = rp2040_spibus_initialize(PX4_BUS_NUMBER_FROM_PX4(2));
if (!spi2) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 2\n");
led_off(LED_BLUE);
return -ENODEV;
}
/* Default SPI2 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi2, 10000000);
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);
up_udelay(20);
// #if defined(FLASH_BASED_PARAMS) // This probably doesn't relate to RP2040 right now.
// static sector_descriptor_t params_sector_map[] = {
// {1, 16 * 1024, 0x08004000},
// {0, 0, 0},
// };
// /* Initialize the flashfs layer to use heap allocated memory */
// result = parameter_flashfs_init(params_sector_map, NULL, 0);
// if (result != OK) {
// syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
// led_off(LED_AMBER);
// return -ENODEV;
// }
// #endif
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}
+119
View File
@@ -0,0 +1,119 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file led.c
*
* board LED backend.
*/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "board_config.h"
#include <arch/board/board.h>
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
static uint32_t g_ledmap[] = {
GPIO_LED_BLUE, // Onboard led on raspberrypi pico
};
__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
px4_arch_configgpio(g_ledmap[l]);
}
}
static void phy_set_led(int led, bool state)
{
/* Pull Down to switch on */
if (led == 0) {
px4_arch_gpiowrite(g_ledmap[led], state);
}
}
__EXPORT void led_on(int led)
{
phy_set_led(led, true);
}
__EXPORT void led_off(int led)
{
phy_set_led(led, false);
}
__EXPORT void led_toggle(int led)
{
if (led == 0) {
phy_set_led(led, !px4_arch_gpioread(g_ledmap[led]));
}
}
// __EXPORT void board_autoled_initialize()
// {
// /* Configure LED1 GPIO for output */
// px4_arch_configgpio(GPIO_LED1);
// }
// __EXPORT void board_autoled_on(int led)
// {
// if (led == 1) {
// /* Pull down to switch on */
// px4_arch_gpiowrite(GPIO_LED1, false);
// }
// }
// __EXPORT void board_autoled_off(int led)
// {
// if (led == 1) {
// /* Pull up to switch off */
// px4_arch_gpiowrite(GPIO_LED1, true);
// }
// }
+48
View File
@@ -0,0 +1,48 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI0, {
initSPIDevice(SPIDEV_MMCSD(0), SPI::CS{GPIO::Pin5}),
}),
initSPIBusExternal(SPI::Bus::SPI1, {
initSPIConfigExternal(SPI::CS{GPIO::Pin13}),
initSPIConfigExternal(SPI::CS{GPIO::Pin14}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
@@ -0,0 +1,49 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/io_timer_hw_description.h>
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1),
initIOTimer(Timer::Timer2),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::ChannelA}, {GPIO::Pin18}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::ChannelB}, {GPIO::Pin19}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::ChannelA}, {GPIO::Pin20}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::ChannelB}, {GPIO::Pin21}),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping = initIOTimerChannelMapping(io_timers,
timer_io_channels);
+85
View File
@@ -0,0 +1,85 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file usb.c
*
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <arm_arch.h>
#include "board_config.h"
/************************************************************************************
* Name: rp2040_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the omnibusf4sd board.
*
************************************************************************************/
__EXPORT void rp2040_usbinitialize(void)
{
px4_arch_configgpio(GPIO_USB_VBUS_VALID);
}
/************************************************************************************
* Name: stm32_usbsuspend
*
* Description:
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
* used. This function is called whenever the USB enters or leaves suspend mode.
* This is an opportunity for the board logic to shutdown clocks, power, etc.
* while the USB is suspended.
*
************************************************************************************/
__EXPORT void rp2040_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}
@@ -0,0 +1,5 @@
set(cpu_flags "-mcpu=cortex-m0plus -mthumb -mfloat-abi=soft") # Nuttx toochain uses -mfloat-abi=soft
set(CMAKE_C_FLAGS "${cpu_flags}" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "${cpu_flags}" CACHE STRING "" FORCE)
set(CMAKE_ASM_FLAGS "${cpu_flags} -D__ASSEMBLY__" CACHE STRING "" FORCE)
+3
View File
@@ -124,6 +124,9 @@ function(px4_os_determine_build_chip)
elseif(CONFIG_ARCH_CHIP_S32K146)
set(CHIP_MANUFACTURER "nxp")
set(CHIP "s32k14x")
elseif(CONFIG_ARCH_CHIP_RP2040)
set(CHIP_MANUFACTURER "rpi")
set(CHIP "rp2040")
else()
message(FATAL_ERROR "Could not determine chip architecture from NuttX config. You may have to add it.")
endif()
@@ -0,0 +1 @@
add_subdirectory(${PX4_CHIP})
@@ -0,0 +1,7 @@
add_subdirectory(../rpi_common/adc adc)
add_subdirectory(../rpi_common/hrt hrt)
add_subdirectory(../rpi_common/version version)
add_subdirectory(../rpi_common/board_reset board_reset)
add_subdirectory(../rpi_common/board_critmon board_critmon)
add_subdirectory(../rpi_common/spi spi)
add_subdirectory(../rpi_common/io_pins io_pins)
@@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "../../../rpi_common/include/px4_arch/adc.h"
@@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "../../../rpi_common/include/px4_arch/hw_description.h"
@@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "../../../rpi_common/include/px4_arch/i2c_hw_description.h"
@@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "../../../rpi_common/include/px4_arch/io_timer.h"
@@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "../../../rpi_common/include/px4_arch/io_timer_hw_description.h"
@@ -0,0 +1,12 @@
#pragma once
#include "../../../rpi_common/include/px4_arch/micro_hal.h"
__BEGIN_DECLS
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_UNUSED
#define PX4_FLASH_BASE RP2040_FLASH_BASE
#define PX4_NUMBER_I2C_BUSES 2
#define PX4_ADC_INTERNAL_TEMP_SENSOR_CHANNEL 4
__END_DECLS
@@ -0,0 +1,66 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "../../../rpi_common/include/px4_arch/spi_hw_description.h"
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
{
const bool nuttx_enabled_spi_buses[] = {
#ifdef CONFIG_RP2040_SPI0
true,
#else
false,
#endif
#ifdef CONFIG_RP2040_SPI1
true,
#else
false,
#endif
};
for (unsigned i = 0; i < sizeof(nuttx_enabled_spi_buses) / sizeof(nuttx_enabled_spi_buses[0]); ++i) {
bool found_bus = false;
for (int j = 0; j < SPI_BUS_MAX_BUS_ITEMS; ++j) {
if (spi_busses_conf[j].bus == (int)i + 1) {
found_bus = true;
}
}
// Either the bus is enabled in NuttX and configured in spi_busses_conf, or disabled and not configured
constexpr_assert(found_bus == nuttx_enabled_spi_buses[i], "SPI bus config mismatch (CONFIG_RP2040_SPIx)");
}
return false;
}
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(arch_adc
adc.cpp
)
@@ -0,0 +1,176 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <board_config.h>
#include <stdint.h>
#include <drivers/drv_adc.h>
#include <drivers/drv_hrt.h>
#include <px4_arch/adc.h>
// #include <rp2040_adc.h> Nuttx doesn't have this file in arch yet.
#include <rp2040_gpio.h>
/*
* Register accessors.
* For now, no reason not to just use ADC1.
*/
#define REG(base, _reg) (*(volatile uint32_t *)((base) + (_reg)))
#define rCS(base) REG((base), 0x00) // ADC Control and Status
#define rRESULT(base) REG((base), 0x04) // Result of most recent ADC conversion
#define rFCS(base) REG((base), 0x08) // FIFO control and status
#define rFIFO(base) REG((base), 0x0c) // Conversion result FIFO
#define rDIV(base) REG((base), 0x10) // Clock divider
#define rINTR(base) REG((base), 0x14) // Raw Interrupts
#define rINTE(base) REG((base), 0x18) // Interrupt Enable
#define rINTF(base) REG((base), 0x1c) // Interrupt Force
#define rINTS(base) REG((base), 0x20) // Interrupt status after masking & forcing
int px4_arch_adc_init(uint32_t base_address)
{
/* Perform ADC init once per ADC */
static uint32_t once[SYSTEM_ADC_COUNT] {};
uint32_t *free = nullptr;
for (uint32_t i = 0; i < SYSTEM_ADC_COUNT; i++) {
if (once[i] == base_address) {
/* This one was done already */
return OK;
}
/* Use first free slot */
if (free == nullptr && once[i] == 0) {
free = &once[i];
}
}
if (free == nullptr) {
/* ADC misconfigured SYSTEM_ADC_COUNT too small */;
PANIC();
}
*free = base_address;
// Assuming that the ADC gpio is configured correctly,
// all that is left to do is divide 48MHz clock if
// necessary and then enable the ADC. (One reading
// requires about 100 clocks.) Also enable the temp
// sensor channel.
// Divide incoming 48MHz clock
// (Trigger adc once per n+1 cycles)
// So, n >= 96. Because, 1 sample = 96 clocks
rDIV(base_address) = 0 | (0 << 8); // 8-bit fraction value | 16-bit int value => n = int + frac/256
// Enable temperature sensor and enable ADC
rCS(base_address) = 1 | (1 << 1);
px4_usleep(10);
// Select temperature channel and kick off a sample and wait for it to complete
rCS(base_address) &= ~(0b111 << 12); // Clear AINSEL
rCS(base_address) |= PX4_ADC_INTERNAL_TEMP_SENSOR_CHANNEL << 12; // Choose temperature channel
hrt_abstime now = hrt_absolute_time();
rCS(base_address) |= 1 << 2; // Start a single conversion
while (!(rCS(base_address) & (1 << 8))) { // Check if the sample is ready
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
if ((hrt_absolute_time() - now) > 500) {
return -1;
}
}
/* Read out result */
(void) rRESULT(base_address);
return 0;
}
void px4_arch_adc_uninit(uint32_t base_address)
{
// Disable ADC
rCS(base_address) = 0;
}
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
{
irqstate_t flags = px4_enter_critical_section();
/* run a single conversion right now - should take about 96 cycles (a few microseconds) max */
rCS(base_address) &= ~(0b111 << 12); // Clear AINSEL
rCS(base_address) |= channel << 12; // Choose temperature channel
rCS(base_address) |= 1 << 2; // Start a single conversion
/* wait for the conversion to complete */
const hrt_abstime now = hrt_absolute_time();
while (!(rCS(base_address) & (1 << 8))) { // Check if the sample is ready
/* don't wait for more than 50us, since that means something broke - should reset here if we see this */
if ((hrt_absolute_time() - now) > 50) {
px4_leave_critical_section(flags);
return UINT32_MAX;
}
}
/* read the result and clear EOC */
uint32_t result = rRESULT(base_address);
px4_leave_critical_section(flags);
return result;
}
float px4_arch_adc_reference_v()
{
return BOARD_ADC_POS_REF_V; // TODO: provide true vref
}
uint32_t px4_arch_adc_temp_sensor_mask()
{
return 1 << PX4_ADC_INTERNAL_TEMP_SENSOR_CHANNEL;
}
uint32_t px4_arch_adc_dn_fullcount()
{
return 1 << 12; // 12 bit ADC
}
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (C) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(arch_board_critmon
board_critmon.c
)
@@ -0,0 +1,66 @@
/************************************************************************************
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <arch/board/board.h>
#if defined(CONFIG_SCHED_CRITMONITOR) || defined(CONFIG_SCHED_IRQMONITOR)
/************************************************************************************
* Public Functions
************************************************************************************/
#error "missing implementation for up_critmon_gettime() and up_critmon_convert()"
/************************************************************************************
* Name: up_critmon_gettime
************************************************************************************/
// uint32_t up_critmon_gettime(void)
// {
// }
/************************************************************************************
* Name: up_critmon_convert
************************************************************************************/
// void up_critmon_convert(uint32_t elapsed, FAR struct timespec *ts)
// {
// }
#endif /* CONFIG_SCHED_CRITMONITOR */
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (C) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(arch_board_reset
board_reset.cpp
)
@@ -0,0 +1,158 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
* Author: @author David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_reset.cpp
* Implementation of RP2040 based Board RESET API
*/
#include <px4_platform_common/px4_config.h>
#include <systemlib/px4_macros.h>
#include <errno.h>
#include <nuttx/board.h>
// Functions in here are modified so that board_reset() function resembles
// the one available in nuttx's boards/raspberrypi-pico folder.
#ifdef CONFIG_BOARDCTL_RESET
/****************************************************************************
* Name: board_configure_reset
*
* Description:
* Configures the device that maintains the state shared by the
* application and boot loader. This is usually an RTC.
*
* Input Parameters:
* mode - The type of reset. See reset_mode_e
*
* Returned Value:
* 0 for Success
* 1 if invalid argument
*
****************************************************************************/
// static const uint32_t modes[] = {
// /* to tb */
// /* BOARD_RESET_MODE_CLEAR 5 y */ 0,
// /* BOARD_RESET_MODE_BOOT_TO_BL 0 n */ 0xb007b007,
// /* BOARD_RESET_MODE_BOOT_TO_VALID_APP 0 y */ 0xb0070002,
// /* BOARD_RESET_MODE_CAN_BL 10 n */ 0xb0080000,
// /* BOARD_RESET_MODE_RTC_BOOT_FWOK 0 n */ 0xb0093a26
// };
// int board_configure_reset(reset_mode_e mode, uint32_t arg)
// {
// int rv = -1;
// if (mode < arraySize(modes)) {
// stm32_pwr_enablebkp(true);
// arg = mode == BOARD_RESET_MODE_CAN_BL ? arg & ~0xff : 0;
// // Check if we can to use the new register definition
// #ifndef STM32_RTC_BK0R
// *(uint32_t *)STM32_BKP_BASE = modes[mode] | arg;
// #else
// *(uint32_t *)STM32_RTC_BK0R = modes[mode] | arg;
// #endif
// stm32_pwr_enablebkp(false);
// rv = OK;
// }
// return rv;
// }
/****************************************************************************
* Name: board_reset
*
* Description:
* Reset board. Support for this function is required by board-level
* logic if CONFIG_BOARDCTL_RESET is selected.
*
* Input Parameters:
* status - Status information provided with the reset event. This
* meaning of this status information is board-specific. If not
* used by a board, the value zero may be provided in calls to
* board_reset().
*
* Returned Value:
* If this function returns, then it was not possible to power-off the
* board due to some constraints. The return value int this case is a
* board-specific reason for the failure to shutdown.
*
****************************************************************************/
int board_reset(int status)
{
if (status == 1) {
// board_configure_reset(BOARD_RESET_MODE_BOOT_TO_BL, 0);
}
#if defined(BOARD_HAS_ON_RESET)
// board_on_reset(status);
#endif
up_systemreset();
return 0;
}
#endif /* CONFIG_BOARDCTL_RESET */
#if defined(SUPPORT_ALT_CAN_BOOTLOADER)
/****************************************************************************
* Name: board_booted_by_px4
*
* Description:
* Determines if the the boot loader was PX4
*
* Input Parameters:
* none
*
* Returned Value:
* true if booted byt a PX4 bootloader.
*
****************************************************************************/
bool board_booted_by_px4(void)
{
uint32_t *vectors = (uint32_t *) STM32_FLASH_BASE;
/* Nuttx uses common vector */
return (vectors[2] == vectors[3]) && (vectors[4] == vectors[5]);
}
#endif
@@ -0,0 +1,41 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(arch_hrt
hrt.c
)
target_compile_options(arch_hrt
PRIVATE
${MAX_CUSTOM_OPT_LEVEL}
-Wno-cast-align # TODO: fix and enable
)
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,40 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <board_config.h>
#define SYSTEM_ADC_BASE RP2040_ADC_BASE
#include <px4_platform/adc.h>
@@ -0,0 +1,222 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <hardware/rp2040_memorymap.h>
#include <px4_platform_common/constexpr_util.h>
/*
* Timers
*/
namespace Timer
{
enum Timer {
Timer0 = 1,
Timer1,
Timer2,
Timer3,
Timer4,
Timer5,
Timer6,
Timer7,
};
enum Channel {
ChannelA = 1,
ChannelB,
};
struct TimerChannel {
Timer timer;
Channel channel;
};
}
static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer)
{
switch (timer) {
case Timer::Timer0: return RP2040_PWM_BASE + 0x00;
case Timer::Timer1: return RP2040_PWM_BASE + 0x14;
case Timer::Timer2: return RP2040_PWM_BASE + 0x28;
case Timer::Timer3: return RP2040_PWM_BASE + 0x3c;
case Timer::Timer4: return RP2040_PWM_BASE + 0x50;
case Timer::Timer5: return RP2040_PWM_BASE + 0x64;
case Timer::Timer6: return RP2040_PWM_BASE + 0x78;
case Timer::Timer7: return RP2040_PWM_BASE + 0x8c;
default: break;
}
return 0;
}
/*
* GPIO
*/
namespace GPIO
{
// RP2040 doesn't have PORTS
enum Pin {
Pin0 = 0,
Pin1,
Pin2,
Pin3,
Pin4,
Pin5,
Pin6,
Pin7,
Pin8,
Pin9,
Pin10,
Pin11,
Pin12,
Pin13,
Pin14,
Pin15,
Pin16,
Pin17,
Pin18,
Pin19,
Pin20,
Pin21,
Pin22,
Pin23,
Pin24,
Pin25,
Pin26,
Pin27,
Pin28,
Pin29,
};
struct GPIOPin {
Pin pin;
};
}
static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin)
{
switch (pin) {
case GPIO::Pin0: return 0;
case GPIO::Pin1: return 1;
case GPIO::Pin2: return 2;
case GPIO::Pin3: return 3;
case GPIO::Pin4: return 4;
case GPIO::Pin5: return 5;
case GPIO::Pin6: return 6;
case GPIO::Pin7: return 7;
case GPIO::Pin8: return 8;
case GPIO::Pin9: return 9;
case GPIO::Pin10: return 10;
case GPIO::Pin11: return 11;
case GPIO::Pin12: return 12;
case GPIO::Pin13: return 13;
case GPIO::Pin14: return 14;
case GPIO::Pin15: return 15;
case GPIO::Pin16: return 16;
case GPIO::Pin17: return 17;
case GPIO::Pin18: return 18;
case GPIO::Pin19: return 19;
case GPIO::Pin20: return 20;
case GPIO::Pin21: return 21;
case GPIO::Pin22: return 22;
case GPIO::Pin23: return 23;
case GPIO::Pin24: return 24;
case GPIO::Pin25: return 25;
case GPIO::Pin26: return 26;
case GPIO::Pin27: return 27;
case GPIO::Pin28: return 28;
case GPIO::Pin29: return 29;
}
return 0;
}
namespace SPI
{
enum class Bus {
SPI0 = 1,
SPI1,
};
using CS = GPIO::GPIOPin; ///< chip-select pin
using DRDY = GPIO::GPIOPin; ///< data ready pin
struct bus_device_external_cfg_t {
CS cs_gpio;
DRDY drdy_gpio;
};
} // namespace SPI
@@ -0,0 +1,54 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_arch/hw_description.h>
#include <px4_platform_common/i2c.h>
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
{
px4_i2c_bus_t ret{};
ret.bus = bus;
ret.is_external = false;
return ret;
}
static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
{
px4_i2c_bus_t ret{};
ret.bus = bus;
ret.is_external = true;
return ret;
}
@@ -0,0 +1,163 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file io_timer.h
*/
#include <px4_platform_common/px4_config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <drivers/drv_hrt.h>
#pragma once
__BEGIN_DECLS
/* configuration limits */
#ifdef BOARD_NUM_IO_TIMERS
#define MAX_IO_TIMERS BOARD_NUM_IO_TIMERS
#else
#define MAX_IO_TIMERS 8
#endif
#if DIRECT_PWM_OUTPUT_CHANNELS > 8
#define MAX_TIMER_IO_CHANNELS DIRECT_PWM_OUTPUT_CHANNELS
#else
#define MAX_TIMER_IO_CHANNELS 16
#endif
#define MAX_LED_TIMERS 2
#define MAX_TIMER_LED_CHANNELS 4
#define IO_TIMER_ALL_MODES_CHANNELS 0
/* TIM_DMA_Base_address TIM DMA Base Address */
#define TIM_DMABASE_CCR1 0x0000000DU
#define TIM_DMABASE_CCR2 0x0000000EU
#define TIM_DMABASE_CCR3 0x0000000FU
#define TIM_DMABASE_CCR4 0x00000010U
typedef enum io_timer_channel_mode_t {
IOTimerChanMode_NotUsed = 0,
IOTimerChanMode_PWMOut = 1,
IOTimerChanMode_PWMIn = 2,
IOTimerChanMode_Capture = 3,
IOTimerChanMode_OneShot = 4,
IOTimerChanMode_Trigger = 5,
IOTimerChanMode_Dshot = 6,
IOTimerChanModeSize
} io_timer_channel_mode_t;
typedef uint16_t io_timer_channel_allocation_t; /* big enough to hold MAX_TIMER_IO_CHANNELS */
/* array of timers dedicated to PWM in and out and capture use
*** Note that the clock_freq is set to the source in the clock tree that
*** feeds this specific timer. This can differs by Timer!
*** In PWM mode the timer's prescaler is set to achieve a counter frequency of 1MHz
*** In OneShot mode the timer's prescaler is set to achieve a counter frequency of 8MHz
*** Other prescaler rates can be achieved by fore instance by setting the clock_freq = 1Mhz
*** the resulting PSC will be one and the timer will count at it's clock frequency.
*/
typedef struct io_timers_t {
uint32_t base;
// uint32_t clock_register; // Not required for rp2040
// uint32_t clock_bit;
// uint32_t vectorno;
// dshot_conf_t dshot;
} io_timers_t;
typedef struct io_timers_channel_mapping_element_t {
uint32_t first_channel_index;
uint32_t channel_count;
} io_timers_channel_mapping_element_t;
/* mapping for each io_timers to timer_io_channels */
typedef struct io_timers_channel_mapping_t {
io_timers_channel_mapping_element_t element[MAX_IO_TIMERS];
} io_timers_channel_mapping_t;
/* array of channels in logical order */
typedef struct timer_io_channels_t {
uint32_t gpio_out;
uint32_t gpio_in;
uint8_t timer_index;
uint8_t timer_channel;
} timer_io_channels_t;
typedef void (*channel_handler_t)(void *context, const io_timers_t *timer, uint32_t chan_index,
const timer_io_channels_t *chan,
hrt_abstime isrs_time, uint16_t isrs_rcnt);
/* supplied by board-specific code */
__EXPORT extern const io_timers_t io_timers[MAX_IO_TIMERS];
__EXPORT extern const io_timers_channel_mapping_t io_timers_channel_mapping;
__EXPORT extern const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS];
__EXPORT extern const io_timers_t led_pwm_timers[MAX_LED_TIMERS];
__EXPORT extern const timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS];
__EXPORT extern io_timer_channel_allocation_t allocations[IOTimerChanModeSize];
__EXPORT int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode,
channel_handler_t channel_handler, void *context);
__EXPORT int io_timer_init_timer(unsigned timer);
__EXPORT int io_timer_set_rate(unsigned timer, unsigned rate);
__EXPORT int io_timer_set_enable(bool state, io_timer_channel_mode_t mode,
io_timer_channel_allocation_t masks);
__EXPORT int io_timer_set_rate(unsigned timer, unsigned rate);
__EXPORT uint16_t io_channel_get_ccr(unsigned channel);
__EXPORT int io_timer_set_ccr(unsigned channel, uint16_t value);
__EXPORT uint32_t io_timer_get_group(unsigned timer);
__EXPORT int io_timer_validate_channel_index(unsigned channel);
__EXPORT int io_timer_is_channel_free(unsigned channel);
__EXPORT int io_timer_free_channel(unsigned channel);
__EXPORT int io_timer_get_channel_mode(unsigned channel);
__EXPORT int io_timer_get_mode_channels(io_timer_channel_mode_t mode);
__EXPORT extern void io_timer_trigger(void);
__EXPORT void io_timer_update_dma_req(uint8_t timer, bool enable);
__EXPORT extern int io_timer_set_dshot_mode(uint8_t timer, unsigned dshot_pwm_rate, uint8_t dma_burst_length);
/**
* Returns the pin configuration for a specific channel, to be used as GPIO output.
* 0 is returned if the channel is not valid.
*/
__EXPORT uint32_t io_timer_channel_get_gpio_output(unsigned channel);
/**
* Returns the pin configuration for a specific channel, to be used as PWM input.
* 0 is returned if the channel is not valid.
*/
__EXPORT uint32_t io_timer_channel_get_as_pwm_input(unsigned channel);
__END_DECLS
@@ -0,0 +1,157 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_arch/io_timer.h>
#include <px4_arch/hw_description.h>
#include <px4_platform_common/constexpr_util.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform/io_timer_init.h>
static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
Timer::TimerChannel timer, GPIO::GPIOPin pin)
{
timer_io_channels_t ret{};
uint32_t gpio_af = 0;
switch (timer.channel) {
case Timer::ChannelA:
if (!(pin.pin & 1) && (pin.pin & 15) / 2 == (timer.timer - 1)) {
gpio_af = getGPIOPin(pin.pin) | GPIO_FUN(RP2040_GPIO_FUNC_PWM);
}
break;
case Timer::ChannelB:
if ((pin.pin & 1) && (pin.pin & 15) / 2 == (timer.timer - 1)) {
gpio_af = getGPIOPin(pin.pin) | GPIO_FUN(RP2040_GPIO_FUNC_PWM);
}
break;
default:
break;
}
ret.gpio_in = gpio_af;
ret.gpio_out = gpio_af;
ret.timer_channel = timer.channel;
// find timer index
ret.timer_index = 0xff;
const uint32_t timer_base = timerBaseRegister(timer.timer);
for (int i = 0; i < MAX_IO_TIMERS; ++i) {
if (io_timers_conf[i].base == timer_base) {
ret.timer_index = i;
break;
}
}
constexpr_assert(ret.timer_index != 0xff, "Timer not found");
return ret;
}
static inline constexpr io_timers_t initIOTimer(Timer::Timer timer)
{
bool nuttx_config_timer_enabled = false;
io_timers_t ret{};
switch (timer) {
case Timer::Timer0:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH0 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer1:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH1 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer2:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH2 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer3:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH3 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer4:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH4 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer5:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH5 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer6:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH6 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
case Timer::Timer7:
ret.base = timerBaseRegister(timer);
#ifdef CONFIG_RP2040_PWM_CH7 // Currently Nuttx doesn't have PWM support for RP2040. This is for possible future use.
nuttx_config_timer_enabled = true;
#endif
break;
}
// This is not strictly required, but for consistency let's make sure NuttX timers are disabled
constexpr_assert(!nuttx_config_timer_enabled, "IO Timer requires NuttX timer config to be disabled (KINETIS_FTMx)");
return ret;
}
@@ -0,0 +1,107 @@
#pragma once
#include <px4_platform/micro_hal.h>
__BEGIN_DECLS
#include <rp2040_spi.h>
#include <rp2040_i2c.h>
#include <rp2040_gpio.h>
// RP2040 doesn't have a bbsram. Following two defines are copied from nxp/k66.
// This will remove the errors of undefined PX4_BBSRAM_SIZE when logger module is activated.
// Fixme: using ??
#define PX4_BBSRAM_SIZE 2048
#define PX4_BBSRAM_GETDESC_IOCTL 0
// RP2040 doesn't really have a cpu register with unique id.
// However, there is a function in pico-sdk which can provide
// a device unique id from its flash which is 64 bits in length.
// For now, a common device id will be used for all RP2040 based devices.
// Take a look at board_identity.c file in version folder.
#define PX4_CPU_UUID_BYTE_LENGTH 12
#define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t))
/* The mfguid will be an array of bytes with
* MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1
*
* It will be converted to a string with the MSD on left and LSD on the right most position.
*/
#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
/* By not defining PX4_CPU_UUID_CORRECT_CORRELATION the following maintains the legacy incorrect order
* used for selection of significant digits of the UUID in the PX4 code base.
* This is done to avoid the ripple effects changing the IDs used on STM32 base platforms
*/
#if defined(PX4_CPU_UUID_CORRECT_CORRELATION)
# define PX4_CPU_UUID_WORD32_UNIQUE_H 0 /* Least significant digits change the most */
# define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */
# define PX4_CPU_UUID_WORD32_UNIQUE_L 2 /* Most significant digits change the least */
#else
/* Legacy incorrect ordering */
# define PX4_CPU_UUID_WORD32_UNIQUE_H 2 /* Most significant digits change the least */
# define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */
# define PX4_CPU_UUID_WORD32_UNIQUE_L 0 /* Least significant digits change the most */
#endif
/* Separator nnn:nnn:nnnn 2 char per byte term */
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
#define px4_savepanic(fileno, context, length) (0) // Turn off px4_savepanic for rp2040 as it is not implemented in nuttx
#define PX4_BUS_OFFSET 1 /* RP2040 buses are 0 based and adjustment is needed */
#define px4_spibus_initialize(bus_num_1based) rp2040_spibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
#define px4_i2cbus_initialize(bus_num_1based) rp2040_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
#define px4_i2cbus_uninitialize(pdev) rp2040_i2cbus_uninitialize(pdev)
// This part of the code is specific to rp2040.
// RP2040 does not have the gpio configuration process similar to stm or tiva devices.
// There are multiple different registers which are required to be configured based on the function selection.
// However, only five values are required for the most part: Pin number, Pull up/down, direction, set/clear and function
// The pinset below can be defined using a 16-bit value where,
// bits Function
// 0-4 GPIO number. 0-29 is valid.
// 5 Pull up
// 6 Pull down
// 7 Direction
// 8 Set/clear
// 9-13 GPIO function select
// 14-15 Unused
#define GPIO_PU (1 << 5) // Pull-up resistor
#define GPIO_PD (1 << 6) // Pull-down resistor
#define GPIO_OUT (1 << 7) // Output enable
#define GPIO_SET (1 << 8) // Output set
#define GPIO_FUN(func) (func << 9) // Function select
#define GPIO_NUM_MASK 0x1f
#define GPIO_PU_MASK 0x20 // GPIO PAD register mask
#define GPIO_PD_MASK 0x40 // GPIO pin number mask
#define GPIO_OUT_MASK 0x80 // GPIO pin function mask
#define GPIO_SET_MASK 0x100 // GPIO pin function mask
#define GPIO_FUN_MASK 0x3E00 // GPIO output enable mask
int rp2040_gpioconfig(uint32_t pinset);
int rp2040_setgpioevent(uint32_t pinset, bool risingedge, bool fallingedge, bool event, xcpt_t func, void *arg);
#define px4_arch_configgpio(pinset) rp2040_gpioconfig(pinset) // Defined in io_pins/rp2040_pinset.c
#define px4_arch_unconfiggpio(pinset) rp2040_gpio_init(pinset & GPIO_NUM_MASK) // Reset the pin as input SIO
#define px4_arch_gpioread(pinset) rp2040_gpio_get(pinset & GPIO_NUM_MASK) // Use gpio_get
#define px4_arch_gpiowrite(pinset, value) rp2040_gpio_put(pinset & GPIO_NUM_MASK, value) // Use gpio_put
#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) rp2040_setgpioevent(pinset,r,f,e,fp,a) // Defined in io_pins/rp2040_pinset.c
// Following are quick defines to be used with the functions defined above
// These defines create a bit-mask which is supposed to be used in the
// functions defined above to set up gpios correctly.
#define PX4_MAKE_GPIO_INPUT(gpio) (gpio | GPIO_PU | GPIO_FUN(RP2040_GPIO_FUNC_SIO))
#define PX4_MAKE_GPIO_OUTPUT_CLEAR(gpio) (gpio | GPIO_OUT | GPIO_FUN(RP2040_GPIO_FUNC_SIO))
#define PX4_MAKE_GPIO_OUTPUT_SET(gpio) (gpio | GPIO_OUT | GPIO_SET | GPIO_FUN(RP2040_GPIO_FUNC_SIO))
#define PX4_GPIO_PIN_OFF(pinset) ((pinset & GPIO_NUM_MASK) | GPIO_FUN(RP2040_GPIO_FUNC_SIO) | GPIO_PD)
#define px4_cache_aligned_data()
#define px4_cache_aligned_alloc malloc
__END_DECLS
@@ -0,0 +1,122 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_arch/hw_description.h>
#include <px4_platform_common/spi.h>
#include <px4_arch/micro_hal.h>
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint32_t devid, SPI::CS cs_gpio, SPI::DRDY drdy_gpio = {})
{
px4_spi_bus_device_t ret{};
ret.cs_gpio = getGPIOPin(cs_gpio.pin) | (GPIO_OUT | GPIO_SET);
ret.drdy_gpio = getGPIOPin(drdy_gpio.pin) | GPIO_PU; // GPIO_PU taken from kinetis
if (PX4_SPIDEVID_TYPE(devid) == 0) { // it's a PX4 device (internal or external)
ret.devid = PX4_SPIDEV_ID(PX4_SPI_DEVICE_ID, devid);
} else { // it's a NuttX device (e.g. SPIDEV_FLASH(0))
ret.devid = devid;
}
ret.devtype_driver = PX4_SPI_DEV_ID(devid);
return ret;
}
static inline constexpr px4_spi_bus_t initSPIBus(SPI::Bus bus, const px4_spi_bus_devices_t &devices,
GPIO::GPIOPin power_enable = {})
{
px4_spi_bus_t ret{};
ret.requires_locking = false;
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
ret.devices[i] = devices.devices[i];
if (ret.devices[i].cs_gpio != 0) {
if (PX4_SPI_DEVICE_ID == PX4_SPIDEVID_TYPE(ret.devices[i].devid)) {
int same_devices_count = 0;
for (int j = 0; j < i; ++j) {
if (ret.devices[j].cs_gpio != 0) {
same_devices_count += (ret.devices[i].devid & 0xff) == (ret.devices[j].devid & 0xff);
}
}
// increment the 2. LSB byte to allow multiple devices of the same type
ret.devices[i].devid |= same_devices_count << 8;
} else {
// A bus potentially requires locking if it is accessed by non-PX4 devices (i.e. NuttX drivers)
ret.requires_locking = true;
}
}
}
ret.bus = (int)bus;
ret.is_external = false;
ret.power_enable_gpio = getGPIOPin(power_enable.pin) | GPIO_OUT;
return ret;
}
// just a wrapper since we cannot pass brace-enclosed initialized arrays directly as arguments
struct bus_device_external_cfg_array_t {
SPI::bus_device_external_cfg_t devices[SPI_BUS_MAX_DEVICES];
};
static inline constexpr px4_spi_bus_t initSPIBusExternal(SPI::Bus bus, const bus_device_external_cfg_array_t &devices)
{
px4_spi_bus_t ret{};
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
ret.devices[i] = initSPIDevice(i, devices.devices[i].cs_gpio, devices.devices[i].drdy_gpio);
}
ret.bus = (int)bus;
ret.is_external = true;
ret.requires_locking = false; // external buses are never accessed by NuttX drivers
return ret;
}
static inline constexpr SPI::bus_device_external_cfg_t initSPIConfigExternal(SPI::CS cs_gpio, SPI::DRDY drdy_gpio = {})
{
SPI::bus_device_external_cfg_t ret{};
ret.cs_gpio = cs_gpio;
ret.drdy_gpio = drdy_gpio;
return ret;
}
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_buses_conf[SPI_BUS_MAX_BUS_ITEMS]);
@@ -0,0 +1,42 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(arch_io_pins
io_timer.c
pwm_servo.c
# pwm_trigger.c
# input_capture.c
rp2040_pinset.c
)
target_compile_options(arch_io_pins PRIVATE ${MAX_CUSTOM_OPT_LEVEL})

Some files were not shown because too many files have changed in this diff Show More