nusrobomaster / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
2 stars 0 forks source link

Initial Dev A Support with SPI Enabled #1

Closed chengguizi closed 3 years ago

chengguizi commented 3 years ago

We should enable SPI support on Dev A as the first goal, as the IMU sensor is mounted on SPI5. This is attempted in the vanila Nuttx here: https://github.com/nusrobomaster/nuttx/issues/6

chengguizi commented 3 years ago

BOARD_NUM_SPI_CFG_HW_VERSIONS defined within board_config.h tells the fact that for each STM32 chip type, how many possible hardware periperals are there. In our case, we only have 1 possible configuration for Dev A, which is that SPI5 connected to MPU6500.

When there a >1 hardware versions, it relies on the external variable px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS]. The function call px4_set_spi_buses_from_hw_version() will detect the hardware version, and spits out the correct px4_spi_bus_t type object px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS]

This px4_set_spi_buses_from_hw_version() function is called at the very beginning of stm32_spiinitialize(), which itself is called in board_app_initialize() in the init.c file. All this are called by nsh at the start-up phase

chengguizi commented 3 years ago

Refer to commit https://github.com/nusrobomaster/PX4-Autopilot/commit/c8b00bd180326e257035d44b2367b10059e4ecc4

SPI enabling has the following key steps:

  1. In the spi.cpp, you need to document the pin configuration and device types for each SPI bus, like the following:

    constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
    initSPIBusExternal(SPI::Bus::SPI4, {
        initSPIConfigExternal(SPI::CS{GPIO::PortE, GPIO::Pin4})
    }),
    initSPIBus(SPI::Bus::SPI5, {
        initSPIDevice(DRV_IMU_DEVTYPE_MPU6500, SPI::CS{GPIO::PortF, GPIO::Pin6},SPI::DRDY{GPIO::PortB, GPIO::Pin8})
    })
    };
  2. In the init.c, initialise the GPIO pins for each SPI, by calling a wrapper function:

    /* configure SPI interfaces (after the hw is determined) */
    syslog(LOG_INFO, "stm32_spiinitialize\n");
    stm32_spiinitialize();
  3. Following point 2, continue in the init.c, conduct bus initialisation (enable CS pin, by pulling it low; configure default speed etc), by calling:

    spi4 = stm32_spibus_initialize(4);
    
    if (!spi4) {
        syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 4);
        led_on(LED_AMBER);
        return -ENODEV;
    }
    
    // /* Default SPI4 to 1MHz and de-assert the known chip selects. */
    // SPI_SETFREQUENCY(spi4, 10000000);
    // SPI_SETBITS(spi4, 8);
    // SPI_SETMODE(spi4, SPIDEV_MODE3);
    
    spi5 = stm32_spibus_initialize(5);
    
    if (!spi5) {
        syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 5);
        led_on(LED_AMBER);
        return -ENODEV;
    }
  4. Also, very importantly, add DMA config (stream and channel) in the board_dma_map.h file, example like:

    //  DMA2 Channel/Stream Selections
    //--------------------------------------------//---------------------------//----------------
    #define DMACHAN_SPI4_RX    DMAMAP_SPI4_RX_1
    #define DMAMAP_USART6_RX   DMAMAP_USART6_RX_2
    #define DMACHAN_SPI4_TX    DMAMAP_SPI4_TX_1
    // #define DMAMAP_SDIO        DMAMAP_SDIO_2      // DMA2, Stream 6, Channel 4
    #define DMAMAP_USART6_TX   DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5    (PX4IO TX)
    #define DMACHAN_SPI5_RX    DMAMAP_SPI5_RX_1
    #define DMACHAN_SPI5_TX    DMAMAP_SPI5_TX_1
    #define DMAMAP_USART1_RX DMAMAP_USART1_RX_2