mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
Introduce dma_reqmap
This commit is contained in:
parent
3631e41292
commit
fe182bb2fb
82 changed files with 1051 additions and 188 deletions
|
@ -18,6 +18,7 @@ COMMON_SRC = \
|
|||
drivers/bus_spi_pinconfig.c \
|
||||
drivers/buttons.c \
|
||||
drivers/display.c \
|
||||
drivers/dma_reqmap.c \
|
||||
drivers/exti.c \
|
||||
drivers/io.c \
|
||||
drivers/light_led.c \
|
||||
|
|
|
@ -53,12 +53,14 @@ typedef struct adcTagMap_s {
|
|||
typedef struct adcDevice_s {
|
||||
ADC_TypeDef* ADCx;
|
||||
rccPeriphTag_t rccADC;
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
DMA_Stream_TypeDef* DMAy_Streamx;
|
||||
uint32_t channel;
|
||||
#else
|
||||
DMA_Channel_TypeDef* DMAy_Channelx;
|
||||
#endif
|
||||
#endif
|
||||
#if defined(STM32F7)
|
||||
ADC_HandleTypeDef ADCHandle;
|
||||
DMA_HandleTypeDef DmaHandle;
|
||||
|
|
|
@ -119,6 +119,7 @@ void adcInit(const adcConfig_t *config)
|
|||
}
|
||||
|
||||
ADCDevice device = ADC_CFG_TO_DEV(config->device);
|
||||
|
||||
if (device == ADCINVALID) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
|
@ -49,10 +50,31 @@
|
|||
#endif
|
||||
|
||||
const adcDevice_t adcHardware[] = {
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = ADC1_DMA_STREAM, .channel = DMA_Channel_0 },
|
||||
{
|
||||
.ADCx = ADC1,
|
||||
.rccADC = RCC_APB2(ADC1),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC1_DMA_STREAM,
|
||||
.channel = DMA_Channel_0
|
||||
#endif
|
||||
},
|
||||
#if !defined(STM32F411xE)
|
||||
{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .DMAy_Streamx = ADC2_DMA_STREAM, .channel = DMA_Channel_1 },
|
||||
{ .ADCx = ADC3, .rccADC = RCC_APB2(ADC3), .DMAy_Streamx = ADC3_DMA_STREAM, .channel = DMA_Channel_2 }
|
||||
{
|
||||
.ADCx = ADC2,
|
||||
.rccADC = RCC_APB2(ADC2),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC2_DMA_STREAM,
|
||||
.channel = DMA_Channel_1
|
||||
#endif
|
||||
},
|
||||
{
|
||||
.ADCx = ADC3,
|
||||
.rccADC = RCC_APB2(ADC3),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC3_DMA_STREAM,
|
||||
.channel = DMA_Channel_2
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
|
@ -212,6 +234,7 @@ void adcInit(const adcConfig_t *config)
|
|||
}
|
||||
|
||||
ADCDevice device = ADC_CFG_TO_DEV(config->device);
|
||||
|
||||
if (device == ADCINVALID) {
|
||||
return;
|
||||
}
|
||||
|
@ -280,16 +303,33 @@ void adcInit(const adcConfig_t *config)
|
|||
ADC_DMACmd(adc.ADCx, ENABLE);
|
||||
ADC_Cmd(adc.ADCx, ENABLE);
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpec(DMA_PERIPH_ADC, device, config->dmaopt[device]);
|
||||
|
||||
if (!dmaSpec) {
|
||||
return;
|
||||
}
|
||||
|
||||
dmaInit(dmaGetIdentifier(dmaSpec->ref), OWNER_ADC, RESOURCE_INDEX(device));
|
||||
|
||||
DMA_DeInit(dmaSpec->ref);
|
||||
#else
|
||||
dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
|
||||
|
||||
DMA_DeInit(adc.DMAy_Streamx);
|
||||
#endif
|
||||
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
DMA_InitStructure.DMA_Channel = dmaSpec->channel;
|
||||
#else
|
||||
DMA_InitStructure.DMA_Channel = adc.channel;
|
||||
#endif
|
||||
|
||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)adcValues;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||
DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
|
||||
|
@ -299,9 +339,14 @@ void adcInit(const adcConfig_t *config)
|
|||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_Init(adc.DMAy_Streamx, &DMA_InitStructure);
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
DMA_Init(dmaSpec->ref, &DMA_InitStructure);
|
||||
DMA_Cmd(dmaSpec->ref, ENABLE);
|
||||
#else
|
||||
DMA_Init(adc.DMAy_Streamx, &DMA_InitStructure);
|
||||
DMA_Cmd(adc.DMAy_Streamx, ENABLE);
|
||||
#endif
|
||||
|
||||
ADC_SoftwareStartConv(adc.ADCx);
|
||||
}
|
||||
|
|
|
@ -27,29 +27,19 @@
|
|||
#ifdef USE_ADC
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/rcc.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "io_impl.h"
|
||||
#include "rcc.h"
|
||||
#include "dma.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
#include "adc.h"
|
||||
#include "adc_impl.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/adc_impl.h"
|
||||
|
||||
#include "pg/adc.h"
|
||||
|
||||
|
||||
#ifndef ADC_INSTANCE
|
||||
#define ADC_INSTANCE ADC1
|
||||
#endif
|
||||
|
||||
#ifndef ADC1_DMA_STREAM
|
||||
#define ADC1_DMA_STREAM DMA2_Stream4
|
||||
#endif
|
||||
|
||||
// Copied from stm32f7xx_ll_adc.h
|
||||
|
||||
#define VREFINT_CAL_VREF ( 3300U) /* Analog voltage reference (Vref+) value with which temperature sensor has been calibrated in production (tolerance: +-10 mV) (unit: mV). */
|
||||
|
@ -71,9 +61,30 @@
|
|||
#endif
|
||||
|
||||
const adcDevice_t adcHardware[] = {
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = ADC1_DMA_STREAM, .channel = DMA_CHANNEL_0 },
|
||||
{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .DMAy_Streamx = ADC2_DMA_STREAM, .channel = DMA_CHANNEL_1 },
|
||||
{ .ADCx = ADC3, .rccADC = RCC_APB2(ADC3), .DMAy_Streamx = ADC3_DMA_STREAM, .channel = DMA_CHANNEL_2 }
|
||||
{
|
||||
.ADCx = ADC1,
|
||||
.rccADC = RCC_APB2(ADC1),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC1_DMA_STREAM,
|
||||
.channel = DMA_CHANNEL_0
|
||||
#endif
|
||||
},
|
||||
{
|
||||
.ADCx = ADC2,
|
||||
.rccADC = RCC_APB2(ADC2),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC2_DMA_STREAM,
|
||||
.channel = DMA_CHANNEL_1
|
||||
#endif
|
||||
},
|
||||
{
|
||||
.ADCx = ADC3,
|
||||
.rccADC = RCC_APB2(ADC3),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC3_DMA_STREAM,
|
||||
.channel = DMA_CHANNEL_2
|
||||
#endif
|
||||
}
|
||||
};
|
||||
|
||||
/* note these could be packed up for saving space */
|
||||
|
@ -236,7 +247,8 @@ void adcInit(const adcConfig_t *config)
|
|||
adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||
}
|
||||
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
ADCDevice device = ADC_CFG_TO_DEV(config->device);
|
||||
|
||||
if (device == ADCINVALID) {
|
||||
return;
|
||||
}
|
||||
|
@ -299,9 +311,22 @@ void adcInit(const adcConfig_t *config)
|
|||
}
|
||||
}
|
||||
|
||||
dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
|
||||
#ifdef USE_DMA_SPEC
|
||||
const dmaChannelSpec_t *dmaspec = dmaGetChannelSpec(DMA_PERIPH_ADC, device, config->dmaopt[device]);
|
||||
|
||||
if (!dmaspec) {
|
||||
return;
|
||||
}
|
||||
|
||||
dmaInit(dmaGetIdentifier(dmaspec->ref), OWNER_ADC, 0);
|
||||
adc.DmaHandle.Init.Channel = dmaspec->channel;
|
||||
adc.DmaHandle.Instance = dmaspec->ref;
|
||||
#else
|
||||
dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
|
||||
adc.DmaHandle.Init.Channel = adc.channel;
|
||||
adc.DmaHandle.Instance = adc.DMAy_Streamx;
|
||||
#endif
|
||||
|
||||
adc.DmaHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
|
||||
adc.DmaHandle.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||
adc.DmaHandle.Init.MemInc = configuredAdcChannels > 1 ? DMA_MINC_ENABLE : DMA_MINC_DISABLE;
|
||||
|
@ -313,7 +338,7 @@ void adcInit(const adcConfig_t *config)
|
|||
adc.DmaHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
|
||||
adc.DmaHandle.Init.MemBurst = DMA_MBURST_SINGLE;
|
||||
adc.DmaHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||
adc.DmaHandle.Instance = adc.DMAy_Streamx;
|
||||
|
||||
|
||||
if (HAL_DMA_Init(&adc.DmaHandle) != HAL_OK)
|
||||
{
|
||||
|
|
149
src/main/drivers/dma_reqmap.c
Normal file
149
src/main/drivers/dma_reqmap.c
Normal file
|
@ -0,0 +1,149 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
||||
typedef struct dmaRequestMapping_s {
|
||||
dmaPeripheral_e device;
|
||||
uint8_t index;
|
||||
dmaChannelSpec_t channelSpec[2];
|
||||
} dmaRequestMapping_t;
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define D(d, s, c) { DMA_CODE(d, s, c), DMA ## d ## _Stream ## s, c }
|
||||
|
||||
static const dmaRequestMapping_t dmaRequestMapping[] = {
|
||||
#ifdef USE_SPI
|
||||
// Everything including F405 and F446
|
||||
{ DMA_PERIPH_SPI_TX, SPIDEV_1, { D(2, 3, 3), D(2, 5, 3) } },
|
||||
{ DMA_PERIPH_SPI_RX, SPIDEV_1, { D(2, 0, 3), D(2, 2, 3) } },
|
||||
{ DMA_PERIPH_SPI_TX, SPIDEV_2, { D(1, 4, 0) } },
|
||||
{ DMA_PERIPH_SPI_RX, SPIDEV_2, { D(1, 3, 0) } },
|
||||
{ DMA_PERIPH_SPI_TX, SPIDEV_3, { D(1, 5, 0), D(1, 7, 0) } },
|
||||
{ DMA_PERIPH_SPI_RX, SPIDEV_3, { D(1, 0, 0), D(1, 2, 0) } },
|
||||
|
||||
#if defined(STM32F411xE) || defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx) || defined(STM32F722xx)
|
||||
{ DMA_PERIPH_SPI_TX, SPIDEV_4, { D(2, 1, 4) } },
|
||||
{ DMA_PERIPH_SPI_RX, SPIDEV_4, { D(2, 0, 4) } },
|
||||
|
||||
#ifdef USE_EXTENDED_SPI_DEVICE
|
||||
{ DMA_PERIPH_SPI_TX, SPIDEV_5, { D(2, 6, 7) } },
|
||||
{ DMA_PERIPH_SPI_RX, SPIDEV_5, { D(2, 5, 7) } },
|
||||
|
||||
#if !defined(STM32F722xx)
|
||||
{ DMA_PERIPH_SPI_TX, SPIDEV_6, { D(2, 5, 1) } },
|
||||
{ DMA_PERIPH_SPI_RX, SPIDEV_6, { D(2, 6, 1) } },
|
||||
#endif
|
||||
#endif // USE_EXTENDED_SPI_DEVICE
|
||||
#endif
|
||||
#endif // USE_SPI
|
||||
|
||||
#ifdef USE_ADC
|
||||
{ DMA_PERIPH_ADC, ADCDEV_1, { D(2, 0, 0), D(2, 4, 0) } },
|
||||
{ DMA_PERIPH_ADC, ADCDEV_2, { D(2, 2, 1), D(2, 3, 1) } },
|
||||
{ DMA_PERIPH_ADC, ADCDEV_3, { D(2, 0, 2), D(2, 1, 2) } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_SDCARD_SDIO
|
||||
{ DMA_PERIPH_SDIO, 0, { D(2, 3, 4), D(2, 6, 4) } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_1, { D(2, 7, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_1, { D(2, 5, 4), D(2, 2, 4) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_2, { D(1, 6, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_2, { D(1, 5, 4) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_3, { D(1, 3, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_3, { D(1, 1, 4) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_4, { D(1, 4, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_4, { D(1, 2, 4) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_5, { D(1, 7, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_5, { D(1, 0, 4) } },
|
||||
{ DMA_PERIPH_UART_TX, UARTDEV_6, { D(2, 6, 5), D(2, 7, 5) } },
|
||||
{ DMA_PERIPH_UART_RX, UARTDEV_6, { D(2, 1, 5), D(2, 2, 5) } },
|
||||
#endif
|
||||
};
|
||||
#undef D
|
||||
#else // STM32F3
|
||||
// The embedded ADC24_DMA_REMAP conditional should be removed
|
||||
// when (and if) F3 is going generic.
|
||||
#define D(d, c) { DMA_CODE(d, 0, c), DMA ## d ## _Channel ## c }
|
||||
static const dmaRequestMapping_t dmaRequestMapping[17] = {
|
||||
#ifdef USE_SPI
|
||||
{ DMA_PERIPH_SPI_TX, 1, { D(1, 3) } },
|
||||
{ DMA_PERIPH_SPI_RX, 1, { D(1, 2) } },
|
||||
{ DMA_PERIPH_SPI_TX, 2, { D(1, 5) } },
|
||||
{ DMA_PERIPH_SPI_RX, 2, { D(1, 4) } },
|
||||
{ DMA_PERIPH_SPI_TX, 3, { D(2, 2) } },
|
||||
{ DMA_PERIPH_SPI_RX, 3, { D(2, 1) } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_ADC
|
||||
{ DMA_PERIPH_ADC, 1, { D(1, 1) } },
|
||||
#ifdef ADC24_DMA_REMAP
|
||||
{ DMA_PERIPH_ADC, 2, { D(2, 3) } },
|
||||
#else
|
||||
{ DMA_PERIPH_ADC, 2, { D(2, 1) } },
|
||||
#endif
|
||||
{ DMA_PERIPH_ADC, 3, { D(2, 5) } },
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART
|
||||
{ DMA_PERIPH_UART_TX, 1, { D(1, 4) } },
|
||||
{ DMA_PERIPH_UART_RX, 1, { D(1, 5) } },
|
||||
|
||||
{ DMA_PERIPH_UART_TX, 2, { D(1, 7) } },
|
||||
{ DMA_PERIPH_UART_RX, 2, { D(1, 6) } },
|
||||
{ DMA_PERIPH_UART_TX, 3, { D(1, 2) } },
|
||||
{ DMA_PERIPH_UART_RX, 3, { D(1, 3) } },
|
||||
{ DMA_PERIPH_UART_TX, 4, { D(2, 5) } },
|
||||
{ DMA_PERIPH_UART_RX, 4, { D(2, 3) } },
|
||||
};
|
||||
#endif
|
||||
#undef D
|
||||
#endif
|
||||
|
||||
const dmaChannelSpec_t *dmaGetChannelSpec(dmaPeripheral_e device, uint8_t index, int8_t opt)
|
||||
{
|
||||
if (opt < 0 || opt >= 2) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
for (unsigned i = 0 ; i < ARRAYLEN(dmaRequestMapping) ; i++) {
|
||||
const dmaRequestMapping_t *periph = &dmaRequestMapping[i];
|
||||
if (periph->device == device && periph->index == index && periph->channelSpec[opt].ref) {
|
||||
return &periph->channelSpec[opt];
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
#endif // USE_DMA_SPEC
|
55
src/main/drivers/dma_reqmap.h
Normal file
55
src/main/drivers/dma_reqmap.h
Normal file
|
@ -0,0 +1,55 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
//#pragma once
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
typedef uint16_t dmaCode_t;
|
||||
|
||||
typedef struct dmaChannelSpec_s {
|
||||
dmaCode_t code;
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
DMA_Stream_TypeDef *ref;
|
||||
uint8_t channel;
|
||||
#else
|
||||
DMA_Channel_TypeDef *ref;
|
||||
#endif
|
||||
} dmaChannelSpec_t;
|
||||
|
||||
#define DMA_CODE(dma, stream, chanreq) ((dma << 12)|(stream << 8)|(chanreq << 0))
|
||||
#define DMA_CODE_CONTROLLER(code) ((code >> 12) & 0xf)
|
||||
#define DMA_CODE_STREAM(code) ((code >> 8) & 0xf)
|
||||
#define DMA_CODE_CHANNEL(code) ((code >> 0) & 0xff)
|
||||
#define DMA_CODE_REQUEST(code) DMA_CODE_CHANNEL(code)
|
||||
|
||||
typedef enum {
|
||||
DMA_PERIPH_SPI_TX,
|
||||
DMA_PERIPH_SPI_RX,
|
||||
DMA_PERIPH_ADC,
|
||||
DMA_PERIPH_SDIO,
|
||||
DMA_PERIPH_UART_TX,
|
||||
DMA_PERIPH_UART_RX,
|
||||
} dmaPeripheral_e;
|
||||
|
||||
typedef int8_t dmaoptValue_t;
|
||||
#define DMA_OPT_UNUSED (-1)
|
||||
|
||||
const dmaChannelSpec_t *dmaGetChannelSpec(dmaPeripheral_e device, uint8_t index, int8_t opt);
|
|
@ -28,10 +28,12 @@
|
|||
#include "drivers/nvic.h"
|
||||
#include "drivers/io.h"
|
||||
#include "dma.h"
|
||||
#include "dma_reqmap.h"
|
||||
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "pg/bus_spi.h"
|
||||
#include "pg/sdcard.h"
|
||||
|
||||
#include "sdcard.h"
|
||||
|
@ -128,7 +130,7 @@ void sdcard_init(const sdcardConfig_t *config)
|
|||
}
|
||||
|
||||
if (sdcardVTable) {
|
||||
sdcardVTable->sdcard_init(config);
|
||||
sdcardVTable->sdcard_init(config, spiPinConfig(0));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -113,7 +113,7 @@ bool sdcard_isInserted(void);
|
|||
|
||||
typedef struct sdcardVTable_s {
|
||||
void (*sdcard_preInit)(const sdcardConfig_t *config);
|
||||
void (*sdcard_init)(const sdcardConfig_t *config);
|
||||
void (*sdcard_init)(const sdcardConfig_t *config, const spiPinConfig_t *spiConfig);
|
||||
bool (*sdcard_readBlock)(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData);
|
||||
sdcardOperationStatus_e (*sdcard_beginWriteBlocks)(uint32_t blockIndex, uint32_t blockCount);
|
||||
sdcardOperationStatus_e (*sdcard_writeBlock)(uint32_t blockIndex, uint8_t *buffer, sdcard_operationCompleteCallback_c callback, uint32_t callbackData);
|
||||
|
|
|
@ -31,18 +31,19 @@
|
|||
#include "drivers/nvic.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/bus_spi.h" // For spiPinConfig_t, which is unused but should be defined
|
||||
#include "pg/sdio.h"
|
||||
|
||||
#include "drivers/sdcard.h"
|
||||
#include "drivers/sdcard_impl.h"
|
||||
#include "drivers/sdcard_standard.h"
|
||||
|
||||
#include "drivers/sdmmc_sdio.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/sdio.h"
|
||||
|
||||
// Use this to speed up writing to SDCARD... asyncfatfs has limited support for multiblock write
|
||||
#define FATFS_BLOCK_CACHE_SIZE 16
|
||||
uint8_t writeCache[512 * FATFS_BLOCK_CACHE_SIZE] __attribute__ ((aligned (4)));
|
||||
|
@ -187,14 +188,25 @@ static bool sdcard_checkInitDone(void)
|
|||
/**
|
||||
* Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
|
||||
*/
|
||||
static void sdcardSdio_init(const sdcardConfig_t *config)
|
||||
static void sdcardSdio_init(const sdcardConfig_t *config, const spiPinConfig_t *spiConfig)
|
||||
{
|
||||
UNUSED(spiConfig);
|
||||
|
||||
sdcard.enabled = config->mode;
|
||||
if (!sdcard.enabled) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return;
|
||||
}
|
||||
sdcard.dmaIdentifier = config->dmaIdentifier;
|
||||
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpec(DMA_PERIPH_SDIO, 0, sdioConfig()->dmaopt);
|
||||
|
||||
if (!dmaChannelSpec) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return;
|
||||
}
|
||||
|
||||
sdcard.dmaIdentifier = dmaGetIdentifier(dmaChannelSpec->ref);
|
||||
|
||||
if (sdcard.dmaIdentifier == 0) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return;
|
||||
|
@ -212,7 +224,7 @@ static void sdcardSdio_init(const sdcardConfig_t *config)
|
|||
} else {
|
||||
sdcard.useCache = 0;
|
||||
}
|
||||
SD_Initialize_LL(dmaGetRefByIdentifier(sdcard.dmaIdentifier));
|
||||
SD_Initialize_LL(dmaChannelSpec->ref);
|
||||
if (SD_IsDetected()) {
|
||||
if (SD_Init() != 0) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
|
|
|
@ -27,11 +27,15 @@
|
|||
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/io.h"
|
||||
#include "dma.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "pg/bus_spi.h"
|
||||
#include "pg/sdcard.h"
|
||||
|
||||
#include "sdcard.h"
|
||||
#include "sdcard_impl.h"
|
||||
#include "sdcard_standard.h"
|
||||
|
@ -473,23 +477,43 @@ void sdcardSpi_preInit(const sdcardConfig_t *config)
|
|||
/**
|
||||
* Begin the initialization process for the SD card. This must be called first before any other sdcard_ routine.
|
||||
*/
|
||||
static void sdcardSpi_init(const sdcardConfig_t *config)
|
||||
static void sdcardSpi_init(const sdcardConfig_t *config, const spiPinConfig_t *spiConfig)
|
||||
{
|
||||
#ifndef USE_DMA_SPEC
|
||||
UNUSED(spiConfig);
|
||||
#endif
|
||||
|
||||
sdcard.enabled = config->mode;
|
||||
if (!sdcard.enabled) {
|
||||
sdcard.state = SDCARD_STATE_NOT_PRESENT;
|
||||
return;
|
||||
}
|
||||
|
||||
spiBusSetInstance(&sdcard.busdev, spiInstanceByDevice(SPI_CFG_TO_DEV(config->device)));
|
||||
SPIDevice spiDevice = SPI_CFG_TO_DEV(config->device);
|
||||
|
||||
sdcard.useDMAForTx = config->useDma;
|
||||
if (sdcard.useDMAForTx) {
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
sdcard.dmaChannel = config->dmaChannel;
|
||||
spiBusSetInstance(&sdcard.busdev, spiInstanceByDevice(spiDevice));
|
||||
|
||||
if (config->useDma) {
|
||||
dmaIdentifier_e dmaIdentifier = DMA_NONE;
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpec(DMA_PERIPH_SPI_TX, config->device, spiConfig[spiDevice].txDmaopt);
|
||||
|
||||
if (dmaChannelSpec) {
|
||||
dmaIdentifier = dmaGetIdentifier(dmaChannelSpec->ref);
|
||||
sdcard.dmaChannel = dmaChannelSpec->channel; // XXX STM32F3 doesn't have this
|
||||
}
|
||||
#else
|
||||
dmaIdentifier = config->dmaIdentifier;
|
||||
#endif
|
||||
sdcard.dma = dmaGetDescriptorByIdentifier(config->dmaIdentifier);
|
||||
dmaInit(config->dmaIdentifier, OWNER_SDCARD, 0);
|
||||
|
||||
if (dmaIdentifier) {
|
||||
sdcard.dma = dmaGetDescriptorByIdentifier(dmaIdentifier);
|
||||
dmaInit(dmaIdentifier, OWNER_SDCARD, 0);
|
||||
sdcard.useDMAForTx = true;
|
||||
} else {
|
||||
sdcard.useDMAForTx = false;
|
||||
}
|
||||
}
|
||||
|
||||
IO_t chipSelectIO;
|
||||
|
|
|
@ -62,6 +62,7 @@ extern uint8_t __config_end;
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/camera_control.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
#include "drivers/display.h"
|
||||
|
@ -135,6 +136,8 @@ extern uint8_t __config_end;
|
|||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/serial_uart.h"
|
||||
#include "pg/sdio.h"
|
||||
#include "pg/timerio.h"
|
||||
#include "pg/usb.h"
|
||||
|
||||
|
@ -4193,7 +4196,225 @@ static void cliDma(char* cmdLine)
|
|||
UNUSED(cmdLine);
|
||||
printDma();
|
||||
}
|
||||
#endif /* USE_RESOURCE_MGMT */
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
|
||||
typedef struct dmaoptEntry_s {
|
||||
char *device;
|
||||
dmaPeripheral_e peripheral;
|
||||
pgn_t pgn;
|
||||
uint8_t stride;
|
||||
uint8_t offset;
|
||||
uint8_t maxIndex;
|
||||
} dmaoptEntry_t;
|
||||
|
||||
// Handy macros for keeping the table tidy.
|
||||
// DEFS : Single entry
|
||||
// DEFA : Array of uint8_t (stride = 1)
|
||||
// DEFW : Wider stride case; array of structs.
|
||||
|
||||
#define DEFS(device, peripheral, pgn, type, member) \
|
||||
{ device, peripheral, pgn, 0, offsetof(type, member), 0 }
|
||||
|
||||
#define DEFA(device, peripheral, pgn, type, member, max) \
|
||||
{ device, peripheral, pgn, sizeof(uint8_t), offsetof(type, member), max }
|
||||
|
||||
#define DEFW(device, peripheral, pgn, type, member, max) \
|
||||
{ device, peripheral, pgn, sizeof(type), offsetof(type, member), max }
|
||||
|
||||
dmaoptEntry_t dmaoptEntryTable[] = {
|
||||
DEFW("SPI_TX", DMA_PERIPH_SPI_TX, PG_SPI_PIN_CONFIG, spiPinConfig_t, txDmaopt, SPIDEV_COUNT),
|
||||
DEFW("SPI_RX", DMA_PERIPH_SPI_RX, PG_SPI_PIN_CONFIG, spiPinConfig_t, rxDmaopt, SPIDEV_COUNT),
|
||||
DEFA("ADC", DMA_PERIPH_ADC, PG_ADC_CONFIG, adcConfig_t, dmaopt, ADCDEV_COUNT),
|
||||
DEFS("SDIO", DMA_PERIPH_SDIO, PG_SDIO_CONFIG, sdioConfig_t, dmaopt),
|
||||
DEFA("UART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, UARTDEV_CONFIG_MAX),
|
||||
DEFA("UART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, UARTDEV_CONFIG_MAX),
|
||||
};
|
||||
|
||||
#undef DEFS
|
||||
#undef DEFA
|
||||
#undef DEFW
|
||||
|
||||
#define DMA_OPT_UI_INDEX(i) ((i) + 1)
|
||||
#define DMA_OPT_STRING_BUFSIZE 5
|
||||
|
||||
static void dmaoptToString(int optval, char *buf)
|
||||
{
|
||||
if (optval == -1) {
|
||||
memcpy(buf, "NONE", DMA_OPT_STRING_BUFSIZE);
|
||||
} else {
|
||||
tfp_sprintf(buf, "%d", optval);
|
||||
}
|
||||
}
|
||||
|
||||
static void printPeripheralDmaopt(dmaoptEntry_t *entry, int index, uint8_t dumpMask)
|
||||
{
|
||||
const pgRegistry_t* pg = pgFind(entry->pgn);
|
||||
const void *currentConfig;
|
||||
const void *defaultConfig;
|
||||
|
||||
if (configIsInCopy) {
|
||||
currentConfig = pg->copy;
|
||||
defaultConfig = pg->address;
|
||||
} else {
|
||||
currentConfig = pg->address;
|
||||
defaultConfig = NULL;
|
||||
}
|
||||
|
||||
dmaoptValue_t currentOpt = *(dmaoptValue_t *)((uint8_t *)currentConfig + entry->stride * index + entry->offset);
|
||||
dmaoptValue_t defaultOpt;
|
||||
|
||||
if (defaultConfig) {
|
||||
defaultOpt = *(dmaoptValue_t *)((uint8_t *)defaultConfig + entry->stride * index + entry->offset);
|
||||
} else {
|
||||
defaultOpt = DMA_OPT_UNUSED;
|
||||
}
|
||||
|
||||
bool equalsDefault = currentOpt == defaultOpt;
|
||||
|
||||
if (defaultConfig) {
|
||||
if (defaultOpt != DMA_OPT_UNUSED) {
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpec(entry->peripheral, index, defaultOpt);
|
||||
dmaCode_t dmaCode = 0;
|
||||
if (dmaChannelSpec) {
|
||||
dmaCode = dmaChannelSpec->code;
|
||||
}
|
||||
cliDefaultPrintLinef(dumpMask, equalsDefault,
|
||||
"dmaopt %s %d %d # DMA%d Stream %d Channel %d",
|
||||
entry->device, DMA_OPT_UI_INDEX(index), defaultOpt, DMA_CODE_CONTROLLER(dmaCode), DMA_CODE_STREAM(dmaCode), DMA_CODE_CHANNEL(dmaCode));
|
||||
} else {
|
||||
cliDefaultPrintLinef(dumpMask, equalsDefault,
|
||||
"dmaopt %s %d NONE",
|
||||
entry->device, DMA_OPT_UI_INDEX(index));
|
||||
}
|
||||
}
|
||||
|
||||
if (currentOpt != DMA_OPT_UNUSED) {
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpec(entry->peripheral, index, currentOpt);
|
||||
dmaCode_t dmaCode = 0;
|
||||
if (dmaChannelSpec) {
|
||||
dmaCode = dmaChannelSpec->code;
|
||||
}
|
||||
cliDumpPrintLinef(dumpMask, equalsDefault,
|
||||
"dmaopt %s %d %d # DMA%d Stream %d Channel %d",
|
||||
entry->device, DMA_OPT_UI_INDEX(index), currentOpt, DMA_CODE_CONTROLLER(dmaCode), DMA_CODE_STREAM(dmaCode), DMA_CODE_CHANNEL(dmaCode));
|
||||
} else {
|
||||
if (!(dumpMask & HIDE_UNUSED)) {
|
||||
cliDumpPrintLinef(dumpMask, equalsDefault,
|
||||
"dmaopt %s %d NONE",
|
||||
entry->device, DMA_OPT_UI_INDEX(index));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void printDmaopt(uint8_t dumpMask)
|
||||
{
|
||||
UNUSED(dumpMask); // XXX For now
|
||||
|
||||
for (size_t i = 0; i < ARRAYLEN(dmaoptEntryTable); i++) {
|
||||
dmaoptEntry_t *entry = &dmaoptEntryTable[i];
|
||||
for (int index = 0; index < entry->maxIndex; index++) {
|
||||
printPeripheralDmaopt(entry, index, dumpMask);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void cliDmaopt(char *cmdline)
|
||||
{
|
||||
char *pch = NULL;
|
||||
char *saveptr;
|
||||
|
||||
// Peripheral name or command option
|
||||
pch = strtok_r(cmdline, " ", &saveptr);
|
||||
|
||||
if (!pch) {
|
||||
printDmaopt(DUMP_MASTER | HIDE_UNUSED);
|
||||
return;
|
||||
}
|
||||
|
||||
if (strcasecmp(pch, "all") == 0) {
|
||||
printDmaopt(DUMP_MASTER);
|
||||
return;
|
||||
}
|
||||
|
||||
dmaoptEntry_t *entry = NULL;
|
||||
for (unsigned i = 0; i < ARRAYLEN(dmaoptEntryTable); i++) {
|
||||
if (strcasecmp(pch, dmaoptEntryTable[i].device) == 0) {
|
||||
entry = &dmaoptEntryTable[i];
|
||||
}
|
||||
}
|
||||
if (!entry) {
|
||||
cliPrintLinef("bad device %s", pch);
|
||||
return;
|
||||
}
|
||||
|
||||
// Index
|
||||
pch = strtok_r(NULL, " ", &saveptr);
|
||||
int index = atoi(pch) - 1;
|
||||
if (index < 0 || index >= entry->maxIndex) {
|
||||
cliPrintLinef("bad index %s", pch);
|
||||
return;
|
||||
}
|
||||
|
||||
const pgRegistry_t* pg = pgFind(entry->pgn);
|
||||
const void *currentConfig;
|
||||
if (configIsInCopy) {
|
||||
currentConfig = pg->copy;
|
||||
} else {
|
||||
currentConfig = pg->address;
|
||||
}
|
||||
dmaoptValue_t *optaddr = (dmaoptValue_t *)((uint8_t *)currentConfig + entry->stride * index + entry->offset);
|
||||
|
||||
// opt or list
|
||||
pch = strtok_r(NULL, " ", &saveptr);
|
||||
|
||||
if (!pch) {
|
||||
if (*optaddr == -1) {
|
||||
cliPrintLinef("%s %d NONE", entry->device, index + 1);
|
||||
} else {
|
||||
cliPrintLinef("%s %d %d", entry->device, index + 1, *optaddr);
|
||||
}
|
||||
return;
|
||||
} else if (strcasecmp(pch, "list") == 0) {
|
||||
// Show possible opts
|
||||
const dmaChannelSpec_t *dmaChannelSpec;
|
||||
for (int opt = 0; (dmaChannelSpec = dmaGetChannelSpec(entry->peripheral, index, opt)); opt++) {
|
||||
cliPrintLinef("# %d: DMA%d Stream %d channel %d", opt, DMA_CODE_CONTROLLER(dmaChannelSpec->code), DMA_CODE_STREAM(dmaChannelSpec->code), dmaChannelSpec->channel);
|
||||
}
|
||||
return;
|
||||
} else if (pch) {
|
||||
int optval;
|
||||
|
||||
if (strcasecmp(pch, "none") == 0) {
|
||||
optval = -1;
|
||||
} else {
|
||||
optval = atoi(pch);
|
||||
if (optval < 0) { // XXX Check against opt max? How?
|
||||
cliPrintLinef("bad optnum %s", pch);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
dmaoptValue_t orgval = *optaddr;
|
||||
|
||||
char optvalString[5];
|
||||
char orgvalString[5];
|
||||
dmaoptToString(optval, optvalString);
|
||||
dmaoptToString(orgval, orgvalString);
|
||||
|
||||
if (optval != orgval) {
|
||||
*optaddr = optval;
|
||||
|
||||
cliPrintLinef("dmaopt %s %d: changed from %s to %s", entry->device, DMA_OPT_UI_INDEX(index), orgvalString, optvalString);
|
||||
} else {
|
||||
cliPrintLinef("dmaopt %s %d: no change", entry->device, DMA_OPT_UI_INDEX(index), orgvalString);
|
||||
}
|
||||
} else {
|
||||
cliPrintLinef("bad option %s", pch);
|
||||
}
|
||||
}
|
||||
#endif // USE_DMA_SPEC
|
||||
#endif // USE_RESOURCE_MGMT
|
||||
|
||||
#ifdef USE_TIMER_MGMT
|
||||
|
||||
|
@ -4358,6 +4579,10 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
#ifdef USE_RESOURCE_MGMT
|
||||
cliPrintHashLine("resources");
|
||||
printResource(dumpMask);
|
||||
#ifdef USE_DMA_SPEC
|
||||
cliPrintHashLine("dmaopt");
|
||||
printDmaopt(dumpMask);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
|
@ -4515,6 +4740,7 @@ static void cliMsc(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
|
||||
typedef struct {
|
||||
const char *name;
|
||||
#ifndef MINIMAL_CLI
|
||||
|
@ -4568,6 +4794,9 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|all] {defaults}", cliDiff),
|
||||
#ifdef USE_RESOURCE_MGMT
|
||||
CLI_COMMAND_DEF("dma", "list dma utilisation", NULL, cliDma),
|
||||
#ifdef USE_DMA_SPEC
|
||||
CLI_COMMAND_DEF("dmaopt", "assign dma spec to a device", "<device> <index> <optnum>", cliDmaopt),
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_DSHOT
|
||||
CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg),
|
||||
|
|
|
@ -32,10 +32,16 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/sdmmc_sdio.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/io.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/sdcard.h"
|
||||
#include "pg/sdio.h"
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
#include "usbd_msc.h"
|
||||
|
@ -148,17 +154,31 @@ USBD_STORAGE_cb_TypeDef USBD_MSC_MICRO_SDIO_fops =
|
|||
static int8_t STORAGE_Init (uint8_t lun)
|
||||
{
|
||||
//Initialize SD_DET
|
||||
#ifdef SDCARD_DETECT_PIN
|
||||
const IO_t sd_det = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
||||
const IO_t sd_det = IOGetByTag(sdcardConfig()->cardDetectTag);
|
||||
IOInit(sd_det, OWNER_SDCARD_DETECT, 0);
|
||||
IOConfigGPIO(sd_det, IOCFG_IPU);
|
||||
#endif
|
||||
|
||||
UNUSED(lun);
|
||||
LED0_OFF;
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpec(DMA_PERIPH_SDIO, 0, sdioConfig()->dmaopt);
|
||||
|
||||
if (!dmaChannelSpec) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
SD_Initialize_LL(dmaChannelSpec->ref);
|
||||
#else
|
||||
SD_Initialize_LL(SDIO_DMA);
|
||||
if (SD_Init() != 0) return 1;
|
||||
#endif
|
||||
|
||||
if (SD_Init() != 0) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
LED0_ON;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -28,6 +28,7 @@
|
|||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/adc_impl.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
|
@ -39,6 +40,9 @@ PG_REGISTER_WITH_RESET_FN(adcConfig_t, adcConfig, PG_ADC_CONFIG, 0);
|
|||
void pgResetFn_adcConfig(adcConfig_t *adcConfig)
|
||||
{
|
||||
adcConfig->device = ADC_DEV_TO_CFG(adcDeviceByInstance(ADC_INSTANCE));
|
||||
adcConfig->dmaopt[ADCDEV_1] = ADC1_DMA_OPT;
|
||||
adcConfig->dmaopt[ADCDEV_2] = ADC2_DMA_OPT;
|
||||
adcConfig->dmaopt[ADCDEV_3] = ADC3_DMA_OPT;
|
||||
|
||||
#ifdef VBAT_ADC_PIN
|
||||
adcConfig->vbat.enabled = true;
|
||||
|
|
|
@ -41,6 +41,8 @@ typedef struct adcConfig_s {
|
|||
uint16_t vrefIntCalibration;
|
||||
uint16_t tempSensorCalibration1;
|
||||
uint16_t tempSensorCalibration2;
|
||||
|
||||
uint8_t dmaopt[3]; // One per ADCDEV_x
|
||||
} adcConfig_t;
|
||||
|
||||
PG_DECLARE(adcConfig_t, adcConfig);
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
|
||||
#ifdef USE_SPI
|
||||
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
|
@ -34,20 +35,22 @@ typedef struct spiDefaultConfig_s {
|
|||
ioTag_t sck;
|
||||
ioTag_t miso;
|
||||
ioTag_t mosi;
|
||||
dmaoptValue_t txDmaopt;
|
||||
dmaoptValue_t rxDmaopt;
|
||||
} spiDefaultConfig_t;
|
||||
|
||||
const spiDefaultConfig_t spiDefaultConfig[] = {
|
||||
#ifdef USE_SPI_DEVICE_1
|
||||
{ SPIDEV_1, IO_TAG(SPI1_SCK_PIN), IO_TAG(SPI1_MISO_PIN), IO_TAG(SPI1_MOSI_PIN) },
|
||||
{ SPIDEV_1, IO_TAG(SPI1_SCK_PIN), IO_TAG(SPI1_MISO_PIN), IO_TAG(SPI1_MOSI_PIN), SPI1_TX_DMA_OPT, SPI1_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_2
|
||||
{ SPIDEV_2, IO_TAG(SPI2_SCK_PIN), IO_TAG(SPI2_MISO_PIN), IO_TAG(SPI2_MOSI_PIN) },
|
||||
{ SPIDEV_2, IO_TAG(SPI2_SCK_PIN), IO_TAG(SPI2_MISO_PIN), IO_TAG(SPI2_MOSI_PIN), SPI2_TX_DMA_OPT, SPI2_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_3
|
||||
{ SPIDEV_3, IO_TAG(SPI3_SCK_PIN), IO_TAG(SPI3_MISO_PIN), IO_TAG(SPI3_MOSI_PIN) },
|
||||
{ SPIDEV_3, IO_TAG(SPI3_SCK_PIN), IO_TAG(SPI3_MISO_PIN), IO_TAG(SPI3_MOSI_PIN), SPI3_TX_DMA_OPT, SPI3_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_4
|
||||
{ SPIDEV_4, IO_TAG(SPI4_SCK_PIN), IO_TAG(SPI4_MISO_PIN), IO_TAG(SPI4_MOSI_PIN) },
|
||||
{ SPIDEV_4, IO_TAG(SPI4_SCK_PIN), IO_TAG(SPI4_MISO_PIN), IO_TAG(SPI4_MOSI_PIN), SPI4_TX_DMA_OPT, SPI4_RX_DMA_OPT },
|
||||
#endif
|
||||
};
|
||||
|
||||
|
@ -60,6 +63,8 @@ void pgResetFn_spiPinConfig(spiPinConfig_t *spiPinConfig)
|
|||
spiPinConfig[defconf->device].ioTagSck = defconf->sck;
|
||||
spiPinConfig[defconf->device].ioTagMiso = defconf->miso;
|
||||
spiPinConfig[defconf->device].ioTagMosi = defconf->mosi;
|
||||
spiPinConfig[defconf->device].txDmaopt = defconf->txDmaopt;
|
||||
spiPinConfig[defconf->device].rxDmaopt = defconf->rxDmaopt;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -29,6 +29,8 @@ typedef struct spiPinConfig_s {
|
|||
ioTag_t ioTagSck;
|
||||
ioTag_t ioTagMiso;
|
||||
ioTag_t ioTagMosi;
|
||||
int8_t txDmaopt;
|
||||
int8_t rxDmaopt;
|
||||
} spiPinConfig_t;
|
||||
|
||||
PG_DECLARE_ARRAY(spiPinConfig_t, SPIDEV_COUNT, spiPinConfig);
|
||||
|
|
|
@ -137,7 +137,8 @@
|
|||
#define PG_GYRO_DEVICE_CONFIG 540
|
||||
#define PG_MCO_CONFIG 541
|
||||
#define PG_RX_SPEKTRUM_SPI_CONFIG 542
|
||||
#define PG_BETAFLIGHT_END 542
|
||||
#define PG_SERIAL_UART_CONFIG 543
|
||||
#define PG_BETAFLIGHT_END 543
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
|
|
|
@ -32,46 +32,52 @@
|
|||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 1);
|
||||
|
||||
void pgResetFn_sdcardConfig(sdcardConfig_t *config)
|
||||
{
|
||||
config->cardDetectTag = IO_TAG(SDCARD_DETECT_PIN);
|
||||
config->cardDetectInverted = SDCARD_DETECT_IS_INVERTED;
|
||||
|
||||
// We can safely handle SPI and SDIO cases separately on custom targets, as these are exclusive per target.
|
||||
// On generic targets, SPI has precedence over SDIO; SDIO must be post-flash configured.
|
||||
config->useDma = false;
|
||||
config->device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
config->mode = SDCARD_MODE_NONE;
|
||||
|
||||
// We can safely handle SPI and SDIO cases separately on custom targets, as these are exclusive per target.
|
||||
// On generic targets, SPI has precedence over SDIO; SDIO must be post-flash configured.
|
||||
|
||||
#ifdef USE_SDCARD_SDIO
|
||||
config->mode = SDCARD_MODE_SDIO;
|
||||
config->useDma = true;
|
||||
#endif
|
||||
|
||||
#ifdef USE_SDCARD_SPI
|
||||
SPIDevice spidevice = spiDeviceByInstance(SDCARD_SPI_INSTANCE);
|
||||
config->device = SPI_DEV_TO_CFG(spidevice);
|
||||
config->chipSelectTag = IO_TAG(SDCARD_SPI_CS_PIN);
|
||||
config->useDma = false;
|
||||
|
||||
if (spidevice != SPIINVALID && config->chipSelectTag) {
|
||||
config->mode = SDCARD_MODE_SPI;
|
||||
}
|
||||
#endif
|
||||
|
||||
config->cardDetectTag = IO_TAG(SDCARD_DETECT_PIN);
|
||||
config->cardDetectInverted = SDCARD_DETECT_IS_INVERTED;
|
||||
|
||||
#ifndef USE_DMA_SPEC
|
||||
#ifdef USE_SDCARD_SPI
|
||||
#if defined(SDCARD_DMA_STREAM_TX_FULL)
|
||||
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDCARD_DMA_STREAM_TX_FULL);
|
||||
#elif defined(SDCARD_DMA_CHANNEL_TX)
|
||||
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDCARD_DMA_CHANNEL_TX);
|
||||
#elif defined(SDIO_DMA)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_SDCARD_SDIO
|
||||
#if defined(SDIO_DMA)
|
||||
config->dmaIdentifier = (uint8_t)dmaGetIdentifier(SDIO_DMA);
|
||||
config->useDma = true;
|
||||
#endif
|
||||
|
||||
#if defined(SDCARD_DMA_CHANNEL)
|
||||
config->dmaChannel = SDCARD_DMA_CHANNEL;
|
||||
#endif
|
||||
#endif // !USE_DMA_SPEC
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -35,8 +35,10 @@ typedef struct sdcardConfig_s {
|
|||
ioTag_t cardDetectTag;
|
||||
ioTag_t chipSelectTag;
|
||||
uint8_t cardDetectInverted;
|
||||
#ifndef USE_DMA_SPEC
|
||||
uint8_t dmaIdentifier;
|
||||
uint8_t dmaChannel;
|
||||
#endif
|
||||
sdcardMode_e mode;
|
||||
} sdcardConfig_t;
|
||||
|
||||
|
|
|
@ -30,7 +30,8 @@ PG_REGISTER_WITH_RESET_TEMPLATE(sdioConfig_t, sdioConfig, PG_SDIO_CONFIG, 0);
|
|||
PG_RESET_TEMPLATE(sdioConfig_t, sdioConfig,
|
||||
.clockBypass = 0,
|
||||
.useCache = 0,
|
||||
.use4BitWidth = true
|
||||
.use4BitWidth = true,
|
||||
.dmaopt = SDCARD_SDIO_DMA_OPT,
|
||||
);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -26,6 +26,7 @@ typedef struct sdioConfig_s {
|
|||
uint8_t clockBypass;
|
||||
uint8_t useCache;
|
||||
uint8_t use4BitWidth;
|
||||
int8_t dmaopt;
|
||||
} sdioConfig_t;
|
||||
|
||||
PG_DECLARE(sdioConfig_t, sdioConfig);
|
||||
|
|
86
src/main/pg/serial_uart.c
Normal file
86
src/main/pg/serial_uart.c
Normal file
|
@ -0,0 +1,86 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_UART
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/serial_uart.h"
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(serialUartConfig_t, UARTDEV_CONFIG_MAX, serialUartConfig, PG_SERIAL_UART_CONFIG, 0);
|
||||
|
||||
typedef struct uartDmaopt_s {
|
||||
UARTDevice_e device;
|
||||
int8_t txDmaopt;
|
||||
int8_t rxDmaopt;
|
||||
} uartDmaopt_t;
|
||||
|
||||
static uartDmaopt_t uartDmaopt[] = {
|
||||
#ifdef USE_UART1
|
||||
{ UARTDEV_1, UART1_TX_DMA_OPT, UART1_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART2
|
||||
{ UARTDEV_2, UART2_TX_DMA_OPT, UART2_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART3
|
||||
{ UARTDEV_3, UART3_TX_DMA_OPT, UART3_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART4
|
||||
{ UARTDEV_4, UART4_TX_DMA_OPT, UART4_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART5
|
||||
{ UARTDEV_5, UART5_TX_DMA_OPT, UART5_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART6
|
||||
{ UARTDEV_6, UART6_TX_DMA_OPT, UART6_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART7
|
||||
{ UARTDEV_7, UART7_TX_DMA_OPT, UART7_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_UART8
|
||||
{ UARTDEV_8, UART8_TX_DMA_OPT, UART8_RX_DMA_OPT },
|
||||
#endif
|
||||
};
|
||||
|
||||
void pgResetFn_serialUartConfig(serialUartConfig_t *config)
|
||||
{
|
||||
for (unsigned i = 0; i < UARTDEV_CONFIG_MAX; i++) {
|
||||
config[i].txDmaopt = -1;
|
||||
config[i].rxDmaopt = -1;
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < ARRAYLEN(uartDmaopt); i++) {
|
||||
UARTDevice_e device = uartDmaopt[i].device;
|
||||
config[device].txDmaopt = uartDmaopt[i].txDmaopt;
|
||||
config[device].rxDmaopt = uartDmaopt[i].rxDmaopt;
|
||||
}
|
||||
}
|
||||
#endif
|
36
src/main/pg/serial_uart.h
Normal file
36
src/main/pg/serial_uart.h
Normal file
|
@ -0,0 +1,36 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
#define UARTDEV_CONFIG_MAX 8 // Alternative to UARTDEV_COUNT_MAX, which requires serial_uart_imp.h
|
||||
|
||||
typedef struct serialUartConfig_s {
|
||||
int8_t txDmaopt;
|
||||
int8_t rxDmaopt;
|
||||
} serialUartConfig_t;
|
||||
|
||||
PG_DECLARE_ARRAY(serialUartConfig_t, UARTDEV_CONFIG_MAX, serialUartConfig);
|
|
@ -73,8 +73,7 @@
|
|||
#define SDCARD_DETECT_PIN PB11
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB10
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
@ -139,7 +138,9 @@
|
|||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
//#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
//#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define VBAT_ADC_PIN PC0
|
||||
|
|
|
@ -81,8 +81,7 @@
|
|||
#define SDCARD_DETECT_PIN PB11
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB10
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
@ -153,7 +152,9 @@
|
|||
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
//#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
//#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define VBAT_ADC_PIN PC0
|
||||
|
|
|
@ -140,8 +140,7 @@
|
|||
#define SDCARD_DETECT_PIN PD3
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
#define SPI4_TX_DMA_OPT 0 // DMA 2 Stream 1 Channel 4
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2 // External I2C
|
||||
|
|
|
@ -57,9 +57,8 @@
|
|||
#define MAX7456_SPI_INSTANCE SPI3
|
||||
#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN
|
||||
|
||||
#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0
|
||||
#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
#define SPI3_RX_DMA_OPT 0 // DMA 1 Stream 0 Channel 0
|
||||
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
|
@ -67,8 +66,7 @@
|
|||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USB_DETECT
|
||||
|
@ -128,7 +126,9 @@
|
|||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC0
|
||||
|
||||
|
|
|
@ -77,8 +77,7 @@
|
|||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
|
|
@ -74,8 +74,7 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
|
|
@ -127,6 +127,7 @@
|
|||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
#define VBAT_ADC_PIN PA6
|
||||
#else
|
||||
|
|
|
@ -131,7 +131,9 @@
|
|||
|
||||
//ADC ----------------------------------------------
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PA0 //TIM5_CH1 & UART4_TX & TELEMETRY & FPORT
|
||||
|
|
|
@ -127,7 +127,8 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||
#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC0
|
||||
|
|
|
@ -124,7 +124,8 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||
#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -64,8 +64,7 @@
|
|||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PE15
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USB_DETECT
|
||||
|
|
|
@ -111,8 +111,7 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PB9
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
// *************** RTC6705 *************************
|
||||
#define USE_VTX_RTC6705
|
||||
|
|
3
src/main/target/FLYWOOF7DUAL/target.h
Executable file → Normal file
3
src/main/target/FLYWOOF7DUAL/target.h
Executable file → Normal file
|
@ -140,7 +140,8 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||
#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2
|
||||
|
||||
|
||||
#define CURRENT_METER_ADC_PIN PC0
|
||||
#define VBAT_ADC_PIN PC1
|
||||
|
|
|
@ -125,7 +125,9 @@
|
|||
|
||||
//ADC ----------------------------------------------
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PA0 //TIM5_CH1 & UART4_TX & TELEMETRY & FPORT
|
||||
|
|
|
@ -125,7 +125,8 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||
#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -68,8 +68,7 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USB_DETECT
|
||||
|
|
|
@ -81,10 +81,8 @@
|
|||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
//#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
//#define SDCARD_DMA_CHANNEL 0
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#endif
|
||||
|
|
|
@ -83,8 +83,7 @@
|
|||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
#define SPI4_TX_DMA_OPT 0 // DMA 2 Stream 1 Channel 4
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
|
4
src/main/target/HAKRCF405/target.h
Executable file → Normal file
4
src/main/target/HAKRCF405/target.h
Executable file → Normal file
|
@ -131,7 +131,9 @@
|
|||
#define MAX7456_SPI_CS_PIN PA15
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC0
|
||||
|
|
|
@ -124,7 +124,9 @@
|
|||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC0
|
||||
|
|
|
@ -172,7 +172,9 @@
|
|||
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC1
|
||||
|
|
|
@ -128,8 +128,7 @@
|
|||
#define SDCARD_DETECT_PIN PD8
|
||||
#define SDCARD_SPI_INSTANCE SPI1
|
||||
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 3
|
||||
#define SPI1_TX_DMA_OPT 1 // DMA 2 Stream 5 Channel 3
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
|
|
@ -74,9 +74,8 @@
|
|||
#else
|
||||
#define MAX7456_SPI_INSTANCE SPI2
|
||||
#define MAX7456_SPI_CS_PIN PB12
|
||||
//#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5
|
||||
//#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0
|
||||
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
|
||||
//#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5 // Can't convert to dmaopt
|
||||
//#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0 // Can't convert to dmaopt
|
||||
#endif
|
||||
|
||||
#if defined(KIWIF4V2)
|
||||
|
@ -85,10 +84,8 @@
|
|||
//#define SDCARD_DETECT_PIN PB9
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
//#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
//#define SDCARD_DMA_CHANNEL 0
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#else
|
||||
#define USE_FLASHFS
|
||||
|
|
|
@ -69,8 +69,7 @@
|
|||
#define SDCARD_DETECT_PIN PC13
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
#undef USE_MSP_DISPLAYPORT
|
||||
|
@ -85,6 +84,7 @@
|
|||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC0
|
||||
|
|
|
@ -84,7 +84,7 @@
|
|||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_SPI_DMA_OPT 0 // DMA 1 Channel 5
|
||||
#endif
|
||||
|
||||
#define GYRO_1_CS_PIN SPI1_NSS_PIN
|
||||
|
|
|
@ -108,8 +108,7 @@
|
|||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PC1
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 1 // DMA 1 Stream 7 Channel 0
|
||||
|
||||
// *************** OSD *****************************
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
@ -157,7 +156,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC5
|
||||
#define CURRENT_METER_ADC_PIN PC4
|
||||
#define RSSI_ADC_PIN PB1
|
||||
|
|
|
@ -103,7 +103,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PB0
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
//#define RSSI_ADC_PIN PA0
|
||||
|
|
|
@ -158,7 +158,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PB0
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
|
||||
|
|
|
@ -94,8 +94,7 @@
|
|||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PC1
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream7
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 1 // DMA 1 Stream 7 Channel 0
|
||||
|
||||
// *************** OSD *****************************
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
@ -141,7 +140,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC4
|
||||
#define RSSI_ADC_PIN PB0
|
||||
|
|
7
src/main/target/MATEKF722SE/target.h
Executable file → Normal file
7
src/main/target/MATEKF722SE/target.h
Executable file → Normal file
|
@ -119,8 +119,7 @@
|
|||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PD2
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
@ -163,7 +162,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC0
|
||||
|
|
|
@ -122,8 +122,7 @@
|
|||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
#define SDCARD_SPI_CS_CFG IOCFG_OUT_OD
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
// Pins are available unless USART3 is connected, not connected
|
||||
//#define USE_I2C
|
||||
|
|
|
@ -59,8 +59,7 @@
|
|||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
//#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream5
|
||||
//#define SDCARD_DMA_CHANNEL 0
|
||||
//#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
|
|
@ -146,7 +146,9 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
//#define ADC_INSTANCE ADC2
|
||||
//#define ADC2_DMA_OPT 1 // DMA 2 Stream 3 Channel 1 (compat default)
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
|
|
|
@ -129,8 +129,7 @@
|
|||
#define SDCARD_DETECT_PIN PF14
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
#define SPI4_TX_DMA_OPT 0 // DMA 2 Stream 1 Channel 4
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
|
|
@ -130,11 +130,10 @@
|
|||
//#define SDCARD_DETECT_PIN PF14
|
||||
//#define SDCARD_SPI_INSTANCE SPI4
|
||||
//#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
//#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
//#define SDCARD_DMA_CHANNEL 4
|
||||
//#define SPI4_TX_DMA_OPT 0 // DMA 2 Stream 1 Channel 4
|
||||
#define USE_SDCARD_SDIO
|
||||
|
||||
#define SDIO_DMA DMA2_Stream3
|
||||
#define SDIO_DMA_OPT 0 // DMA 2 Stream 3 Chanel 4
|
||||
#define SDCARD_SPI_CS_PIN NONE //This is not used on SDIO, has to be kept for now to keep compiler happy
|
||||
|
||||
#define USE_I2C
|
||||
|
|
|
@ -122,6 +122,8 @@
|
|||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
//#define SPI1_TX_DMA_OPT 0 // DMA1_Channel3
|
||||
//#define SPI1_RX_DMA_OPT 0 // DMA1_Channel2
|
||||
|
||||
// OSD define info:
|
||||
// feature name (includes source) -> MAX_OSD, used in target.mk
|
||||
|
@ -132,8 +134,6 @@
|
|||
#define MAX7456_SPI_CS_PIN PB1
|
||||
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
|
||||
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||
//#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3
|
||||
//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2
|
||||
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER
|
||||
|
||||
#define USE_SPI
|
||||
|
@ -153,7 +153,7 @@
|
|||
// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative
|
||||
|
||||
#ifndef USE_DSHOT
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_SPI_DMA_OPT 0 // DMA 1 Channel 5
|
||||
#endif
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
|
|
|
@ -155,8 +155,7 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
// For variants with SDcard replaced with flash chip
|
||||
#define FLASH_CS_PIN SDCARD_SPI_CS_PIN
|
||||
|
@ -249,7 +248,9 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC2_DMA_OPT 1 // DMA 2 Stream 3 Channel 1 (compat default)
|
||||
//#define ADC_INSTANCE ADC1
|
||||
//#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
|
||||
#define CURRENT_METER_ADC_PIN PC1 // Direct from CRNT pad (part of onboard sensor for Pro)
|
||||
#define VBAT_ADC_PIN PC2 // 11:1 (10K + 1K) divider
|
||||
|
|
|
@ -187,6 +187,7 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC2_DMA_OPT 1 // DMA 2 Stream 3 Channel 1 (compat default)
|
||||
#define CURRENT_METER_ADC_PIN PC1 // Direct from CRNT pad (part of onboard sensor for Pro)
|
||||
#define VBAT_ADC_PIN PC2 // 11:1 (10K + 1K) divider
|
||||
#define RSSI_ADC_PIN PA0 // Direct from RSSI pad
|
||||
|
|
|
@ -189,8 +189,7 @@
|
|||
#define SDCARD_DETECT_PIN PE3
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
#define SPI4_TX_DMA_OPT 0 // DMA 2 Stream 1 Channel 4
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -219,6 +218,7 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define RSSI_ADC_PIN PC5
|
||||
|
|
|
@ -155,7 +155,14 @@ static uint16_t adcIDDetectReadVrefint(void)
|
|||
#include "drivers/adc_impl.h"
|
||||
|
||||
static adcDevice_t adcIDDetHardware =
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = ADC1_DMA_STREAM, .channel = DMA_CHANNEL_0 };
|
||||
{
|
||||
.ADCx = ADC1,
|
||||
.rccADC = RCC_APB2(ADC1),
|
||||
#if !defined(USE_DMA_SPEC)
|
||||
.DMAy_Streamx = ADC1_DMA_STREAM,
|
||||
.channel = DMA_CHANNEL_0
|
||||
#endif
|
||||
};
|
||||
|
||||
// XXX adcIDDetectInitDevice is an exact copy of adcInitDevice() from adc_stm32f7xx.c. Export and use?
|
||||
|
||||
|
|
|
@ -172,6 +172,8 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
#define VBAT_ADC_PIN PC0 // 11:1 (10K + 1K) divider
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC4
|
||||
|
|
|
@ -164,8 +164,7 @@
|
|||
#define SDCARD_DETECT_PIN PC0
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN SPI3_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
#else
|
||||
|
||||
|
|
|
@ -124,15 +124,14 @@
|
|||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA2_Channel2
|
||||
#define SPI3_RX_DMA_OPT 0 // DMA2_Channel1
|
||||
|
||||
#define REMAP_TIM17_DMA
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI3
|
||||
#define MAX7456_SPI_CS_PIN PA15
|
||||
|
||||
#define MAX7456_DMA_CHANNEL_TX DMA2_Channel2
|
||||
#define MAX7456_DMA_CHANNEL_RX DMA2_Channel1
|
||||
#define MAX7456_DMA_IRQ_HANDLER_ID DMA2_CH1_HANDLER
|
||||
|
||||
#define USE_VTX_RTC6705
|
||||
|
@ -149,7 +148,7 @@
|
|||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#define SDCARD_SPI_DMA_OPT 0 // DMA 1 Channel 5
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
|
|
@ -129,7 +129,9 @@
|
|||
#define SBUS_TELEMETRY_UART SERIAL_PORT_USART3
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PA0
|
||||
|
|
|
@ -130,7 +130,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define RSSI_ADC_PIN PC3
|
||||
|
|
|
@ -116,6 +116,7 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default)
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
|
||||
|
|
|
@ -136,9 +136,6 @@
|
|||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI3
|
||||
#define MAX7456_SPI_CS_PIN PA15
|
||||
|
||||
#define MAX7456_DMA_CHANNEL_TX DMA2_Channel2
|
||||
#define MAX7456_DMA_CHANNEL_RX DMA2_Channel1
|
||||
#define MAX7456_DMA_IRQ_HANDLER_ID DMA2_CH1_HANDLER
|
||||
|
||||
#define SPI_SHARED_MAX7456_AND_RTC6705
|
||||
|
|
|
@ -148,8 +148,7 @@
|
|||
#define SDCARD_DETECT_PIN PC14
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#ifndef SPRACINGF4EVODG
|
||||
#define GYRO_1_CS_PIN SPI1_NSS_PIN
|
||||
|
@ -165,11 +164,13 @@
|
|||
#define USE_ADC
|
||||
// It's possible to use ADC1 or ADC3 on this target, same pins.
|
||||
//#define ADC_INSTANCE ADC1
|
||||
//#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
//#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
|
||||
// Using ADC3 frees up DMA2_Stream0 for SPI1_RX
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define ADC3_DMA_STREAM DMA2_Stream1
|
||||
#define ADC3_DMA_OPT 1 // DMA 2 Stream 1 Channel 2
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -155,10 +155,8 @@
|
|||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_INSTANCE SPI3
|
||||
#define MAX7456_SPI_CS_PIN PA15
|
||||
|
||||
//#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5
|
||||
//#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0
|
||||
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
|
||||
//#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
//#define SPI3_RX_DMA_OPT 0 // DMA 1 Stream 0 Channel 0
|
||||
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
|
@ -166,15 +164,15 @@
|
|||
#define SDCARD_DETECT_PIN PC14
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
|
||||
#define GYRO_1_CS_PIN SPI1_NSS_PIN
|
||||
#define GYRO_1_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -146,8 +146,7 @@
|
|||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PC3
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream7
|
||||
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_0
|
||||
#define SPI3_TX_DMA_OPT 1 // DMA 1 Stream 7 Channel 0
|
||||
|
||||
#define USE_VTX_RTC6705
|
||||
#define USE_VTX_RTC6705_SOFTSPI
|
||||
|
@ -166,11 +165,13 @@
|
|||
#define USE_ADC
|
||||
// It's possible to use ADC1 or ADC3 on this target, same pins.
|
||||
//#define ADC_INSTANCE ADC1
|
||||
//#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
//#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
|
||||
// Using ADC3 frees up DMA2_Stream0 for SPI1_RX (not necessarily, SPI1_RX has DMA2_Stream2 as well)
|
||||
#define ADC_INSTANCE ADC3
|
||||
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||
#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2
|
||||
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -98,8 +98,7 @@
|
|||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PD8
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
#define USE_ADC
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
|
|
|
@ -69,7 +69,8 @@
|
|||
#define SDCARD_DETECT_PIN PE2
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#warning Missing channel for F4/F7 spec dma 1 stream 4; DMA_OPT assumed as 0
|
||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel unknown
|
||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||
#endif
|
||||
|
||||
|
|
|
@ -73,8 +73,7 @@
|
|||
/*
|
||||
*/
|
||||
/*
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0
|
||||
*/
|
||||
|
||||
|
||||
|
|
|
@ -195,7 +195,7 @@
|
|||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SDIO
|
||||
|
||||
#define SDIO_DMA DMA2_Stream3
|
||||
#define SDIO_DMA_OPT 0 // DMA 2 Stream 3 Channel 4
|
||||
#define SDCARD_SPI_CS_PIN NONE //This is not used on SDIO, has to be kept for now to keep compiler happy
|
||||
#if defined(PIRXF4)
|
||||
#define SDCARD_DETECT_PIN PC15
|
||||
|
|
|
@ -88,8 +88,7 @@
|
|||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
#define SPI3_TX_DMA_OPT 0 // DMA 1 Stream 5 Channel 0
|
||||
|
||||
// SPI Ports
|
||||
#define USE_SPI
|
||||
|
|
|
@ -125,7 +125,9 @@
|
|||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_INSTANCE ADC1 // Default added
|
||||
#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
|
||||
|
||||
#define RSSI_ADC_PIN PC0
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_PIN PC2
|
||||
|
|
|
@ -330,9 +330,6 @@
|
|||
#ifndef SDCARD_DETECT_PIN
|
||||
#define SDCARD_DETECT_PIN NONE
|
||||
#endif
|
||||
#ifndef SDCARD_SPI_CS_PIN
|
||||
#define SDCARD_SPI_CS_PIN NONE
|
||||
#endif
|
||||
#ifdef SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_IS_INVERTED 1
|
||||
#else
|
||||
|
@ -342,8 +339,16 @@
|
|||
#ifndef SDCARD_SPI_INSTANCE
|
||||
#define SDCARD_SPI_INSTANCE NULL
|
||||
#endif
|
||||
#ifndef SDCARD_SPI_CS_PIN
|
||||
#define SDCARD_SPI_CS_PIN NONE
|
||||
#endif
|
||||
#endif // USE_SDCARD_SPI
|
||||
#ifdef USE_SDCARD_SDIO
|
||||
#ifndef SDCARD_SDIO_DMA_OPT
|
||||
#define SDCARD_SDIO_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif // USE_SDCARD_SDIO
|
||||
#endif // USE_SDCARD
|
||||
|
||||
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8)
|
||||
#define USE_UART
|
||||
|
@ -397,3 +402,130 @@
|
|||
#define BARO_I2C_INSTANCE I2C_DEVICE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_ADC
|
||||
#if !defined(GENERIC_TARGET) && !defined(ADC_INSTANCE)
|
||||
#define ADC_INSTANCE ADC1
|
||||
#ifndef ADC1_DMA_OPT
|
||||
#define ADC1_DMA_OPT 1
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if !defined(ADC1_DMA_OPT)
|
||||
#define ADC1_DMA_OPT (-1)
|
||||
#endif
|
||||
#if !defined(ADC2_DMA_OPT)
|
||||
#define ADC2_DMA_OPT (-1)
|
||||
#endif
|
||||
#if !defined(ADC3_DMA_OPT)
|
||||
#define ADC3_DMA_OPT (-1)
|
||||
#endif
|
||||
|
||||
#endif // USE_ADC
|
||||
|
||||
#ifdef USE_SPI
|
||||
#ifdef USE_SPI_DEVICE_1
|
||||
#ifndef SPI1_TX_DMA_OPT
|
||||
#define SPI1_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef SPI1_RX_DMA_OPT
|
||||
#define SPI1_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_2
|
||||
#ifndef SPI2_TX_DMA_OPT
|
||||
#define SPI2_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef SPI2_RX_DMA_OPT
|
||||
#define SPI2_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_3
|
||||
#ifndef SPI3_TX_DMA_OPT
|
||||
#define SPI3_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef SPI3_RX_DMA_OPT
|
||||
#define SPI3_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_SPI_DEVICE_4
|
||||
#ifndef SPI4_TX_DMA_OPT
|
||||
#define SPI4_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef SPI4_RX_DMA_OPT
|
||||
#define SPI4_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART1
|
||||
#ifndef UART1_TX_DMA_OPT
|
||||
#define UART1_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART1_RX_DMA_OPT
|
||||
#define UART1_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2
|
||||
#ifndef UART2_TX_DMA_OPT
|
||||
#define UART2_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART2_RX_DMA_OPT
|
||||
#define UART2_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART3
|
||||
#ifndef UART3_TX_DMA_OPT
|
||||
#define UART3_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART3_RX_DMA_OPT
|
||||
#define UART3_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART4
|
||||
#ifndef UART4_TX_DMA_OPT
|
||||
#define UART4_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART4_RX_DMA_OPT
|
||||
#define UART4_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART5
|
||||
#ifndef UART5_TX_DMA_OPT
|
||||
#define UART5_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART5_RX_DMA_OPT
|
||||
#define UART5_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART6
|
||||
#ifndef UART6_TX_DMA_OPT
|
||||
#define UART6_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART6_RX_DMA_OPT
|
||||
#define UART6_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART7
|
||||
#ifndef UART7_TX_DMA_OPT
|
||||
#define UART7_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART7_RX_DMA_OPT
|
||||
#define UART7_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART8
|
||||
#ifndef UART8_TX_DMA_OPT
|
||||
#define UART8_TX_DMA_OPT (-1)
|
||||
#endif
|
||||
#ifndef UART8_RX_DMA_OPT
|
||||
#define UART8_RX_DMA_OPT (-1)
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -60,6 +60,7 @@
|
|||
#define USE_USB_CDC_HID
|
||||
#define USE_USB_MSC
|
||||
#define USE_PERSISTENT_MSC_RTC
|
||||
#define USE_DMA_SPEC
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
|
||||
#define USE_OVERCLOCK
|
||||
|
@ -81,7 +82,8 @@
|
|||
#define USE_USB_MSC
|
||||
#define USE_PERSISTENT_MSC_RTC
|
||||
#define USE_MCO
|
||||
#endif
|
||||
#define USE_DMA_SPEC
|
||||
#endif // STM32F7
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
|
||||
|
@ -142,8 +144,6 @@
|
|||
#define USE_SERIALRX_SUMH // Graupner legacy protocol
|
||||
#define USE_SERIALRX_XBUS // JR
|
||||
|
||||
|
||||
|
||||
#if (FLASH_SIZE > 64)
|
||||
#define MAX_PROFILE_COUNT 3
|
||||
#else
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue