forked from Archive/PX4-Autopilot
i2c+spi: extend hw_description for I2C + SPI
This commit is contained in:
parent
a2c270e484
commit
af15c7d945
|
@ -232,3 +232,159 @@ enum class Pad {
|
|||
|
||||
}
|
||||
|
||||
/*
|
||||
* GPIO
|
||||
*/
|
||||
|
||||
namespace GPIO
|
||||
{
|
||||
enum Port {
|
||||
PortInvalid = 0,
|
||||
Port1,
|
||||
Port2,
|
||||
Port3,
|
||||
Port4,
|
||||
Port5,
|
||||
};
|
||||
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,
|
||||
Pin30,
|
||||
Pin31,
|
||||
};
|
||||
struct GPIOPin {
|
||||
Port port;
|
||||
Pin pin;
|
||||
};
|
||||
}
|
||||
|
||||
static inline constexpr uint32_t getGPIOPort(GPIO::Port port)
|
||||
{
|
||||
switch (port) {
|
||||
case GPIO::Port1: return GPIO_PORT1;
|
||||
|
||||
case GPIO::Port2: return GPIO_PORT2;
|
||||
|
||||
case GPIO::Port3: return GPIO_PORT3;
|
||||
|
||||
case GPIO::Port4: return GPIO_PORT4;
|
||||
|
||||
case GPIO::Port5: return GPIO_PORT5;
|
||||
|
||||
default: break;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin)
|
||||
{
|
||||
switch (pin) {
|
||||
case GPIO::Pin0: return GPIO_PIN0;
|
||||
|
||||
case GPIO::Pin1: return GPIO_PIN1;
|
||||
|
||||
case GPIO::Pin2: return GPIO_PIN2;
|
||||
|
||||
case GPIO::Pin3: return GPIO_PIN3;
|
||||
|
||||
case GPIO::Pin4: return GPIO_PIN4;
|
||||
|
||||
case GPIO::Pin5: return GPIO_PIN5;
|
||||
|
||||
case GPIO::Pin6: return GPIO_PIN6;
|
||||
|
||||
case GPIO::Pin7: return GPIO_PIN7;
|
||||
|
||||
case GPIO::Pin8: return GPIO_PIN8;
|
||||
|
||||
case GPIO::Pin9: return GPIO_PIN9;
|
||||
|
||||
case GPIO::Pin10: return GPIO_PIN10;
|
||||
|
||||
case GPIO::Pin11: return GPIO_PIN11;
|
||||
|
||||
case GPIO::Pin12: return GPIO_PIN12;
|
||||
|
||||
case GPIO::Pin13: return GPIO_PIN13;
|
||||
|
||||
case GPIO::Pin14: return GPIO_PIN14;
|
||||
|
||||
case GPIO::Pin15: return GPIO_PIN15;
|
||||
|
||||
case GPIO::Pin16: return GPIO_PIN16;
|
||||
|
||||
case GPIO::Pin17: return GPIO_PIN17;
|
||||
|
||||
case GPIO::Pin18: return GPIO_PIN18;
|
||||
|
||||
case GPIO::Pin19: return GPIO_PIN19;
|
||||
|
||||
case GPIO::Pin20: return GPIO_PIN20;
|
||||
|
||||
case GPIO::Pin21: return GPIO_PIN21;
|
||||
|
||||
case GPIO::Pin22: return GPIO_PIN22;
|
||||
|
||||
case GPIO::Pin23: return GPIO_PIN23;
|
||||
|
||||
case GPIO::Pin24: return GPIO_PIN24;
|
||||
|
||||
case GPIO::Pin25: return GPIO_PIN25;
|
||||
|
||||
case GPIO::Pin26: return GPIO_PIN26;
|
||||
|
||||
case GPIO::Pin27: return GPIO_PIN27;
|
||||
|
||||
case GPIO::Pin28: return GPIO_PIN28;
|
||||
|
||||
case GPIO::Pin29: return GPIO_PIN29;
|
||||
|
||||
case GPIO::Pin30: return GPIO_PIN30;
|
||||
|
||||
case GPIO::Pin31: return GPIO_PIN31;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
namespace SPI
|
||||
{
|
||||
|
||||
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,55 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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,133 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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 <imxrt_gpio.h>
|
||||
|
||||
#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST)
|
||||
|
||||
#define DRDY_IOMUX (IOMUX_SCHMITT_TRIGGER | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ)
|
||||
|
||||
#define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
|
||||
|
||||
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 = getGPIOPort(cs_gpio.port) | getGPIOPin(cs_gpio.pin) | (GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX);
|
||||
|
||||
if (drdy_gpio.port != GPIO::PortInvalid) {
|
||||
ret.drdy_gpio = getGPIOPort(drdy_gpio.port) | getGPIOPin(drdy_gpio.pin) | (GPIO_INPUT | DRDY_IOMUX);
|
||||
}
|
||||
|
||||
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(int bus, const px4_spi_bus_devices_t &devices,
|
||||
GPIO::GPIOPin power_enable = {})
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
ret.requires_locking = true; // TODO: set this to false once all drivers are converted to use the I2CSPIDriver class
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
ret.devices[i] = devices.devices[i];
|
||||
|
||||
// check that the same device is configured only once (the chip-select code depends on that)
|
||||
for (int j = i + 1; j < SPI_BUS_MAX_DEVICES; ++j) {
|
||||
if (ret.devices[j].cs_gpio != 0) {
|
||||
constexpr_assert(ret.devices[i].devid != ret.devices[j].devid, "Same device configured multiple times");
|
||||
}
|
||||
}
|
||||
|
||||
if (ret.devices[i].cs_gpio != 0) {
|
||||
// A bus potentially requires locking if it is accessed by non-PX4 devices (i.e. NuttX drivers)
|
||||
if (PX4_SPI_DEVICE_ID != PX4_SPIDEVID_TYPE(ret.devices[i].devid)) {
|
||||
ret.requires_locking = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = false;
|
||||
|
||||
if (power_enable.port != GPIO::PortInvalid) {
|
||||
ret.power_enable_gpio = getGPIOPort(power_enable.port) | getGPIOPin(power_enable.pin) |
|
||||
(GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX);
|
||||
}
|
||||
|
||||
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(int bus, const bus_device_external_cfg_array_t &devices)
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (devices.devices[i].cs_gpio.port == GPIO::PortInvalid) {
|
||||
break;
|
||||
}
|
||||
|
||||
ret.devices[i] = initSPIDevice(i, devices.devices[i].cs_gpio, devices.devices[i].drdy_gpio);
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = true;
|
||||
// TODO: set requires_locking to false once all drivers are converted to use the I2CSPIDriver class
|
||||
ret.requires_locking = true; // 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;
|
||||
}
|
||||
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../kinetis/include/px4_arch/i2c_hw_description.h"
|
||||
|
|
@ -0,0 +1,41 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../kinetis/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
|
@ -92,7 +92,8 @@ static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer)
|
|||
namespace GPIO
|
||||
{
|
||||
enum Port {
|
||||
PortA = 0,
|
||||
PortInvalid = 0,
|
||||
PortA,
|
||||
PortB,
|
||||
PortC,
|
||||
PortD,
|
||||
|
@ -150,6 +151,8 @@ static inline constexpr uint32_t getGPIOPort(GPIO::Port port)
|
|||
case GPIO::PortD: return PIN_PORTD;
|
||||
|
||||
case GPIO::PortE: return PIN_PORTE;
|
||||
|
||||
default: break;
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
@ -226,3 +229,15 @@ static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin)
|
|||
return 0;
|
||||
}
|
||||
|
||||
namespace SPI
|
||||
{
|
||||
|
||||
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,55 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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;
|
||||
}
|
||||
|
|
@ -85,6 +85,8 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t
|
|||
case GPIO::PortE:
|
||||
gpio_af = PIN_ALT6;
|
||||
break;
|
||||
|
||||
default: break;
|
||||
}
|
||||
|
||||
uint32_t gpio_pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin);
|
||||
|
|
|
@ -0,0 +1,127 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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 <kinetis.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 = getGPIOPort(cs_gpio.port) | getGPIOPin(cs_gpio.pin) | (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE);
|
||||
|
||||
if (drdy_gpio.port != GPIO::PortInvalid) {
|
||||
ret.drdy_gpio = getGPIOPort(drdy_gpio.port) | getGPIOPin(drdy_gpio.pin) | (GPIO_PULLUP | PIN_INT_BOTH);
|
||||
}
|
||||
|
||||
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(int bus, const px4_spi_bus_devices_t &devices,
|
||||
GPIO::GPIOPin power_enable = {})
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
ret.requires_locking = true; // TODO: set this to false once all drivers are converted to use the I2CSPIDriver class
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
ret.devices[i] = devices.devices[i];
|
||||
|
||||
// check that the same device is configured only once (the chip-select code depends on that)
|
||||
for (int j = i + 1; j < SPI_BUS_MAX_DEVICES; ++j) {
|
||||
if (ret.devices[j].cs_gpio != 0) {
|
||||
constexpr_assert(ret.devices[i].devid != ret.devices[j].devid, "Same device configured multiple times");
|
||||
}
|
||||
}
|
||||
|
||||
if (ret.devices[i].cs_gpio != 0) {
|
||||
// A bus potentially requires locking if it is accessed by non-PX4 devices (i.e. NuttX drivers)
|
||||
if (PX4_SPI_DEVICE_ID != PX4_SPIDEVID_TYPE(ret.devices[i].devid)) {
|
||||
ret.requires_locking = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = false;
|
||||
|
||||
if (power_enable.port != GPIO::PortInvalid) {
|
||||
ret.power_enable_gpio = getGPIOPort(power_enable.port) | getGPIOPin(power_enable.pin) |
|
||||
(GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE);
|
||||
}
|
||||
|
||||
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(int bus, const bus_device_external_cfg_array_t &devices)
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (devices.devices[i].cs_gpio.port == GPIO::PortInvalid) {
|
||||
break;
|
||||
}
|
||||
|
||||
ret.devices[i] = initSPIDevice(i, devices.devices[i].cs_gpio, devices.devices[i].drdy_gpio);
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = true;
|
||||
// TODO: set requires_locking to false once all drivers are converted to use the I2CSPIDriver class
|
||||
ret.requires_locking = true; // 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;
|
||||
}
|
||||
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../imxrt/include/px4_arch/i2c_hw_description.h"
|
||||
|
|
@ -0,0 +1,41 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../imxrt/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
|
@ -167,7 +167,8 @@ static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer)
|
|||
namespace GPIO
|
||||
{
|
||||
enum Port {
|
||||
PortA = 0,
|
||||
PortInvalid = 0,
|
||||
PortA,
|
||||
PortB,
|
||||
PortC,
|
||||
PortD,
|
||||
|
@ -176,6 +177,8 @@ enum Port {
|
|||
PortG,
|
||||
PortH,
|
||||
PortI,
|
||||
PortJ,
|
||||
PortK,
|
||||
};
|
||||
enum Pin {
|
||||
Pin0 = 0,
|
||||
|
@ -229,6 +232,14 @@ static inline constexpr uint32_t getGPIOPort(GPIO::Port port)
|
|||
|
||||
case GPIO::PortI: return GPIO_PORTI;
|
||||
#endif
|
||||
#ifdef GPIO_PORTJ
|
||||
|
||||
case GPIO::PortJ: return GPIO_PORTJ;
|
||||
#endif
|
||||
#ifdef GPIO_PORTK
|
||||
|
||||
case GPIO::PortK: return GPIO_PORTK;
|
||||
#endif
|
||||
|
||||
default: break;
|
||||
}
|
||||
|
@ -275,3 +286,16 @@ static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin)
|
|||
return 0;
|
||||
}
|
||||
|
||||
namespace SPI
|
||||
{
|
||||
|
||||
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,55 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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,164 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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 <stm32_gpio.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 = getGPIOPort(cs_gpio.port) | getGPIOPin(cs_gpio.pin) | (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz |
|
||||
GPIO_OUTPUT_SET);
|
||||
|
||||
if (drdy_gpio.port != GPIO::PortInvalid) {
|
||||
ret.drdy_gpio = getGPIOPort(drdy_gpio.port) | getGPIOPin(drdy_gpio.pin) | (GPIO_INPUT | GPIO_FLOAT | GPIO_EXTI);
|
||||
}
|
||||
|
||||
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(int bus, const px4_spi_bus_devices_t &devices,
|
||||
GPIO::GPIOPin power_enable = {})
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
ret.requires_locking = true; // TODO: set this to false once all drivers are converted to use the I2CSPIDriver class
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
ret.devices[i] = devices.devices[i];
|
||||
|
||||
// check that the same device is configured only once (the chip-select code depends on that)
|
||||
for (int j = i + 1; j < SPI_BUS_MAX_DEVICES; ++j) {
|
||||
if (ret.devices[j].cs_gpio != 0) {
|
||||
constexpr_assert(ret.devices[i].devid != ret.devices[j].devid, "Same device configured multiple times");
|
||||
}
|
||||
}
|
||||
|
||||
if (ret.devices[i].cs_gpio != 0) {
|
||||
// A bus potentially requires locking if it is accessed by non-PX4 devices (i.e. NuttX drivers)
|
||||
if (PX4_SPI_DEVICE_ID != PX4_SPIDEVID_TYPE(ret.devices[i].devid)) {
|
||||
ret.requires_locking = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = false;
|
||||
|
||||
if (power_enable.port != GPIO::PortInvalid) {
|
||||
ret.power_enable_gpio = getGPIOPort(power_enable.port) | getGPIOPin(power_enable.pin) |
|
||||
(GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_2MHz | GPIO_OUTPUT_CLEAR);
|
||||
}
|
||||
|
||||
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(int bus, const bus_device_external_cfg_array_t &devices)
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (devices.devices[i].cs_gpio.port == GPIO::PortInvalid) {
|
||||
break;
|
||||
}
|
||||
|
||||
ret.devices[i] = initSPIDevice(i, devices.devices[i].cs_gpio, devices.devices[i].drdy_gpio);
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = true;
|
||||
// TODO: set requires_locking to false once all drivers are converted to use the I2CSPIDriver class
|
||||
ret.requires_locking = true; // 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;
|
||||
}
|
||||
|
||||
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, const px4_spi_bus_array_t &bus_items)
|
||||
{
|
||||
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 = hw_version;
|
||||
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;
|
||||
}
|
|
@ -0,0 +1,36 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 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_spi
|
||||
spi.cpp
|
||||
)
|
|
@ -0,0 +1,574 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 <systemlib/px4_macros.h>
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
// wrapper for stm32f7
|
||||
#ifdef CONFIG_STM32F7_SPI1
|
||||
#define CONFIG_STM32_SPI1
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI2
|
||||
#define CONFIG_STM32_SPI2
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI3
|
||||
#define CONFIG_STM32_SPI3
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
#define CONFIG_STM32_SPI4
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
#define CONFIG_STM32_SPI5
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI6
|
||||
#define CONFIG_STM32_SPI6
|
||||
#endif
|
||||
|
||||
// wrapper for stm32h7
|
||||
#ifdef CONFIG_STM32H7_SPI1
|
||||
#define CONFIG_STM32_SPI1
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI2
|
||||
#define CONFIG_STM32_SPI2
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI3
|
||||
#define CONFIG_STM32_SPI3
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI4
|
||||
#define CONFIG_STM32_SPI4
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI5
|
||||
#define CONFIG_STM32_SPI5
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI6
|
||||
#define CONFIG_STM32_SPI6
|
||||
#endif
|
||||
|
||||
static const px4_spi_bus_t *_spi_bus1;
|
||||
static const px4_spi_bus_t *_spi_bus2;
|
||||
static const px4_spi_bus_t *_spi_bus3;
|
||||
static const px4_spi_bus_t *_spi_bus4;
|
||||
static const px4_spi_bus_t *_spi_bus5;
|
||||
static const px4_spi_bus_t *_spi_bus6;
|
||||
|
||||
static void spi_bus_configgpio_cs(const px4_spi_bus_t *bus)
|
||||
{
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (bus->devices[i].cs_gpio != 0) {
|
||||
px4_arch_configgpio(bus->devices[i].cs_gpio);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void stm32_spiinitialize()
|
||||
{
|
||||
px4_set_spi_buses_from_hw_version();
|
||||
board_control_spi_sensors_power_configgpio();
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
|
||||
switch (px4_spi_buses[i].bus) {
|
||||
case 1: _spi_bus1 = &px4_spi_buses[i]; break;
|
||||
|
||||
case 2: _spi_bus2 = &px4_spi_buses[i]; break;
|
||||
|
||||
case 3: _spi_bus3 = &px4_spi_buses[i]; break;
|
||||
|
||||
case 4: _spi_bus4 = &px4_spi_buses[i]; break;
|
||||
|
||||
case 5: _spi_bus5 = &px4_spi_buses[i]; break;
|
||||
|
||||
case 6: _spi_bus6 = &px4_spi_buses[i]; break;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
ASSERT(_spi_bus1);
|
||||
|
||||
if (board_has_bus(BOARD_SPI_BUS, 1)) {
|
||||
spi_bus_configgpio_cs(_spi_bus1);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32_SPI1
|
||||
|
||||
|
||||
#if defined(CONFIG_STM32_SPI2)
|
||||
ASSERT(_spi_bus2);
|
||||
|
||||
if (board_has_bus(BOARD_SPI_BUS, 2)) {
|
||||
spi_bus_configgpio_cs(_spi_bus2);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32_SPI2
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
ASSERT(_spi_bus3);
|
||||
|
||||
if (board_has_bus(BOARD_SPI_BUS, 3)) {
|
||||
spi_bus_configgpio_cs(_spi_bus3);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32_SPI3
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
ASSERT(_spi_bus4);
|
||||
|
||||
if (board_has_bus(BOARD_SPI_BUS, 4)) {
|
||||
spi_bus_configgpio_cs(_spi_bus4);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32_SPI4
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI5
|
||||
ASSERT(_spi_bus5);
|
||||
|
||||
if (board_has_bus(BOARD_SPI_BUS, 5)) {
|
||||
spi_bus_configgpio_cs(_spi_bus5);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32_SPI5
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI6
|
||||
ASSERT(_spi_bus6);
|
||||
|
||||
if (board_has_bus(BOARD_SPI_BUS, 6)) {
|
||||
spi_bus_configgpio_cs(_spi_bus6);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32_SPI6
|
||||
}
|
||||
|
||||
static inline void stm32_spixselect(const px4_spi_bus_t *bus, struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
int matched_dev_idx = -1;
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (bus->devices[i].cs_gpio == 0) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (devid == bus->devices[i].devid) {
|
||||
matched_dev_idx = i;
|
||||
|
||||
} else {
|
||||
// Making sure the other peripherals are not selected
|
||||
stm32_gpiowrite(bus->devices[i].cs_gpio, 1);
|
||||
}
|
||||
}
|
||||
|
||||
// different devices might use the same CS, so make sure to configure the one we want last
|
||||
if (matched_dev_idx != -1) {
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(bus->devices[matched_dev_idx].cs_gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi1select and stm32_spi1status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 1.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
stm32_spixselect(_spi_bus1, dev, devid, selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32_SPI1
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi2select and stm32_spi2status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 2.
|
||||
*
|
||||
************************************************************************************/
|
||||
#if defined(CONFIG_STM32_SPI2)
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
stm32_spixselect(_spi_bus2, dev, devid, selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32_SPI2
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi3select and stm32_spi3status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 3.
|
||||
*
|
||||
************************************************************************************/
|
||||
#if defined(CONFIG_STM32_SPI3)
|
||||
__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
stm32_spixselect(_spi_bus3, dev, devid, selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32_SPI3
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi4select and stm32_spi4status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 4.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
|
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
stm32_spixselect(_spi_bus4, dev, devid, selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32_SPI4
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi5select and stm32_spi5status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 5.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32_SPI5
|
||||
|
||||
__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
stm32_spixselect(_spi_bus5, dev, devid, selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32_SPI5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi6select and stm32_spi6status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 6.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32_SPI6
|
||||
|
||||
__EXPORT void stm32_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
stm32_spixselect(_spi_bus6, dev, devid, selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32_SPI6
|
||||
|
||||
|
||||
void board_control_spi_sensors_power(bool enable_power, int bus_mask)
|
||||
{
|
||||
const px4_spi_bus_t *buses = px4_spi_buses;
|
||||
// this might be called very early on boot where we have not yet determined the hw version
|
||||
// (we expect all versions to have the same power GPIO)
|
||||
#if BOARD_NUM_HW_VERSIONS > 1
|
||||
|
||||
if (!buses) {
|
||||
buses = &px4_spi_buses_all_hw[0].buses[0];
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
if (buses[bus].bus == -1) {
|
||||
break;
|
||||
}
|
||||
|
||||
const bool bus_matches = bus_mask & (1 << (buses[bus].bus - 1));
|
||||
|
||||
if (buses[bus].power_enable_gpio == 0 ||
|
||||
!board_has_bus(BOARD_SPI_BUS, buses[bus].bus) ||
|
||||
!bus_matches) {
|
||||
continue;
|
||||
}
|
||||
|
||||
px4_arch_gpiowrite(buses[bus].power_enable_gpio, enable_power ? 1 : 0);
|
||||
}
|
||||
}
|
||||
|
||||
void board_control_spi_sensors_power_configgpio()
|
||||
{
|
||||
const px4_spi_bus_t *buses = px4_spi_buses;
|
||||
// this might be called very early on boot where we have yet not determined the hw version
|
||||
// (we expect all versions to have the same power GPIO)
|
||||
#if BOARD_NUM_HW_VERSIONS > 1
|
||||
|
||||
if (!buses) {
|
||||
buses = &px4_spi_buses_all_hw[0].buses[0];
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
if (buses[bus].bus == -1) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (buses[bus].power_enable_gpio == 0 ||
|
||||
!board_has_bus(BOARD_SPI_BUS, buses[bus].bus)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
px4_arch_configgpio(buses[bus].power_enable_gpio);
|
||||
}
|
||||
}
|
||||
|
||||
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz))
|
||||
|
||||
__EXPORT void board_spi_reset(int ms, int bus_mask)
|
||||
{
|
||||
bool has_power_enable = false;
|
||||
|
||||
// disable SPI bus
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
if (px4_spi_buses[bus].bus == -1) {
|
||||
break;
|
||||
}
|
||||
|
||||
const bool bus_requested = bus_mask & (1 << (px4_spi_buses[bus].bus - 1));
|
||||
|
||||
if (px4_spi_buses[bus].power_enable_gpio == 0 ||
|
||||
!board_has_bus(BOARD_SPI_BUS, px4_spi_buses[bus].bus) ||
|
||||
!bus_requested) {
|
||||
continue;
|
||||
}
|
||||
|
||||
has_power_enable = true;
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||
px4_arch_configgpio(_PIN_OFF(px4_spi_buses[bus].devices[i].cs_gpio));
|
||||
}
|
||||
|
||||
if (px4_spi_buses[bus].devices[i].drdy_gpio != 0) {
|
||||
px4_arch_configgpio(_PIN_OFF(px4_spi_buses[bus].devices[i].drdy_gpio));
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(CONFIG_STM32_SPI1)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 1) {
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI1_SCK));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI1_MISO));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI1_MOSI));
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI2)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 2) {
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI2_SCK));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI2_MISO));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI2_MOSI));
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI3)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 3) {
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI3_SCK));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI3_MISO));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI3_MOSI));
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI4)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 4) {
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI4_SCK));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI4_MISO));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI4_MOSI));
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI5)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 5) {
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI5_SCK));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI5_MISO));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI5_MOSI));
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI6)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 6) {
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI6_SCK));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI6_MISO));
|
||||
px4_arch_configgpio(_PIN_OFF(GPIO_SPI6_MOSI));
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
if (!has_power_enable) {
|
||||
// board does not have power control over any of the sensor buses
|
||||
return;
|
||||
}
|
||||
|
||||
// set the sensor rail(s) off
|
||||
board_control_spi_sensors_power(false, bus_mask);
|
||||
|
||||
// wait for the sensor rail to reach GND
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
// switch the sensor rail back on
|
||||
board_control_spi_sensors_power(true, bus_mask);
|
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */
|
||||
usleep(100);
|
||||
|
||||
/* reconfigure the SPI pins */
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
if (px4_spi_buses[bus].bus == -1) {
|
||||
break;
|
||||
}
|
||||
|
||||
const bool bus_requested = bus_mask & (1 << (px4_spi_buses[bus].bus - 1));
|
||||
|
||||
if (px4_spi_buses[bus].power_enable_gpio == 0 ||
|
||||
!board_has_bus(BOARD_SPI_BUS, px4_spi_buses[bus].bus) ||
|
||||
!bus_requested) {
|
||||
continue;
|
||||
}
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||
px4_arch_configgpio(px4_spi_buses[bus].devices[i].cs_gpio);
|
||||
}
|
||||
|
||||
if (px4_spi_buses[bus].devices[i].drdy_gpio != 0) {
|
||||
px4_arch_configgpio(px4_spi_buses[bus].devices[i].drdy_gpio);
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(CONFIG_STM32_SPI1)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 1) {
|
||||
px4_arch_configgpio(GPIO_SPI1_SCK);
|
||||
px4_arch_configgpio(GPIO_SPI1_MISO);
|
||||
px4_arch_configgpio(GPIO_SPI1_MOSI);
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI2)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 2) {
|
||||
px4_arch_configgpio(GPIO_SPI2_SCK);
|
||||
px4_arch_configgpio(GPIO_SPI2_MISO);
|
||||
px4_arch_configgpio(GPIO_SPI2_MOSI);
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI3)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 3) {
|
||||
px4_arch_configgpio(GPIO_SPI3_SCK);
|
||||
px4_arch_configgpio(GPIO_SPI3_MISO);
|
||||
px4_arch_configgpio(GPIO_SPI3_MOSI);
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI4)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 4) {
|
||||
px4_arch_configgpio(GPIO_SPI4_SCK);
|
||||
px4_arch_configgpio(GPIO_SPI4_MISO);
|
||||
px4_arch_configgpio(GPIO_SPI4_MOSI);
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI5)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 5) {
|
||||
px4_arch_configgpio(GPIO_SPI5_SCK);
|
||||
px4_arch_configgpio(GPIO_SPI5_MISO);
|
||||
px4_arch_configgpio(GPIO_SPI5_MOSI);
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(CONFIG_STM32_SPI6)
|
||||
|
||||
if (px4_spi_buses[bus].bus == 6) {
|
||||
px4_arch_configgpio(GPIO_SPI6_SCK);
|
||||
px4_arch_configgpio(GPIO_SPI6_MISO);
|
||||
px4_arch_configgpio(GPIO_SPI6_MOSI);
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
@ -39,6 +39,7 @@ add_subdirectory(../stm32_common/dshot dshot)
|
|||
add_subdirectory(../stm32_common/hrt hrt)
|
||||
add_subdirectory(../stm32_common/led_pwm led_pwm)
|
||||
add_subdirectory(../stm32_common/io_pins io_pins)
|
||||
add_subdirectory(../stm32_common/spi spi)
|
||||
add_subdirectory(../stm32_common/tone_alarm tone_alarm)
|
||||
add_subdirectory(../stm32_common/version version)
|
||||
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../stm32_common/include/px4_arch/i2c_hw_description.h"
|
||||
|
|
@ -0,0 +1,87 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../stm32_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_STM32_SPI1
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI5
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI6
|
||||
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_STM32_SPIx)");
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
|
@ -40,6 +40,7 @@ add_subdirectory(../stm32_common/dshot dshot)
|
|||
add_subdirectory(../stm32_common/hrt hrt)
|
||||
add_subdirectory(../stm32_common/led_pwm led_pwm)
|
||||
add_subdirectory(../stm32_common/io_pins io_pins)
|
||||
add_subdirectory(../stm32_common/spi spi)
|
||||
add_subdirectory(../stm32_common/tone_alarm tone_alarm)
|
||||
add_subdirectory(../stm32_common/version version)
|
||||
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../stm32_common/include/px4_arch/i2c_hw_description.h"
|
||||
|
|
@ -0,0 +1,87 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../stm32_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_STM32F7_SPI1
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI2
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI3
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI6
|
||||
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_STM32F7_SPIx)");
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
|
@ -39,6 +39,7 @@ add_subdirectory(../stm32_common/board_reset board_reset)
|
|||
add_subdirectory(../stm32_common/dshot dshot)
|
||||
add_subdirectory(../stm32_common/hrt hrt)
|
||||
add_subdirectory(../stm32_common/io_pins io_pins)
|
||||
add_subdirectory(../stm32_common/spi spi)
|
||||
add_subdirectory(../stm32_common/tone_alarm tone_alarm)
|
||||
add_subdirectory(../stm32_common/version version)
|
||||
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../stm32_common/include/px4_arch/i2c_hw_description.h"
|
||||
|
|
@ -0,0 +1,87 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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 "../../../stm32_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_STM32H7_SPI1
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI2
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI3
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI4
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI5
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_STM32H7_SPI6
|
||||
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;
|
||||
}
|
||||
|
|
@ -0,0 +1,54 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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_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,59 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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_platform_common/spi.h>
|
||||
|
||||
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint8_t devid_driver, uint8_t cs_index)
|
||||
{
|
||||
px4_spi_bus_device_t ret{};
|
||||
ret.cs_gpio = 1; // set to some non-zero value to indicate this is used
|
||||
ret.devid = PX4_SPIDEV_ID(PX4_SPI_DEVICE_ID, cs_index);
|
||||
ret.devtype_driver = devid_driver;
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr px4_spi_bus_t initSPIBus(int bus, const px4_spi_bus_devices_t &devices)
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
ret.devices[i] = devices.devices[i];
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = false; // all buses are marked internal on Linux
|
||||
ret.requires_locking = false;
|
||||
return ret;
|
||||
}
|
|
@ -0,0 +1,54 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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_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,59 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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_platform_common/spi.h>
|
||||
|
||||
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint8_t devid_driver)
|
||||
{
|
||||
px4_spi_bus_device_t ret{};
|
||||
ret.cs_gpio = 1; // set to some non-zero value to indicate this is used
|
||||
ret.devid = PX4_SPIDEV_ID(PX4_SPI_DEVICE_ID, 0);
|
||||
ret.devtype_driver = devid_driver;
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr px4_spi_bus_t initSPIBus(int bus, const px4_spi_bus_devices_t &devices)
|
||||
{
|
||||
px4_spi_bus_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
ret.devices[i] = devices.devices[i];
|
||||
}
|
||||
|
||||
ret.bus = bus;
|
||||
ret.is_external = false; // all buses are marked internal on QuRT
|
||||
ret.requires_locking = false;
|
||||
return ret;
|
||||
}
|
Loading…
Reference in New Issue