Skip to content

Commit

Permalink
imx9: Enable spi and i2c
Browse files Browse the repository at this point in the history
Signed-off-by: Jukka Laitinen <[email protected]>
  • Loading branch information
jlaitine authored and pussuw committed Apr 16, 2024
1 parent d75b1d9 commit 42418df
Show file tree
Hide file tree
Showing 4 changed files with 61 additions and 40 deletions.
35 changes: 35 additions & 0 deletions platforms/nuttx/src/px4/nxp/imx9/include/px4_arch/adc.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
/****************************************************************************
*
* Copyright (C) 2022 Technology Innovation Institute. 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

#define SYSTEM_ADC_BASE 0 // not used
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,8 @@

#include <board_config.h>

// TODO: fix this
#ifdef CONFIG_SPI
#include "imx9_gpio.h"

namespace IOMUX
{
namespace GPIO
{
enum Port {
Expand Down Expand Up @@ -205,5 +202,3 @@ struct bus_device_external_cfg_t {
};

} // namespace SPI

#endif
16 changes: 10 additions & 6 deletions platforms/nuttx/src/px4/nxp/imx9/include/px4_arch/micro_hal.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ __BEGIN_DECLS

#include <chip.h>
#include "imx9_gpio.h"
#include "imx9_lpi2c.h"
#include "imx9_lpspi.h"

/*
*/
Expand All @@ -65,23 +67,25 @@ __BEGIN_DECLS
#define PX4_CPU_UUID_WORD32_UNIQUE_H 0 /* Least significant digits change the most */
#define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Most significant digits change the least */

#define PX4_BUS_OFFSET 1 /* imx9 buses are 0 based so adjustment needed */
#define PX4_BUS_OFFSET 0 /* imx9 buses are 1 based so no adjustment needed */

#define px4_savepanic(fileno, context, length) imx9_dump_savepanic(fileno, context, length)

#define px4_spibus_initialize(bus_num_1based) NULL //imx9_lpspibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
#define px4_spibus_initialize(bus_num_1based) imx9_lpspibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))

#define px4_i2cbus_initialize(bus_num_1based) NULL //imx9_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
#define px4_i2cbus_uninitialize(pdev) (-1)//imx9_i2cbus_uninitialize(pdev)
#define px4_i2cbus_initialize(bus_num_1based) imx9_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
#define px4_i2cbus_uninitialize(pdev) imx9_i2cbus_uninitialize(pdev)

#define px4_arch_configgpio(pinset) imx9_config_gpio(pinset)
#define px4_arch_unconfiggpio(pinset)
#define px4_arch_gpioread(pinset) imx9_gpio_read(pinset)
#define px4_arch_gpiowrite(pinset, value) imx9_gpio_write(pinset, value)

int imx9_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge, bool event, xcpt_t func, void *arg);
// TODO: temporary hack, remove when implemented
inline int imx9_gpio_setevent(uint32_t pinset, bool risingedge, bool fallingedge, bool event, xcpt_t func,
void *arg) {return 0;}

#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) imx9_gpiosetevent(pinset,r,f,e,fp,a)
#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) imx9_gpio_setevent(pinset,r,f,e,fp,a)

/* Code to access HRT timer counter directly from uer space TODO */

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,6 @@

#if defined(CONFIG_SPI)

//#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[] = {
Expand Down Expand Up @@ -104,14 +102,16 @@ constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX
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 = 0; // TODO!

ret.cs_gpio = getGPIOPort(cs_gpio.port) | getGPIOPin(cs_gpio.pin) | GPIO_OUTPUT | GPIO_OUTPUT_ONE;

if (drdy_gpio.port != GPIO::PortInvalid) {
ret.drdy_gpio = 0; // TODO!
ret.drdy_gpio = getGPIOPort(drdy_gpio.port) | getGPIOPin(drdy_gpio.pin) | GPIO_INTERRUPT | GPIO_INT_FALLINGEDGE;
}

if (PX4_SPIDEVID_TYPE(devid) == 0) { // it's a PX4 device (internal or external)
ret.devid = PX4_SPIDEV_ID(PX4_SPI_DEVICE_ID, devid);
uint32_t address = ((cs_gpio.port << 5) | cs_gpio.pin) & 0xff; // address on the bus, 3 bits for port 5 for pin
ret.devid = PX4_SPIDEV_ID(PX4_SPI_DEVICE_ID, devid | (address << 8));

} else { // it's a NuttX device (e.g. SPIDEV_FLASH(0))
ret.devid = devid;
Expand All @@ -125,34 +125,21 @@ static inline constexpr px4_spi_bus_t initSPIBus(SPI::Bus bus, const px4_spi_bus
GPIO::GPIOPin power_enable = {})
{
px4_spi_bus_t ret{};
ret.requires_locking = false;

for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
ret.devices[i] = devices.devices[i];


if (ret.devices[i].cs_gpio != 0) {
if (PX4_SPI_DEVICE_ID == PX4_SPIDEVID_TYPE(ret.devices[i].devid)) {
int same_devices_count = 0;
int i = 0;

for (int j = 0; j < i; ++j) {
if (ret.devices[j].cs_gpio != 0) {
same_devices_count += (ret.devices[i].devid & 0xff) == (ret.devices[j].devid & 0xff);
}
}
ret.bus = (int)bus;
ret.is_external = false;

// increment the 2. LSB byte to allow multiple devices of the same type
ret.devices[i].devid |= same_devices_count << 8;
for (; i < SPI_BUS_MAX_DEVICES; ++i) {
ret.devices[i] = devices.devices[i];

} else {
// A bus potentially requires locking if it is accessed by non-PX4 devices (i.e. NuttX drivers)
ret.requires_locking = true;
}
if (devices.devices[i].cs_gpio == 0) {
break;
}
}

ret.bus = (int)bus;
ret.is_external = false;
/* Locking is required if there are more than 1 device on the bus */
ret.requires_locking = i > 1 ? true : false;

if (power_enable.port != GPIO::PortInvalid) {
ret.power_enable_gpio = 0; //TODO!
Expand Down Expand Up @@ -180,7 +167,7 @@ static inline constexpr px4_spi_bus_t initSPIBusExternal(SPI::Bus bus, const bus

ret.bus = (int)bus;
ret.is_external = true;
ret.requires_locking = false; // external buses are never accessed by NuttX drivers
ret.requires_locking = true;
return ret;
}

Expand Down

0 comments on commit 42418df

Please sign in to comment.