Browse Source

boards: omnibus/f4sd add board_dma_map.h

sbg
Daniel Agar 5 years ago committed by Beat Küng
parent
commit
baa50a1985
  1. 5
      boards/omnibus/f4sd/default.cmake
  2. 2
      boards/omnibus/f4sd/init/rc.board_sensors
  3. 24
      boards/omnibus/f4sd/nuttx-config/include/board.h
  4. 94
      boards/omnibus/f4sd/nuttx-config/include/board_dma_map.h

5
boards/omnibus/f4sd/default.cmake

@ -20,11 +20,8 @@ px4_add_board( @@ -20,11 +20,8 @@ px4_add_board(
#distance_sensor # all available distance sensor drivers
dshot
gps
#heater
#imu # all available imu drivers
#imu/mpu6000
imu/invensense/mpu6000
imu/invensense/icm20602
imu/invensense/mpu6000
#irlock
#lights/blinkm
lights/rgbled

2
boards/omnibus/f4sd/init/rc.board_sensors

@ -9,11 +9,9 @@ if ! mpu6000 -R 6 -s start @@ -9,11 +9,9 @@ if ! mpu6000 -R 6 -s start
then
# some boards such as the Hobbywing XRotor F4 G2 use the ICM-20602
icm20602 -s -R 6 start
#mpu6000 -R 12 -T 20602 -s start
fi
# Possible external compasses
hmc5883 -X start
bmp280 -s start

24
boards/omnibus/f4sd/nuttx-config/include/board.h

@ -43,6 +43,7 @@ @@ -43,6 +43,7 @@
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"
#include <nuttx/config.h>
@ -202,23 +203,6 @@ @@ -202,23 +203,6 @@
# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
#endif
/* DMA Channl/Stream Selections *****************************************************/
/* Stream selections are arbitrary for now but might become important in the future
* is we set aside more DMA channels/streams.
*
* SDIO DMA
*   DMAMAP_SDIO_1 = Channel 4, Stream 3
*   DMAMAP_SDIO_2 = Channel 4, Stream 6
*/
#define DMAMAP_SDIO DMAMAP_SDIO_1
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2
#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX
#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX
/* LED definitions ******************************************************************/
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
@ -261,9 +245,6 @@ @@ -261,9 +245,6 @@
#define GPIO_USART1_RX GPIO_USART1_RX_1
#define GPIO_USART1_TX GPIO_USART1_TX_1
/* USART1 require a RX DMA configuration */
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1
/* USART3:
*
* PC10 (TX) and PC11 (RX) are broken out on J4
@ -293,9 +274,6 @@ @@ -293,9 +274,6 @@
#define GPIO_USART6_RX GPIO_USART6_RX_1
#define GPIO_USART6_TX GPIO_USART6_TX_1
/* USART6 require a RX DMA configuration */
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1
/* SPI1:
* MPU6000
* CS: PA4 -- configured in board_config.h

94
boards/omnibus/f4sd/nuttx-config/include/board_dma_map.h

@ -0,0 +1,94 @@ @@ -0,0 +1,94 @@
/****************************************************************************
*
* 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
/*
| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
| Channel 0 | SPI3_RX_1 | - | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | - | SPI3_TX_2 |
| Channel 1 | I2C1_RX | - | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 |
| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 |
| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | I2C2_EXT_RX | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 |
| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 |
| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX |
| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 |
| | | | TIM3_UP | | TIM3_TRIG | | | |
| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - |
| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | |
| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX |
| | | | | | | | | |
| Usage | | TIM2_UP_1 | TIM3_UP | SPI2_RX | SPI2_TX | | | |
| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | - |
| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | |
| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | |
| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 |
| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN |
| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | - | SPI1_TX_2 | - | QUADSPI |
| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDIO | - | USART1_RX_2 | SDIO | USART1_TX |
| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 |
| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - |
| | | | | | TIM1_TRIG_2 | | | |
| | | | | | TIM1_COM | | | |
| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 |
| | | | | | | | | TIM8_TRIG |
| | | | | | | | | TIM8_COM |
| | | | | | | | | |
| Usage | SPI1_RX_1 | USART6_RX_1 | USART1_RX_1 | SPI1_TX_1 | | | SDIO | |
*/
// DMA1 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
// AVAILABLE // DMA2, Stream 0
// DMAMAP_TIM2_UP // DMA1, Stream 1, Channel 3 (DSHOT)
// DMAMAP_TIM3_UP // DMA1, Stream 2, Channel 5 (DSHOT)
#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0 (SPI2 RX)
#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0 (SPI2 TX)
// AVAILABLE // DMA2, Stream 5
// AVAILABLE // DMA2, Stream 6
// AVAILABLE // DMA2, Stream 7
// DMA2 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI1 RX)
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1 // DMA2, Stream 1, Channel 4
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1 // DMA2, Stream 2, Channel 4
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI1 TX)
// AVAILABLE // DMA2, Stream 4
// AVAILABLE // DMA2, Stream 5
#define DMAMAP_SDIO DMAMAP_SDIO_2 // DMA2, Stream 6, Channel 4
// AVAILABLE // DMA2, Stream 7
Loading…
Cancel
Save