Fix Spracing Mini merge
This commit is contained in:
parent
a259a49db1
commit
220850e429
3
Makefile
3
Makefile
|
@ -54,7 +54,7 @@ OPBL_VALID_TARGETS = CC3D_OPBL
|
|||
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
|
||||
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI
|
||||
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI
|
||||
|
||||
|
||||
# Configure default flash sizes for the targets
|
||||
|
@ -741,7 +741,6 @@ SPRACINGF3MINI_SRC = \
|
|||
drivers/sdcard_standard.c \
|
||||
drivers/transponder_ir.c \
|
||||
drivers/transponder_ir_stm32f30x.c \
|
||||
drivers/usb_detection.c \
|
||||
io/asyncfatfs/asyncfatfs.c \
|
||||
io/asyncfatfs/fat_standard.c \
|
||||
io/transponder_ir.c \
|
||||
|
|
|
@ -15,213 +15,6 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
void SD_Detect_LowLevel_DeInit(void);
|
||||
void SD_Detect_LowLevel_Init(void);
|
||||
|
||||
|
||||
/** @defgroup STM32303C_EVAL_SPI_SD_Exported_Types
|
||||
* @{
|
||||
*/
|
||||
|
||||
typedef enum
|
||||
{
|
||||
/**
|
||||
* @brief SD reponses and error flags
|
||||
*/
|
||||
SD_RESPONSE_NO_ERROR = (0x00),
|
||||
SD_IN_IDLE_STATE = (0x01),
|
||||
SD_ERASE_RESET = (0x02),
|
||||
SD_ILLEGAL_COMMAND = (0x04),
|
||||
SD_COM_CRC_ERROR = (0x08),
|
||||
SD_ERASE_SEQUENCE_ERROR = (0x10),
|
||||
SD_ADDRESS_ERROR = (0x20),
|
||||
SD_PARAMETER_ERROR = (0x40),
|
||||
SD_RESPONSE_FAILURE = (0xFF),
|
||||
|
||||
/**
|
||||
* @brief Data response error
|
||||
*/
|
||||
SD_DATA_OK = (0x05),
|
||||
SD_DATA_CRC_ERROR = (0x0B),
|
||||
SD_DATA_WRITE_ERROR = (0x0D),
|
||||
SD_DATA_OTHER_ERROR = (0xFF)
|
||||
} SD_Error;
|
||||
|
||||
/**
|
||||
* @brief Card Specific Data: CSD Register
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
__IO uint8_t CSDStruct; /*!< CSD structure */
|
||||
__IO uint8_t SysSpecVersion; /*!< System specification version */
|
||||
__IO uint8_t Reserved1; /*!< Reserved */
|
||||
__IO uint8_t TAAC; /*!< Data read access-time 1 */
|
||||
__IO uint8_t NSAC; /*!< Data read access-time 2 in CLK cycles */
|
||||
__IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */
|
||||
__IO uint16_t CardComdClasses; /*!< Card command classes */
|
||||
__IO uint8_t RdBlockLen; /*!< Max. read data block length */
|
||||
__IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */
|
||||
__IO uint8_t WrBlockMisalign; /*!< Write block misalignment */
|
||||
__IO uint8_t RdBlockMisalign; /*!< Read block misalignment */
|
||||
__IO uint8_t DSRImpl; /*!< DSR implemented */
|
||||
__IO uint8_t Reserved2; /*!< Reserved */
|
||||
__IO uint32_t DeviceSize; /*!< Device Size */
|
||||
__IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */
|
||||
__IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */
|
||||
__IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */
|
||||
__IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */
|
||||
__IO uint8_t DeviceSizeMul; /*!< Device size multiplier */
|
||||
__IO uint8_t EraseGrSize; /*!< Erase group size */
|
||||
__IO uint8_t EraseGrMul; /*!< Erase group size multiplier */
|
||||
__IO uint8_t WrProtectGrSize; /*!< Write protect group size */
|
||||
__IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */
|
||||
__IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */
|
||||
__IO uint8_t WrSpeedFact; /*!< Write speed factor */
|
||||
__IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */
|
||||
__IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */
|
||||
__IO uint8_t Reserved3; /*!< Reserded */
|
||||
__IO uint8_t ContentProtectAppli; /*!< Content protection application */
|
||||
__IO uint8_t FileFormatGrouop; /*!< File format group */
|
||||
__IO uint8_t CopyFlag; /*!< Copy flag (OTP) */
|
||||
__IO uint8_t PermWrProtect; /*!< Permanent write protection */
|
||||
__IO uint8_t TempWrProtect; /*!< Temporary write protection */
|
||||
__IO uint8_t FileFormat; /*!< File Format */
|
||||
__IO uint8_t ECC; /*!< ECC code */
|
||||
__IO uint8_t CSD_CRC; /*!< CSD CRC */
|
||||
__IO uint8_t Reserved4; /*!< always 1*/
|
||||
} SD_CSD;
|
||||
|
||||
/**
|
||||
* @brief Card Identification Data: CID Register
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
__IO uint8_t ManufacturerID; /*!< ManufacturerID */
|
||||
__IO uint16_t OEM_AppliID; /*!< OEM/Application ID */
|
||||
__IO uint32_t ProdName1; /*!< Product Name part1 */
|
||||
__IO uint8_t ProdName2; /*!< Product Name part2*/
|
||||
__IO uint8_t ProdRev; /*!< Product Revision */
|
||||
__IO uint32_t ProdSN; /*!< Product Serial Number */
|
||||
__IO uint8_t Reserved1; /*!< Reserved1 */
|
||||
__IO uint16_t ManufactDate; /*!< Manufacturing Date */
|
||||
__IO uint8_t CID_CRC; /*!< CID CRC */
|
||||
__IO uint8_t Reserved2; /*!< always 1 */
|
||||
} SD_CID;
|
||||
|
||||
/**
|
||||
* @brief SD Card information
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
SD_CSD SD_csd;
|
||||
SD_CID SD_cid;
|
||||
uint32_t CardCapacity; /*!< Card Capacity */
|
||||
uint32_t CardBlockSize; /*!< Card Block Size */
|
||||
} SD_CardInfo;
|
||||
|
||||
|
||||
/** @defgroup STM32303C_EVAL_SPI_SD_Exported_Constants
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Block Size
|
||||
*/
|
||||
#define SD_BLOCK_SIZE 0x200
|
||||
|
||||
/**
|
||||
* @brief Dummy byte
|
||||
*/
|
||||
#define SD_DUMMY_BYTE 0xFF
|
||||
|
||||
/**
|
||||
* @brief Start Data tokens:
|
||||
* Tokens (necessary because at nop/idle (and CS active) only 0xff is
|
||||
* on the data/command line)
|
||||
*/
|
||||
#define SD_START_DATA_SINGLE_BLOCK_READ 0xFE /*!< Data token start byte, Start Single Block Read */
|
||||
#define SD_START_DATA_MULTIPLE_BLOCK_READ 0xFE /*!< Data token start byte, Start Multiple Block Read */
|
||||
#define SD_START_DATA_SINGLE_BLOCK_WRITE 0xFE /*!< Data token start byte, Start Single Block Write */
|
||||
#define SD_START_DATA_MULTIPLE_BLOCK_WRITE 0xFD /*!< Data token start byte, Start Multiple Block Write */
|
||||
#define SD_STOP_DATA_MULTIPLE_BLOCK_WRITE 0xFD /*!< Data toke stop byte, Stop Multiple Block Write */
|
||||
|
||||
/**
|
||||
* @brief SD detection on its memory slot
|
||||
*/
|
||||
#define SD_PRESENT ((uint8_t)0x01)
|
||||
#define SD_NOT_PRESENT ((uint8_t)0x00)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Commands: CMDxx = CMD-number | 0x40
|
||||
*/
|
||||
#define SD_CMD_GO_IDLE_STATE 0 /*!< CMD0 = 0x40 */
|
||||
#define SD_CMD_SEND_OP_COND 1 /*!< CMD1 = 0x41 */
|
||||
#define SD_CMD_SEND_IF_COND 8
|
||||
#define SD_CMD_SEND_CSD 9 /*!< CMD9 = 0x49 */
|
||||
#define SD_CMD_SEND_CID 10 /*!< CMD10 = 0x4A */
|
||||
#define SD_CMD_STOP_TRANSMISSION 12 /*!< CMD12 = 0x4C */
|
||||
#define SD_CMD_SEND_STATUS 13 /*!< CMD13 = 0x4D */
|
||||
#define SD_CMD_SET_BLOCKLEN 16 /*!< CMD16 = 0x50 */
|
||||
#define SD_CMD_READ_SINGLE_BLOCK 17 /*!< CMD17 = 0x51 */
|
||||
#define SD_CMD_READ_MULT_BLOCK 18 /*!< CMD18 = 0x52 */
|
||||
#define SD_CMD_SET_BLOCK_COUNT 23 /*!< CMD23 = 0x57 */
|
||||
#define SD_CMD_WRITE_SINGLE_BLOCK 24 /*!< CMD24 = 0x58 */
|
||||
#define SD_CMD_WRITE_MULT_BLOCK 25 /*!< CMD25 = 0x59 */
|
||||
#define SD_CMD_PROG_CSD 27 /*!< CMD27 = 0x5B */
|
||||
#define SD_CMD_SET_WRITE_PROT 28 /*!< CMD28 = 0x5C */
|
||||
#define SD_CMD_CLR_WRITE_PROT 29 /*!< CMD29 = 0x5D */
|
||||
#define SD_CMD_SEND_WRITE_PROT 30 /*!< CMD30 = 0x5E */
|
||||
#define SD_CMD_SD_ERASE_GRP_START 32 /*!< CMD32 = 0x60 */
|
||||
#define SD_CMD_SD_ERASE_GRP_END 33 /*!< CMD33 = 0x61 */
|
||||
#define SD_CMD_UNTAG_SECTOR 34 /*!< CMD34 = 0x62 */
|
||||
#define SD_CMD_ERASE_GRP_START 35 /*!< CMD35 = 0x63 */
|
||||
#define SD_CMD_ERASE_GRP_END 36 /*!< CMD36 = 0x64 */
|
||||
#define SD_CMD_UNTAG_ERASE_GROUP 37 /*!< CMD37 = 0x65 */
|
||||
#define SD_CMD_ERASE 38 /*!< CMD38 = 0x66 */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup STM32303C_EVAL_SPI_SD_Exported_Macros
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @brief Select SD Card: ChipSelect pin low
|
||||
*/
|
||||
#define SD_CS_LOW() GPIO_ResetBits(SD_CS_GPIO, SD_CS_PIN)
|
||||
/**
|
||||
* @brief Deselect SD Card: ChipSelect pin high
|
||||
*/
|
||||
#define SD_CS_HIGH() GPIO_SetBits(SD_CS_GPIO, SD_CS_PIN)
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup STM32303C_EVAL_SPI_SD_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
void SD_DeInit(void);
|
||||
SD_Error SD_Init(void);
|
||||
uint8_t SD_Detect(void);
|
||||
SD_Error SD_GetCardInfo(SD_CardInfo *cardinfo);
|
||||
SD_Error SD_ReadBlock(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t BlockSize);
|
||||
SD_Error SD_ReadMultiBlocks(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t BlockSize, uint32_t NumberOfBlocks);
|
||||
SD_Error SD_WriteBlock(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t BlockSize);
|
||||
SD_Error SD_WriteMultiBlocks(uint8_t* pBuffer, uint32_t WriteAddr, uint16_t BlockSize, uint32_t NumberOfBlocks);
|
||||
SD_Error SD_GetCSDRegister(SD_CSD* SD_csd);
|
||||
SD_Error SD_GetCIDRegister(SD_CID* SD_cid);
|
||||
|
||||
void SD_SendCmd(uint8_t Cmd, uint32_t Arg, uint8_t Crc);
|
||||
SD_Error SD_GetResponse(uint8_t Response);
|
||||
uint8_t SD_GetDataResponse(void);
|
||||
SD_Error SD_GoIdleState(void);
|
||||
uint16_t SD_GetStatus(void);
|
||||
|
||||
uint8_t SD_WriteByte(uint8_t byte);
|
||||
uint8_t SD_ReadByte(void);
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -0,0 +1,99 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "sdcard.h"
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/usb_io.h"
|
||||
|
||||
#ifdef USB_IO
|
||||
|
||||
void usbCableDetectDeinit(void)
|
||||
{
|
||||
#ifdef USB_CABLE_DETECTION
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = USB_DETECT_PIN;
|
||||
GPIO_Init(USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
|
||||
#endif
|
||||
}
|
||||
|
||||
void usbCableDetectInit(void)
|
||||
{
|
||||
#ifdef USB_CABLE_DETECTION
|
||||
RCC_AHBPeriphClockCmd(USB_DETECT_GPIO_CLK, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = USB_DETECT_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
||||
GPIO_Init(USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
|
||||
#endif
|
||||
}
|
||||
|
||||
bool usbCableIsInserted(void)
|
||||
{
|
||||
bool result = false;
|
||||
|
||||
#ifdef USB_CABLE_DETECTION
|
||||
result = (GPIO_ReadInputData(USB_DETECT_GPIO_PORT) & USB_DETECT_PIN) != 0;
|
||||
#endif
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void usbGenerateDisconnectPulse(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
/* Pull down PA12 to create USB disconnect pulse */
|
||||
#if defined(STM32F303xC)
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
#else
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
|
||||
#endif
|
||||
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
GPIO_ResetBits(GPIOA, GPIO_Pin_12);
|
||||
|
||||
delay(200);
|
||||
|
||||
GPIO_SetBits(GPIOA, GPIO_Pin_12);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,24 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
void usbGenerateDisconnectPulse(void);
|
||||
|
||||
void usbCableDetectDeinit(void);
|
||||
void usbCableDetectInit(void);
|
||||
bool usbCableIsInserted(void);
|
|
@ -28,7 +28,7 @@
|
|||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/usb_detection.h"
|
||||
#include "drivers/usb_io.h"
|
||||
|
||||
#include "io/transponder_ir.h"
|
||||
#include "config/config.h"
|
||||
|
@ -65,7 +65,7 @@ void updateTransponder(void)
|
|||
|
||||
nextUpdateAt = now + 4500 + jitter;
|
||||
|
||||
#ifdef SPRACINGF3MINI
|
||||
#ifdef REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
|
||||
// reduce current draw when USB cable is plugged in by decreasing the transponder transmit rate.
|
||||
if (usbCableIsInserted()) {
|
||||
nextUpdateAt = now + (1000 * 1000) / 10; // 10 hz.
|
||||
|
|
|
@ -51,6 +51,8 @@
|
|||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
#include "drivers/gyro_sync.h"
|
||||
#include "drivers/usb_io.h"
|
||||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/sdcard.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
@ -523,15 +525,20 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
#ifdef USB_CABLE_DETECTION
|
||||
usbCableDetectInit();
|
||||
#endif
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
transponderInit(masterConfig.transponderData);
|
||||
transponderEnable();
|
||||
transponderStartRepeating();
|
||||
if (feature(FEATURE_TRANSPONDER)) {
|
||||
transponderInit(masterConfig.transponderData);
|
||||
transponderEnable();
|
||||
transponderStartRepeating();
|
||||
systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
#ifdef NAZE
|
||||
|
|
|
@ -369,4 +369,3 @@ void SetSysClock(void)
|
|||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
||||
|
|
|
@ -57,7 +57,7 @@
|
|||
#define USE_BARO_BMP280
|
||||
|
||||
#define MAG
|
||||
//#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
#define USE_MPU9250_MAG // Enables bypass configuration
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883 // External
|
||||
|
||||
|
@ -67,6 +67,13 @@
|
|||
#define BEEPER
|
||||
#define LED0
|
||||
|
||||
#define USB_IO
|
||||
#define USB_CABLE_DETECTION
|
||||
|
||||
#define USB_DETECT_PIN GPIO_Pin_5
|
||||
#define USB_DETECT_GPIO_PORT GPIOB
|
||||
#define USB_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
|
@ -169,21 +176,22 @@
|
|||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
//#define LED_STRIP
|
||||
//#define LED_STRIP_TIMER TIM1
|
||||
//
|
||||
//#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
//#define WS2811_GPIO GPIOA
|
||||
//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
//#define WS2811_GPIO_AF GPIO_AF_6
|
||||
//#define WS2811_PIN GPIO_Pin_8
|
||||
//#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
//#define WS2811_TIMER TIM1
|
||||
//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
//#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
//#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define USE_TRANSPONDER_ON_DMA1_CHANNEL2
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_6
|
||||
#define WS2811_PIN GPIO_Pin_8
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define TRANSPONDER
|
||||
#define TRANSPONDER_GPIO GPIOA
|
||||
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define TRANSPONDER_GPIO_AF GPIO_AF_6
|
||||
|
@ -193,23 +201,22 @@
|
|||
#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2
|
||||
#define TRANSPONDER_IRQ DMA1_Channel2_IRQn
|
||||
#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
|
||||
#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||
|
||||
#define USB_CABLE_DETECTION
|
||||
#define USB_DETECT_PIN GPIO_Pin_5
|
||||
#define USB_DETECT_GPIO_PORT GPIOB
|
||||
#define USB_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
|
||||
#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define TELEMETRY
|
||||
#define TRANSPONDER
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
#define DISPLAY
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#define BUTTONS
|
||||
#define BUTTON_A_PORT GPIOB
|
||||
#define BUTTON_A_PIN Pin_1
|
||||
#define BUTTON_B_PORT GPIOB
|
||||
|
@ -225,7 +232,6 @@
|
|||
#define BINDPLUG_PIN BUTTON_B_PIN
|
||||
|
||||
#define USE_SERIAL_1WIRE
|
||||
#define USE_SERIAL_1WIRE_CLI
|
||||
|
||||
#define S1W_TX_GPIO UART1_GPIO
|
||||
#define S1W_TX_PIN UART1_TX_PIN
|
||||
|
|
Loading…
Reference in New Issue