Compare commits

...

9 Commits

Author SHA1 Message Date
David Sidrane 2e5842dbeb px4_fmu-v6xrt:Use multi-PHY 2024-01-04 10:06:24 -08:00
David Sidrane b1f09b2453 NuttX with multi-PHY 2024-01-04 10:06:24 -08:00
David Sidrane 01e66f82a7 px4_fmu-v6xrt:Use TJA1103 Phy 2024-01-03 06:19:44 -08:00
David Sidrane 75fb07bdd4 px4_fmu-v6xrt:Fix Probes 2024-01-03 06:19:44 -08:00
David Sidrane 1a5c1891a7 px4_fmu-v6xrt:Default to Selecting ACD6V6 2024-01-03 06:19:44 -08:00
David Sidrane c97afa2e36 px4_fmu-v6xrt:Use RC_SERIAL_SWAP_USING_SINGLEWIRE 2024-01-03 06:19:44 -08:00
David Sidrane 85694a62e1 RCInput:Add Support for RX-TX SWAP using onewire
A board can optionaly define RC_SERIAL_SWAP_USING_SINGLEWIRE
   If the board is wired board with TX to the input (Swapped) and
   the SoC does not support U[S]ART level RX-TX swapping to allow
   useing onewire to do the swap if and only if:

     RC_SERIAL_SWAP_USING_SINGLEWIRE   is defined
     RC_SERIAL_SWAP_RXTX               is defined
     TIOCSSWAP                         is defined and retuns !OK
     TIOCSSINGLEWIRE                   is defined
2024-01-03 06:19:44 -08:00
David Sidrane f6fd9f9ae1 px4_fmuv6xrt::Support base version selection 2024-01-03 06:19:40 -08:00
David Sidrane b3048c3344 rt1170:spi_hw_description:Support Validation and HW selection 2024-01-03 06:16:30 -08:00
10 changed files with 239 additions and 54 deletions

View File

@ -265,6 +265,32 @@
/* ETH Disambiguation *******************************************************/
#define BOARD_ETH0_PHY_LIST \
{ \
"LAN8742A", \
MII_PHYID1_LAN8742A, \
MII_PHYID2_LAN8742A, \
MII_LAN8740_SCSR, \
0, \
0xffff, \
MII_LAN8720_SPSCR_10MBPS, \
MII_LAN8720_SPSCR_100MBPS, \
MII_LAN8720_SPSCR_DUPLEX, \
22 \
}, \
{ \
"TJA1103", \
MII_PHYID1_TJA1103, \
MII_PHYID2_TJA1103, \
0xffff, \
18, \
0xffff, \
0 , \
MII_LAN8720_SPSCR_100MBPS, \
MII_LAN8720_SPSCR_DUPLEX, \
45, \
}, \
// This is the ENET_1G interface.
#if defined(CONFIG_ETH0_PHY_TJA1103)
@ -292,16 +318,20 @@
#include <imxrt_gpio.h>
#include <imxrt_iomuxc.h>
// add -I<full path> build/px4_fmu-v6xrt_default/NuttX/nuttx/arch/arm/src/chip \ to NuttX Makedefs.in
#define PROBE_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE)
#define PROBE_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_SLEW_FAST)
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 /* GPIO_B0_06 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_2 /* GPIO_EMC_08 */ (GPIO_PORT4 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_3 /* GPIO_EMC_10 */ (GPIO_PORT4 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_4 /* GPIO_AD_B0_09 */ (GPIO_PORT1 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_5 /* GPIO_EMC_33 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_6 /* GPIO_EMC_30 */ (GPIO_PORT4 | GPIO_PIN30 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_7 /* GPIO_EMC_04 */ (GPIO_PORT4 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_8 /* GPIO_EMC_01 */ (GPIO_PORT4 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_1 /* GPIO_EMC_B1_23 */ (GPIO_PORT1 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_2 /* GPIO_EMC_B1_25 */ (GPIO_PORT1 | GPIO_PIN25 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_3 /* GPIO_EMC_B1_27 */ (GPIO_PORT1 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_4 /* GPIO_EMC_B1_06 */ (GPIO_PORT1 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_5 /* GPIO_EMC_B1_08 */ (GPIO_PORT1 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_6 /* GPIO_EMC_B1_10 */ (GPIO_PORT1 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_7 /* GPIO_EMC_B1_19 */ (GPIO_PORT1 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_8 /* GPIO_EMC_B1_29 */ (GPIO_PORT1 | GPIO_PIN29 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_9 /* GPIO_EMC_B1_31 */ (GPIO_PORT1 | GPIO_PIN31 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_10 /* GPIO_EMC_B1_21 */ (GPIO_PORT1 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_11 /* GPIO_EMC_B1_00 */ (GPIO_PORT1 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_12 /* GPIO_EMC_B1_02 */ (GPIO_PORT1 | GPIO_PIN2 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX)
# define PROBE_INIT(mask) \
do { \
@ -313,6 +343,10 @@
if ((mask)& PROBE_N(6)) { imxrt_config_gpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { imxrt_config_gpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { imxrt_config_gpio(PROBE_8); } \
if ((mask)& PROBE_N(9)) { imxrt_config_gpio(PROBE_9); } \
if ((mask)& PROBE_N(10)) { imxrt_config_gpio(PROBE_10); } \
if ((mask)& PROBE_N(11)) { imxrt_config_gpio(PROBE_11); } \
if ((mask)& PROBE_N(12)) { imxrt_config_gpio(PROBE_12); } \
} while(0)
# define PROBE(n,s) do {imxrt_gpio_write(PROBE_##n,(s));}while(0)

View File

@ -51,7 +51,7 @@ CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_SIZE=70
CONFIG_ETH0_PHY_LAN8742A=y
CONFIG_ETH0_PHY_MULTI=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y

View File

@ -296,7 +296,11 @@
#define GPIO_HW_REV_SENSE /* GPIO_AD_22 GPIO9 Pin 21 */ ADC_GPIO(4, 21)
#define GPIO_HW_VER_SENSE /* GPIO_AD_23 GPIO9 Pin 22 */ ADC_GPIO(5, 22)
#define HW_INFO_INIT_PREFIX "V6XRT"
#define V6XRT_00 HW_VER_REV(0x0,0x0) // First Release
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0 on HB Base and T1 Pase
// Base/FMUM
#define V6XRT00 HW_VER_REV(0x0,0x0) // First Release
#define V6XRT30 HW_VER_REV(0x3,0x0) // T1 Base w/o PX4IO
#define BOARD_I2C_LATEINIT 1 /* See Note about SE550 Eanable */
@ -385,7 +389,7 @@
#define GPIO_NFC_GPIO /* GPIO_EMC_B1_04 GPIO1_IO04 */ (GPIO_PORT1 | GPIO_PIN4 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_GPIO_EMC_B2_12 /* GPIO_EMC_B2_12 AKA PD15, PH11 */ (GPIO_PORT2 | GPIO_PIN22 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_GPIO_EMC_B2_12 /* GPIO_EMC_B2_12 AKA PD15, PH11 */ (GPIO_PORT2 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | OUT_IOMUX)
/* 10/100 Mbps Ethernet & Gigabit Ethernet */
@ -448,8 +452,10 @@
#define HRT_PPM_CHANNEL /* GPIO_EMC_B1_09 GPIO_GPT5_CAPTURE1_1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* GPIO_EMC_B1_09 GPT1_CAPTURE2 */ (GPIO_GPT5_CAPTURE1_1 | GENERAL_INPUT_IOMUX)
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE 1 // Suport Single wire wiring
#define RC_SERIAL_SWAP_RXTX 1 // Set Swap (but not supported in HW) to use Single wire
#define RC_SERIAL_SWAP_USING_SINGLEWIRE 1 // Set to use Single wire swap as HW does not support swap
/* FLEXSPI4 */

View File

@ -98,8 +98,36 @@ static const px4_hw_mft_item_t hw_mft_list_V00[] = {
},
};
static const px4_hw_mft_item_t hw_mft_list_V30[] = {
{
// PX4_MFT_PX4IO
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
// PX4_MFT_USB
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN2
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN3
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{V6XRT_00, hw_mft_list_V00, arraySize(hw_mft_list_V00)},
{V6XRT00, hw_mft_list_V00, arraySize(hw_mft_list_V00)},
{V6XRT30, hw_mft_list_V30, arraySize(hw_mft_list_V30)},
};
/************************************************************************************
@ -122,7 +150,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
@ -133,7 +161,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
PX4_ERR("Board %4" PRIx32 " is not supported!", ver_rev);
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}

View File

@ -41,47 +41,46 @@
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_config.h>
#include <px4_log.h>
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
initSPIHWVersion(V6XRT00, {
initSPIBus(SPI::Bus::LPSPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port2, GPIO::Pin11}, SPI::DRDY{GPIO::Port3, GPIO::Pin19}), /* GPIO_EMC_B2_01 GPIO2_IO11, GPIO_AD_20, GPIO3_IO19 */
}, {GPIO::Port2, GPIO::Pin1}), // Power GPIO_EMC_B1_33 GPIO2_IO01
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
initSPIBus(SPI::Bus::LPSPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port3, GPIO::Pin24}, SPI::DRDY{GPIO::Port2, GPIO::Pin7}), /* GPIO_AD_25 GPIO3_IO24, GPIO_EMC_B1_39 GPIO2_IO07 */
}, {GPIO::Port1, GPIO::Pin22}), // Power GPIO_EMC_B1_22 GPIO1_IO22
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <systemlib/px4_macros.h>
#include <px4_platform/gpio.h>
initSPIBus(SPI::Bus::LPSPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin28}), /* GPIO_EMC_B2_08 GPIO2_IO18, GPIO_EMC_B2_18 GPIO2_IO28 */
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin15}), /* GPIO_EMC_B2_05 GPIO2_IO15 */
}, {GPIO::Port1, GPIO::Pin14}), // Power GPIO_EMC_B1_14 GPIO1_IO14
#include <arm_internal.h>
#include <chip.h>
#include "imxrt_lpspi.h"
#include "imxrt_gpio.h"
#include "board_config.h"
#include <systemlib/err.h>
initSPIBusExternal(SPI::Bus::LPSPI6, {
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin9}, SPI::DRDY{GPIO::Port1, GPIO::Pin5}), /* GPIO_LPSR_09 GPIO6_IO09 GPIO_EMC_B1_05 GPIO1_IO05*/
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin8}, SPI::DRDY{GPIO::Port1, GPIO::Pin7}), /* GPIO_LPSR_08 GPIO6_IO08 GPIO_EMC_B1_07 GPIO1_IO07*/
}),
}),
#ifdef CONFIG_IMXRT_LPSPI
initSPIHWVersion(V6XRT30, {
initSPIBus(SPI::Bus::LPSPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port2, GPIO::Pin11}, SPI::DRDY{GPIO::Port3, GPIO::Pin19}), /* GPIO_EMC_B2_01 GPIO2_IO11, GPIO_AD_20, GPIO3_IO19 */
}, {GPIO::Port2, GPIO::Pin1}), // Power GPIO_EMC_B1_33 GPIO2_IO01
initSPIBus(SPI::Bus::LPSPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port3, GPIO::Pin24}, SPI::DRDY{GPIO::Port2, GPIO::Pin7}), /* GPIO_AD_25 GPIO3_IO24, GPIO_EMC_B1_39 GPIO2_IO07 */
}, {GPIO::Port1, GPIO::Pin22}), // Power GPIO_EMC_B1_22 GPIO1_IO22
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::LPSPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42686P, SPI::CS{GPIO::Port2, GPIO::Pin11}, SPI::DRDY{GPIO::Port3, GPIO::Pin19}), /* GPIO_EMC_B2_01 GPIO2_IO11, GPIO_AD_20, GPIO3_IO19 */
}, {GPIO::Port2, GPIO::Pin1}), // Power GPIO_EMC_B1_33 GPIO2_IO01
initSPIBus(SPI::Bus::LPSPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin28}), /* GPIO_EMC_B2_08 GPIO2_IO18, GPIO_EMC_B2_18 GPIO2_IO28 */
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin15}), /* GPIO_EMC_B2_05 GPIO2_IO15 */
}, {GPIO::Port1, GPIO::Pin14}), // Power GPIO_EMC_B1_14 GPIO1_IO14
initSPIBus(SPI::Bus::LPSPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port3, GPIO::Pin24}, SPI::DRDY{GPIO::Port2, GPIO::Pin7}), /* GPIO_AD_25 GPIO3_IO24, GPIO_EMC_B1_39 GPIO2_IO07 */
}, {GPIO::Port1, GPIO::Pin22}), // Power GPIO_EMC_B1_22 GPIO1_IO22
initSPIBus(SPI::Bus::LPSPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin28}), /* GPIO_EMC_B2_08 GPIO2_IO18, GPIO_EMC_B2_18 GPIO2_IO28 */
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin15}), /* GPIO_EMC_B2_05 GPIO2_IO15 */
}, {GPIO::Port1, GPIO::Pin14}), // Power GPIO_EMC_B1_14 GPIO1_IO14
initSPIBusExternal(SPI::Bus::LPSPI6, {
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin9}, SPI::DRDY{GPIO::Port1, GPIO::Pin5}), /* GPIO_LPSR_09 GPIO6_IO09 GPIO_EMC_B1_05 GPIO1_IO05*/
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin8}, SPI::DRDY{GPIO::Port1, GPIO::Pin7}), /* GPIO_LPSR_08 GPIO6_IO08 GPIO_EMC_B1_07 GPIO1_IO07*/
initSPIBusExternal(SPI::Bus::LPSPI6, {
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin9}, SPI::DRDY{GPIO::Port1, GPIO::Pin5}), /* GPIO_LPSR_09 GPIO6_IO09 GPIO_EMC_B1_05 GPIO1_IO05*/
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin8}, SPI::DRDY{GPIO::Port1, GPIO::Pin7}), /* GPIO_LPSR_08 GPIO6_IO08 GPIO_EMC_B1_07 GPIO1_IO07*/
}),
}),
};
#endif
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);

View File

@ -458,6 +458,15 @@ static inline bool board_rc_singlewire(const char *device) { return false; }
* A board may define RC_SERIAL_SWAP_RXTX, so that RC_SERIAL_PORT is configured
* as UART with RX/TX swapped.
*
* It can optionaly define RC_SERIAL_SWAP_USING_SINGLEWIRE If the board is wired
* with TX to the input (Swapped) and the SoC does not support U[S]ART level
* HW swapping, then use onewire to do the swap if and only if:
*
* RC_SERIAL_SWAP_USING_SINGLEWIRE is defined
* RC_SERIAL_SWAP_RXTX is defined
* TIOCSSWAP is defined and retuns !OK
* TIOCSSINGLEWIRE is defined
*
* Input Parameters:
* device: serial device, e.g. "/dev/ttyS0"
*

@ -1 +1 @@
Subproject commit 1e3aaefc60a18838dc696e8f0f335d8c989f35cc
Subproject commit 09ed3d1ba226e886ca8545baea748083ba629f40

View File

@ -40,6 +40,57 @@
#include <imxrt_gpio.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_IMXRT_LPSPI1
true,
#else
false,
#endif
#ifdef CONFIG_IMXRT_LPSPI2
true,
#else
false,
#endif
#ifdef CONFIG_IMXRT_LPSPI3
true,
#else
false,
#endif
#ifdef CONFIG_IMXRT_LPSPI4
true,
#else
false,
#endif
#ifdef CONFIG_IMXRT_LPSPI5
true,
#else
false,
#endif
#ifdef CONFIG_IMXRT_LPSPI6
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_STM32H7_SPIx)");
}
return false;
}
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{};
@ -132,8 +183,41 @@ static inline constexpr SPI::bus_device_external_cfg_t initSPIConfigExternal(SPI
return ret;
}
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
struct px4_spi_bus_array_t {
px4_spi_bus_t item[SPI_BUS_MAX_BUS_ITEMS];
};
static inline constexpr px4_spi_bus_all_hw_t initSPIHWVersion(int hw_version_revision,
const px4_spi_bus_array_t &bus_items)
{
return true;
px4_spi_bus_all_hw_t ret{};
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
ret.buses[i] = bus_items.item[i];
}
ret.board_hw_version_revision = hw_version_revision;
return ret;
}
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_buses_conf[SPI_BUS_MAX_BUS_ITEMS]);
constexpr bool validateSPIConfig(const px4_spi_bus_all_hw_t spi_buses_conf[BOARD_NUM_SPI_CFG_HW_VERSIONS])
{
for (int ver = 0; ver < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++ver) {
validateSPIConfig(spi_buses_conf[ver].buses);
}
for (int ver = 1; ver < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++ver) {
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
const bool equal_power_enable_gpio = spi_buses_conf[ver].buses[i].power_enable_gpio == spi_buses_conf[ver -
1].buses[i].power_enable_gpio;
// currently board_control_spi_sensors_power_configgpio() depends on that - this restriction can be removed
// by ensuring board_control_spi_sensors_power_configgpio() is called after the hw version is determined
// and SPI config is initialized.
constexpr_assert(equal_power_enable_gpio, "All HW versions must define the same power enable GPIO");
}
}
return false;
}
#endif // CONFIG_SPI

View File

@ -302,6 +302,25 @@ void RCInput::rc_io_invert(bool invert)
}
}
void RCInput::swap_rx_tx()
{
#if defined(RC_SERIAL_SWAP_USING_SINGLEWIRE)
int rv = -ENOTTY;
# if defined(TIOCSSWAP)
rv = ioctl(_rcs_fd, TIOCSSWAP, SER_SWAP_ENABLED);
# endif // TIOCSSWAP
# ifdef TIOCSSINGLEWIRE
if (rv != OK) {
ioctl(_rcs_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
}
# else
UNUSED(rv);
# endif // TIOCSSINGLEWIRE
#endif // RC_SERIAL_SWAP_USING_SINGLEWIRE
}
void RCInput::Run()
{
if (should_exit()) {
@ -494,6 +513,7 @@ void RCInput::Run()
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
dsm_config(_rcs_fd);
swap_rx_tx();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
@ -531,6 +551,7 @@ void RCInput::Run()
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
dsm_config(_rcs_fd);
swap_rx_tx();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
@ -582,6 +603,7 @@ void RCInput::Run()
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
dsm_config(_rcs_fd);
swap_rx_tx();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
@ -660,6 +682,7 @@ void RCInput::Run()
_rc_scan_begin = cycle_timestamp;
// Configure serial port for CRSF
crsf_config(_rcs_fd);
swap_rx_tx();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
@ -708,6 +731,7 @@ void RCInput::Run()
_rc_scan_begin = cycle_timestamp;
// Configure serial port for GHST
ghst_config(_rcs_fd);
swap_rx_tx();
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);

View File

@ -126,6 +126,7 @@ private:
void set_rc_scan_state(RC_SCAN _rc_scan_state);
void rc_io_invert(bool invert);
void swap_rx_tx(void);
input_rc_s _input_rc{};
hrt_abstime _rc_scan_begin{0};