Removed trailing spaces

This commit is contained in:
Martin Budden 2016-11-11 06:59:25 +00:00
parent 882e26201a
commit 7c8cb3205d
51 changed files with 498 additions and 498 deletions

View File

@ -657,7 +657,7 @@ static void blackboxCreateLogFile()
{
uint32_t remainder = blackboxSDCard.largestLogFileNumber + 1;
char filename[] = LOGFILE_PREFIX "00000." LOGFILE_SUFFIX;
char filename[] = LOGFILE_PREFIX "00000." LOGFILE_SUFFIX;
for (int i = 7; i >= 3; i--) {
filename[i] = (remainder % 10) + '0';

View File

@ -525,7 +525,7 @@ STATIC_UNIT_TESTED void cmsMenuOpen(void)
{
if (!cmsInMenu) {
// New open
pCurrentDisplay = cmsDisplayPortSelectCurrent();
pCurrentDisplay = cmsDisplayPortSelectCurrent();
if (!pCurrentDisplay)
return;
cmsInMenu = true;

View File

@ -17,7 +17,7 @@
//
// CMS things for blackbox and flashfs.
//
//
#include <stdbool.h>
#include <stdint.h>

View File

@ -97,7 +97,7 @@ static void cmsx_Vtx_ConfigWriteback(void)
static long cmsx_Vtx_onEnter(void)
{
cmsx_Vtx_FeatureRead();
cmsx_Vtx_ConfigRead();
cmsx_Vtx_ConfigRead();
return 0;
}

View File

@ -153,7 +153,7 @@ typedef struct master_s {
ppmConfig_t ppmConfig;
pwmConfig_t pwmConfig;
#endif
#ifdef BEEPER
beeperConfig_t beeperConfig;
#endif
@ -207,10 +207,10 @@ typedef struct master_s {
char name[MAX_NAME_LENGTH + 1];
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum
/*
uint8_t chk; // XOR checksum
/*
do not add properties after the CHK
as it is assumed to exist at length-1
as it is assumed to exist at length-1
*/
} master_t;

View File

@ -562,14 +562,14 @@ void createDefaultConfig(master_t *config)
resetTelemetryConfig(&config->telemetryConfig);
#endif
#ifdef BEEPER
#ifdef BEEPER
resetBeeperConfig(&config->beeperConfig);
#endif
#ifdef SONAR
resetSonarConfig(&config->sonarConfig);
#endif
#ifdef SERIALRX_PROVIDER
config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
#else
@ -732,7 +732,7 @@ void createDefaultConfig(master_t *config)
targetConfiguration(config);
#endif
// copy first profile into remaining profile
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));

View File

@ -355,7 +355,7 @@ void mixerLoadMix(int index, motorMixer_t *customMixers)
void mixerConfigureOutput(void)
{
syncMotorOutputWithPidLoop = pwmIsSynced();
motorCount = QUAD_MOTOR_COUNT;
for (uint8_t i = 0; i < motorCount; i++) {

View File

@ -1122,7 +1122,7 @@ void ledStripEnable(void)
static void ledStripDisable(void)
{
setStripColor(&HSV(BLACK));
ws2811UpdateStrip();
}
#endif

View File

@ -365,7 +365,7 @@ static uint8_t Connect(uint8_32_u *pDeviceInfo)
static serialPort_t *port;
static uint8_t ReadByte(void)
static uint8_t ReadByte(void)
{
// need timeout?
while (!serialRxBytesWaiting(port));
@ -392,7 +392,7 @@ static void WriteByteCrc(uint8_t b)
CRCout.word = _crc_xmodem_update(CRCout.word, b);
}
void esc4wayProcess(serialPort_t *mspPort)
void esc4wayProcess(serialPort_t *mspPort)
{
uint8_t ParamBuf[256];
@ -450,16 +450,16 @@ void esc4wayProcess(serialPort_t *mspPort)
} else {
ACK_OUT = ACK_I_INVALID_CRC;
}
TX_LED_ON;
if (ACK_OUT == ACK_OK)
{
// wtf.D_FLASH_ADDR_H=Adress_H;
// wtf.D_FLASH_ADDR_L=Adress_L;
ioMem.D_PTR_I = ParamBuf;
switch(CMD) {
// ******* Interface related stuff *******
case cmd_InterfaceTestAlive:
@ -816,7 +816,7 @@ void esc4wayProcess(serialPort_t *mspPort)
WriteByte(CRCout.bytes[1]);
WriteByte(CRCout.bytes[0]);
serialEndWrite(port);
TX_LED_OFF;
if (isExitScheduled) {
esc4wayRelease();

View File

@ -186,7 +186,7 @@ static void BL_SendBuf(uint8_t *pstring, uint8_t len)
pstring++;
len--;
} while (len > 0);
if (isMcuConnected()) {
suart_putc_(&CRC_16.bytes[0]);
suart_putc_(&CRC_16.bytes[1]);
@ -238,7 +238,7 @@ static uint8_t BL_GetACK(uint32_t Timeout)
return (LastACK);
}
uint8_t BL_SendCMDKeepAlive(void)
uint8_t BL_SendCMDKeepAlive(void)
{
uint8_t sCMD[] = {CMD_KEEP_ALIVE, 0};
BL_SendBuf(sCMD, 2);
@ -306,8 +306,8 @@ uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem)
} else {
return BL_ReadA(CMD_READ_FLASH_SIL, pMem);
}
}
}
uint8_t BL_ReadEEprom(ioMem_t *pMem)
{
return BL_ReadA(CMD_READ_EEPROM, pMem);
@ -829,7 +829,7 @@ uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)
return true;
}
uint8_t BL_SendCMDKeepAlive(void)
uint8_t BL_SendCMDKeepAlive(void)
{
return true;
}
@ -844,7 +844,7 @@ static uint8_t BL_ReadA(uint8_t cmd, ioMem_t *pMem)
{
UNUSED(cmd);
uint16_t address = pMem->D_FLASH_ADDR_H << 8 | pMem->D_FLASH_ADDR_L;
uint16_t bytes = pMem->D_NUM_BYTES;
if (bytes == 0) bytes = 256;
@ -857,7 +857,7 @@ static uint8_t BL_WriteA(uint8_t cmd, ioMem_t *pMem, uint32_t timeout)
UNUSED(cmd);
UNUSED(timeout);
uint16_t address = pMem->D_FLASH_ADDR_H << 8 | pMem->D_FLASH_ADDR_L;
uint16_t bytes = pMem->D_NUM_BYTES;
if (bytes == 0) bytes = 256;
memcpy(&fakeFlash[address], pMem->D_PTR_I, bytes);
@ -869,7 +869,7 @@ uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem)
UNUSED(interface_mode);
return BL_ReadA(0, pMem);
}
uint8_t BL_ReadEEprom(ioMem_t *pMem)
{
return BL_ReadA(0, pMem);

View File

@ -23,7 +23,7 @@ typedef struct {
IO_t io;
} escHardware_t;
extern uint8_t selected_esc;
extern uint8_t selected_esc;
bool isEscHi(uint8_t selEsc);
bool isEscLo(uint8_t selEsc);

View File

@ -527,8 +527,8 @@ static const char * const lookupTableSuperExpoYaw[] = {
};
static const char * const lookupTablePwmProtocol[] = {
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
#ifdef USE_DSHOT
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
#ifdef USE_DSHOT
"DSHOT600", "DSHOT300", "DSHOT150"
#endif
};
@ -3754,15 +3754,15 @@ typedef struct {
const cliResourceValue_t resourceTable[] = {
#ifdef BEEPER
{ OWNER_BEEPER, &masterConfig.beeperConfig.ioTag, 0 },
#endif
#endif
{ OWNER_MOTOR, &masterConfig.motorConfig.ioTags[0], MAX_SUPPORTED_MOTORS },
#ifdef USE_SERVOS
{ OWNER_SERVO, &masterConfig.servoConfig.ioTags[0], MAX_SUPPORTED_SERVOS },
#endif
#endif
#ifndef SKIP_RX_PWM_PPM
{ OWNER_PPMINPUT, &masterConfig.ppmConfig.ioTag, 0 },
{ OWNER_PWMINPUT, &masterConfig.pwmConfig.ioTags[0], PWM_INPUT_PORT_COUNT },
#endif
#endif
#ifdef SONAR
{ OWNER_SONAR_TRIGGER, &masterConfig.sonarConfig.triggerTag, 0 },
{ OWNER_SONAR_ECHO, &masterConfig.sonarConfig.echoTag, 0 },
@ -3856,14 +3856,14 @@ static void cliResource(char *cmdline)
for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) {
const char* owner;
owner = ownerNames[dmaGetOwner(i)];
cliPrintf(DMA_OUTPUT_STRING, i / DMA_MOD_VALUE + 1, (i % DMA_MOD_VALUE) + DMA_MOD_OFFSET);
uint8_t resourceIndex = dmaGetResourceIndex(i);
if (resourceIndex > 0) {
cliPrintf(" %s%d\r\n", owner, resourceIndex);
} else {
cliPrintf(" %s\r\n", owner);
}
}
}
#ifndef CLI_MINIMAL_VERBOSITY
@ -3877,14 +3877,14 @@ static void cliResource(char *cmdline)
int index = 0;
char *pch = NULL;
char *saveptr;
pch = strtok_r(cmdline, " ", &saveptr);
for (resourceIndex = 0; ; resourceIndex++) {
if (resourceIndex >= ARRAYLEN(resourceTable)) {
cliPrint("Invalid resource\r\n");
return;
}
if (strncasecmp(pch, ownerNames[resourceTable[resourceIndex].owner], len) == 0) {
break;
}
@ -3893,7 +3893,7 @@ static void cliResource(char *cmdline)
if (resourceTable[resourceIndex].maxIndex > 0) {
pch = strtok_r(NULL, " ", &saveptr);
index = atoi(pch);
if (index <= 0 || index > resourceTable[resourceIndex].maxIndex) {
cliShowArgumentRangeError("index", 1, resourceTable[resourceIndex].maxIndex);
return;
@ -3902,7 +3902,7 @@ static void cliResource(char *cmdline)
pch = strtok_r(NULL, " ", &saveptr);
ioTag_t *tag = (ioTag_t*)(resourceTable[resourceIndex].ptr + (index == 0 ? 0 : index - 1));
uint8_t pin = 0;
if (strlen(pch) > 0) {
if (strcasecmp(pch, "NONE") == 0) {
@ -3919,7 +3919,7 @@ static void cliResource(char *cmdline)
pch++;
pin = atoi(pch);
if (pin < 16) {
ioRec_t *rec = IO_Rec(IOGetByTag(DEFIO_TAG_MAKE(port, pin)));
ioRec_t *rec = IO_Rec(IOGetByTag(DEFIO_TAG_MAKE(port, pin)));
if (rec) {
*tag = DEFIO_TAG_MAKE(port, pin);
cliPrintf("Resource is set to %c%02d!", port + 'A', pin);
@ -3931,7 +3931,7 @@ static void cliResource(char *cmdline)
}
}
}
cliShowParseError();
}
#endif

View File

@ -280,7 +280,7 @@ void init(void)
if (feature(FEATURE_RX_PPM)) {
ppmRxInit(&masterConfig.ppmConfig, masterConfig.motorConfig.motorPwmProtocol);
} else if (feature(FEATURE_RX_PARALLEL_PWM)) {
pwmRxInit(&masterConfig.pwmConfig);
pwmRxInit(&masterConfig.pwmConfig);
}
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
#endif

View File

@ -123,7 +123,7 @@ uint8_t spektrumFrameStatus(void)
spek_fade_last_sec_count = fade;
spek_fade_last_sec = current_secs;
} else if(spek_fade_last_sec != current_secs) {
// If the difference is > 1, then we missed several seconds worth of frames and
// If the difference is > 1, then we missed several seconds worth of frames and
// should just throw out the fade calc (as it's likely a full signal loss).
if((current_secs - spek_fade_last_sec) == 1) {
if(rssi_channel != 0) {
@ -291,7 +291,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
if (rssi_channel >= rxRuntimeConfig->channelCount) {
rssi_channel = 0;
}
return spektrumPort != NULL;
}
#endif // SERIAL_RX

View File

@ -256,7 +256,7 @@ bool detectGyro(void)
}
#endif
; // fallthrough
case GYRO_ICM20689:
#ifdef USE_GYRO_SPI_ICM20689
if (icm20689SpiGyroDetect(&gyro))

View File

@ -41,7 +41,7 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config)
void targetConfiguration(master_t *config)
{
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5;

View File

@ -41,7 +41,7 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config)
void targetConfiguration(master_t *config)
{
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5;

View File

@ -4,7 +4,7 @@
* @author MCD Application Team
* @version V1.0.0
* @date 22-April-2016
* @brief HAL configuration file.
* @brief HAL configuration file.
******************************************************************************
* @attention
*
@ -33,7 +33,7 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F7xx_HAL_CONF_H
@ -48,43 +48,43 @@
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CEC_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_DCMI_MODULE_ENABLED */
#define HAL_DMA_MODULE_ENABLED
// #define HAL_DMA2D_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
// #define HAL_DMA2D_MODULE_ENABLED
/* #define HAL_ETH_MODULE_ENABLED */
#define HAL_FLASH_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
/* #define HAL_NAND_MODULE_ENABLED */
/* #define HAL_NOR_MODULE_ENABLED */
/* #define HAL_SRAM_MODULE_ENABLED */
/* #define HAL_SDRAM_MODULE_ENABLED */
/* #define HAL_HASH_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_LPTIM_MODULE_ENABLED */
/* #define HAL_LTDC_MODULE_ENABLED */
#define HAL_PWR_MODULE_ENABLED
/* #define HAL_QSPI_MODULE_ENABLED */
#define HAL_RCC_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
/* #define HAL_RNG_MODULE_ENABLED */
//#define HAL_RTC_MODULE_ENABLED
//#define HAL_RTC_MODULE_ENABLED
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
@ -101,9 +101,9 @@
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
@ -114,7 +114,7 @@
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
@ -123,7 +123,7 @@
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#if !defined (LSI_VALUE)
#define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
@ -141,8 +141,8 @@
/**
* @brief External clock source for I2S peripheral
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/
@ -154,7 +154,7 @@
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
*/
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */
#define USE_RTOS 0U
@ -163,7 +163,7 @@
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1 */
@ -180,7 +180,7 @@
#define MAC_ADDR4 0U
#define MAC_ADDR5 0U
/* Definition of the Ethernet driver buffers size and count */
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */
@ -189,7 +189,7 @@
/* Section 2: PHY configuration section */
/* LAN8742A PHY Address*/
#define LAN8742A_PHY_ADDRESS 0x00
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY ((uint32_t)0x00000FFF)
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF)
@ -201,7 +201,7 @@
#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
@ -216,7 +216,7 @@
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */
@ -239,7 +239,7 @@
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
@ -253,7 +253,7 @@
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f7xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f7xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
@ -275,7 +275,7 @@
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32f7xx_hal_cryp.h"
#include "stm32f7xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
@ -297,7 +297,7 @@
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f7xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f7xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
@ -312,7 +312,7 @@
#ifdef HAL_SDRAM_MODULE_ENABLED
#include "stm32f7xx_hal_sdram.h"
#endif /* HAL_SDRAM_MODULE_ENABLED */
#endif /* HAL_SDRAM_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32f7xx_hal_hash.h"
@ -417,14 +417,14 @@
#ifdef HAL_MDIOS_MODULE_ENABLED
#include "stm32f7xx_hal_mdios.h"
#endif /* HAL_MDIOS_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
@ -441,6 +441,6 @@
#endif
#endif /* __STM32F7xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -52,9 +52,9 @@ void detectHardwareRevision(void)
// Check hardware revision
delayMicroseconds(10); // allow configuration to settle
/*
/*
if both PB12 and 13 are tied to GND then it is Rev3A (mini)
if only PB12 is tied to GND then it is a Rev3 (full size)
if only PB12 is tied to GND then it is a Rev3 (full size)
*/
if (!IORead(pin1)) {
if (!IORead(pin2)) {
@ -67,10 +67,10 @@ void detectHardwareRevision(void)
hardwareRevision = BJF4_REV2;
return;
}
/*
/*
enable the UART1 inversion PC9
TODO: once param groups are in place, inverter outputs
can be moved to be simple IO outputs, and merely set them
HI or LO in configuration.
@ -78,7 +78,7 @@ void detectHardwareRevision(void)
IO_t uart1invert = IOGetByTag(IO_TAG(PC9));
IOInit(uart1invert, OWNER_INVERTER, RESOURCE_OUTPUT, 2);
IOConfigGPIO(uart1invert, IOCFG_AF_PP);
IOLo(uart1invert);
IOLo(uart1invert);
}
void updateHardwareRevision(void)
@ -86,8 +86,8 @@ void updateHardwareRevision(void)
if (hardwareRevision != BJF4_REV2) {
return;
}
/*
/*
if flash exists on PB3 then Rev1
*/
if (m25p16_init(IO_TAG(PB3))) {

View File

@ -25,7 +25,7 @@
#include "drivers/timer_def.h"
/*
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT
@ -36,7 +36,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
};
*/
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0 ), // S1_OUT
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0 ), // S2_OUT

View File

@ -28,7 +28,7 @@
// alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(master_t *config)
void targetConfiguration(master_t *config)
{
config->motorConfig.maxthrottle = 1980;
config->batteryConfig.vbatmaxcellvoltage = 45;

View File

@ -4,7 +4,7 @@
* @author MCD Application Team
* @version V1.0.0
* @date 22-April-2016
* @brief HAL configuration file.
* @brief HAL configuration file.
******************************************************************************
* @attention
*
@ -33,7 +33,7 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F7xx_HAL_CONF_H
@ -48,43 +48,43 @@
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CEC_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_DCMI_MODULE_ENABLED */
#define HAL_DMA_MODULE_ENABLED
// #define HAL_DMA2D_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
// #define HAL_DMA2D_MODULE_ENABLED
/* #define HAL_ETH_MODULE_ENABLED */
#define HAL_FLASH_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
/* #define HAL_NAND_MODULE_ENABLED */
/* #define HAL_NOR_MODULE_ENABLED */
/* #define HAL_SRAM_MODULE_ENABLED */
/* #define HAL_SDRAM_MODULE_ENABLED */
/* #define HAL_HASH_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_LPTIM_MODULE_ENABLED */
/* #define HAL_LTDC_MODULE_ENABLED */
#define HAL_PWR_MODULE_ENABLED
/* #define HAL_QSPI_MODULE_ENABLED */
#define HAL_RCC_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
/* #define HAL_RNG_MODULE_ENABLED */
//#define HAL_RTC_MODULE_ENABLED
//#define HAL_RTC_MODULE_ENABLED
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
@ -101,9 +101,9 @@
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
@ -114,7 +114,7 @@
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
@ -123,7 +123,7 @@
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#if !defined (LSI_VALUE)
#define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
@ -141,8 +141,8 @@
/**
* @brief External clock source for I2S peripheral
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/
@ -154,7 +154,7 @@
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
*/
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */
#define USE_RTOS 0U
@ -163,7 +163,7 @@
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1 */
@ -180,7 +180,7 @@
#define MAC_ADDR4 0U
#define MAC_ADDR5 0U
/* Definition of the Ethernet driver buffers size and count */
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */
@ -189,7 +189,7 @@
/* Section 2: PHY configuration section */
/* LAN8742A PHY Address*/
#define LAN8742A_PHY_ADDRESS 0x00
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY ((uint32_t)0x00000FFF)
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF)
@ -201,7 +201,7 @@
#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
@ -216,7 +216,7 @@
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */
@ -239,7 +239,7 @@
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
@ -253,7 +253,7 @@
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f7xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f7xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
@ -275,7 +275,7 @@
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32f7xx_hal_cryp.h"
#include "stm32f7xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
@ -297,7 +297,7 @@
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f7xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f7xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
@ -312,7 +312,7 @@
#ifdef HAL_SDRAM_MODULE_ENABLED
#include "stm32f7xx_hal_sdram.h"
#endif /* HAL_SDRAM_MODULE_ENABLED */
#endif /* HAL_SDRAM_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32f7xx_hal_hash.h"
@ -417,14 +417,14 @@
#ifdef HAL_MDIOS_MODULE_ENABLED
#include "stm32f7xx_hal_mdios.h"
#endif /* HAL_MDIOS_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
@ -441,6 +441,6 @@
#endif
#endif /* __STM32F7xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -37,6 +37,6 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM11 - PB15
#endif
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
};

View File

@ -42,20 +42,20 @@
// alternative defaults settings for MULTIFLITEPICO targets
void targetConfiguration(master_t *config) {
config->mag_hardware = MAG_NONE; // disabled by default
config->batteryConfig.vbatscale = 100;
config->batteryConfig.vbatresdivval = 15;
config->batteryConfig.vbatresdivmultiplier = 4;
config->batteryConfig.vbatmaxcellvoltage = 44;
config->batteryConfig.vbatmincellvoltage = 32;
config->batteryConfig.vbatwarningcellvoltage = 33;
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->rcControlsConfig.yaw_deadband = 2;
config->rcControlsConfig.deadband = 2;
config->modeActivationConditions[0].modeId = BOXANGLE;
config->modeActivationConditions[0].auxChannelIndex = AUX1 - NON_AUX_CHANNEL_COUNT;
config->modeActivationConditions[0].range.startStep = CHANNEL_VALUE_TO_STEP(900);
@ -64,23 +64,23 @@ void targetConfiguration(master_t *config) {
config->modeActivationConditions[1].auxChannelIndex = AUX1 - NON_AUX_CHANNEL_COUNT;
config->modeActivationConditions[1].range.startStep = CHANNEL_VALUE_TO_STEP(1425);
config->modeActivationConditions[1].range.endStep = CHANNEL_VALUE_TO_STEP(1575);
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->motorConfig.motorPwmRate = 17000;
config->gyro_sync_denom = 4;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 70;
config->profile[0].pidProfile.I8[ROLL] = 62;
config->profile[0].pidProfile.D8[ROLL] = 19;
config->profile[0].pidProfile.P8[PITCH] = 70;
config->profile[0].pidProfile.I8[PITCH] = 62;
config->profile[0].pidProfile.D8[PITCH] = 19;
config->profile[0].controlRateProfile[0].rcRate8 = 70;
config->profile[0].pidProfile.I8[PIDLEVEL] = 40;
}

View File

@ -79,7 +79,7 @@ void targetConfiguration(master_t *config)
}
}
#endif
if (hardwareRevision >= NAZE32_REV5) {
// naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
config->beeperConfig.isOD = false;

View File

@ -120,7 +120,7 @@
#define USE_UART1
#define USE_UART2
/* only 2 uarts available on the NAZE, add ifdef here if present on other boards */
/* only 2 uarts available on the NAZE, add ifdef here if present on other boards */
//#define USE_UART3
//#define USE_SOFTSERIAL1
//#define USE_SOFTSERIAL2

View File

@ -26,7 +26,7 @@
// alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(master_t *config)
void targetConfiguration(master_t *config)
{
config->rxConfig.sbus_inversion = 0;
config->rxConfig.rssi_scale = 19;

View File

@ -51,7 +51,7 @@
#endif
// PC0 used as inverter select GPIO
#define INVERTER PC0
#define INVERTER PC0
#define INVERTER_USART USART1
#define MPU6000_CS_PIN PA4

View File

@ -24,19 +24,19 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_PPM | TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM17, IO_TAG(PB9), TIM_Channel_1, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel3, DMA2_CH3_HANDLER },
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER },
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM3, IO_TAG(PA4), TIM_Channel_2, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD12), TIM_Channel_1, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD13), TIM_Channel_2, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD14), TIM_Channel_3, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD15), TIM_Channel_4, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, 0, GPIO_AF_1, NULL, 0 }
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_PPM | TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM17, IO_TAG(PB9), TIM_Channel_1, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel3, DMA2_CH3_HANDLER },
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER },
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM3, IO_TAG(PA4), TIM_Channel_2, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD12), TIM_Channel_1, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD13), TIM_Channel_2, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD14), TIM_Channel_3, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD15), TIM_Channel_4, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, 0, GPIO_AF_1, NULL, 0 }
};

View File

@ -169,7 +169,7 @@
#define RSSI_ADC_PIN PC2
#define EXTERNAL1_ADC_PIN PC3
#define USE_DSHOT
#define USE_DSHOT
#define LED_STRIP

View File

@ -93,8 +93,8 @@
/** @addtogroup stm32f30x_system
* @{
*/
*/
/** @addtogroup STM32F30x_System_Private_Includes
* @{
*/
@ -116,7 +116,7 @@ uint32_t hse_value = HSE_VALUE;
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
This value must be a multiple of 0x200. */
/**
* @}
*/
@ -184,19 +184,19 @@ void SystemInit(void)
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
/* Disable all interrupts */
RCC->CIR = 0x00000000;
/* Configure the System clock source, PLL Multiplier and Divider factors,
AHB/APBx prescalers and Flash settings ----------------------------------*/
//SetSysClock(); // called from main()
#ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
#endif
#endif
}
/**
@ -204,7 +204,7 @@ void SystemInit(void)
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
@ -222,7 +222,7 @@ void SystemInit(void)
*
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
@ -241,7 +241,7 @@ void SystemCoreClockUpdate (void)
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case 0x00: /* HSI used as system clock */
@ -255,7 +255,7 @@ void SystemCoreClockUpdate (void)
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2;
if (pllsource == 0x00)
{
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
@ -266,7 +266,7 @@ void SystemCoreClockUpdate (void)
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
}
}
break;
default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
@ -276,7 +276,7 @@ void SystemCoreClockUpdate (void)
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
SystemCoreClock >>= tmp;
}
/**
@ -322,7 +322,7 @@ void SetSysClock(void)
/* HCLK = SYSCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;

View File

@ -4,7 +4,7 @@
* @author MCD Application Team
* @version V1.1.1
* @date 28-March-2014
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
******************************************************************************
* @attention
*
@ -31,8 +31,8 @@
/** @addtogroup stm32f30x_system
* @{
*/
*/
/**
* @brief Define to prevent recursive inclusion
*/
@ -52,7 +52,7 @@ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Cloc
/** @addtogroup STM32F30x_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
@ -69,8 +69,8 @@ extern void SystemCoreClockUpdate(void);
/**
* @}
*/
/**
* @}
*/
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -293,8 +293,8 @@
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
@ -316,7 +316,7 @@
#include "stm32f4xx.h"
#include "system_stm32f4xx.h"
uint32_t hse_value = HSE_VALUE;
/**
@ -567,10 +567,10 @@ void SystemCoreClockUpdate(void)
case 0x08: /* PLL P used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
SYSCLK = PLL_VCO / PLL_P
*/
*/
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
if (pllsource != 0)
{
/* HSE used as PLL clock source */
@ -619,10 +619,10 @@ void SystemCoreClockUpdate(void)
}
/**
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
* AHB/APBx prescalers and Flash settings
* @Note This function should be called only once the RCC clock configuration
* is reset to the default reset state (done in SystemInit() function).
* @Note This function should be called only once the RCC clock configuration
* is reset to the default reset state (done in SystemInit() function).
* @param None
* @retval None
*/
@ -632,10 +632,10 @@ void SetSysClock(void)
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
@ -664,7 +664,7 @@ void SetSysClock(void)
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
/* PCLK2 = HCLK / 2*/
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
/* PCLK1 = HCLK / 4*/
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
@ -702,7 +702,7 @@ void SetSysClock(void)
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
/* Enable the Over-drive to extend the clock frequency to 180 Mhz */
PWR->CR |= PWR_CR_ODEN;

View File

@ -4,8 +4,8 @@
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
@ -22,7 +22,7 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
******************************************************************************
*/
#ifndef __SYSTEM_STM32F4XX_H

View File

@ -192,7 +192,7 @@
{
while(1) { ; }
}
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
|RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_USART6
|RCC_PERIPHCLK_UART4|RCC_PERIPHCLK_UART5
@ -216,7 +216,7 @@
// Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz
__HAL_RCC_TIMCLKPRESCALER(RCC_TIMPRES_ACTIVATED);
SystemCoreClockUpdate();
}
@ -266,7 +266,7 @@ void SystemInit(void)
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
#endif
/* Enable I-Cache */
//SCB_EnableICache();
@ -275,7 +275,7 @@ void SystemInit(void)
/* Configure the system clock to 216 MHz */
SystemClock_Config();
//if(SystemCoreClock != 260000000)
{
//while(1)
@ -283,7 +283,7 @@ void SystemInit(void)
// There is a mismatch between the configured clock and the expected clock in portable.h
}
}
}

View File

@ -4,8 +4,8 @@
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 STMicroelectronics</center></h2>
@ -16,21 +16,21 @@
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
******************************************************************************
*/
#ifndef __SYSTEM_STM32F7XX_H
#define __SYSTEM_STM32F7XX_H
#ifdef __cplusplus
extern "C" {
#endif
#endif
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern void SystemInit(void);

View File

@ -158,7 +158,7 @@ void configureMAVLinkTelemetryPort(void)
// default rate for minimOSD
baudRateIndex = BAUD_57600;
}
mavlinkPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
if (!mavlinkPort) {
@ -185,9 +185,9 @@ void checkMAVLinkTelemetryState(void)
void mavlinkSendSystemStatus(void)
{
uint16_t msgLength;
uint32_t onboardControlAndSensors = 35843;
/*
onboard_control_sensors_present Bitmask
fedcba9876543210
@ -197,16 +197,16 @@ void mavlinkSendSystemStatus(void)
0100000000100000 With GPS = 16416
0000001111111111
*/
if (sensors(SENSOR_MAG)) onboardControlAndSensors |= 4100;
if (sensors(SENSOR_BARO)) onboardControlAndSensors |= 8200;
if (sensors(SENSOR_GPS)) onboardControlAndSensors |= 16416;
mavlink_msg_sys_status_pack(0, 200, &mavMsg,
// onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
//Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure,
// 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position,
// 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization,
// onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
//Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure,
// 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position,
// 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization,
// 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
onboardControlAndSensors,
// onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled
@ -272,7 +272,7 @@ void mavlinkSendPosition(void)
{
uint16_t msgLength;
uint8_t gpsFixType = 0;
if (!sensors(SENSOR_GPS))
return;
@ -388,7 +388,7 @@ void mavlinkSendHUDAndHeartbeat(void)
mavGroundSpeed = GPS_speed / 100.0f;
}
#endif
// select best source for altitude
#if defined(BARO) || defined(SONAR)
if (sensors(SENSOR_SONAR) || sensors(SENSOR_BARO)) {
@ -407,7 +407,7 @@ void mavlinkSendHUDAndHeartbeat(void)
mavAltitude = GPS_altitude;
}
#endif
mavlink_msg_vfr_hud_pack(0, 200, &mavMsg,
// airspeed Current airspeed in m/s
mavAirSpeed,
@ -424,11 +424,11 @@ void mavlinkSendHUDAndHeartbeat(void)
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);
mavlinkSerialWrite(mavBuffer, msgLength);
uint8_t mavModes = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
if (ARMING_FLAG(ARMED))
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
uint8_t mavSystemType;
switch(masterConfig.mixerMode)
{
@ -463,11 +463,11 @@ void mavlinkSendHUDAndHeartbeat(void)
default:
mavSystemType = MAV_TYPE_GENERIC;
break;
}
}
// Custom mode for compatibility with APM OSDs
uint8_t mavCustomMode = 1; // Acro by default
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
mavCustomMode = 0; //Stabilize
mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
@ -478,7 +478,7 @@ void mavlinkSendHUDAndHeartbeat(void)
mavCustomMode = 6; //Return to Launch
if (FLIGHT_MODE(GPS_HOLD_MODE))
mavCustomMode = 16; //Position Hold (Earlier called Hybrid)
uint8_t mavSystemState = 0;
if (ARMING_FLAG(ARMED)) {
if (failsafeIsActive()) {
@ -491,7 +491,7 @@ void mavlinkSendHUDAndHeartbeat(void)
else {
mavSystemState = MAV_STATE_STANDBY;
}
mavlink_msg_heartbeat_pack(0, 200, &mavMsg,
// type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
mavSystemType,
@ -513,7 +513,7 @@ void processMAVLinkTelemetry(void)
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS)) {
mavlinkSendSystemStatus();
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_RC_CHANNELS)) {
mavlinkSendRCChannelsAndRSSI();
}
@ -527,7 +527,7 @@ void processMAVLinkTelemetry(void)
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA1)) {
mavlinkSendAttitude();
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2)) {
mavlinkSendHUDAndHeartbeat();
}
@ -542,7 +542,7 @@ void handleMAVLinkTelemetry(void)
if (!mavlinkPort) {
return;
}
uint32_t now = micros();
if ((now - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) {
processMAVLinkTelemetry();

View File

@ -385,7 +385,7 @@ static void processMspPacket(mspPacket_t* packet)
if (mspFcProcessCommand(packet, &smartPortMspReply, NULL) == MSP_RESULT_ERROR) {
sbufWriteU8(&smartPortMspReply.buf, SMARTPORT_MSP_ERROR);
}
// change streambuf direction
sbufSwitchToReader(&smartPortMspReply.buf, smartPortMspTxBuffer);
smartPortMspReplyPending = true;
@ -420,7 +420,7 @@ bool smartPortSendMspReply()
uint8_t packet[SMARTPORT_PAYLOAD_SIZE];
uint8_t* p = packet;
uint8_t* end = p + SMARTPORT_PAYLOAD_SIZE;
sbuf_t* txBuf = &smartPortMspReply.buf;
// detect first reply packet
@ -496,11 +496,11 @@ void handleSmartPortMspFrame(smartPortFrame_t* sp_frame)
static uint8_t lastSeq = 0;
static uint8_t checksum = 0;
static mspPacket_t cmd;
// re-assemble MSP frame & forward to MSP port when complete
uint8_t* p = ((uint8_t*)sp_frame) + SMARTPORT_PAYLOAD_OFFSET;
uint8_t* end = p + SMARTPORT_PAYLOAD_SIZE;
uint8_t head = *p++;
uint8_t seq = head & SMARTPORT_MSP_SEQ_MASK;
uint8_t version = (head & SMARTPORT_MSP_VER_MASK) >> SMARTPORT_MSP_VER_SHIFT;
@ -594,7 +594,7 @@ void handleSmartPortTelemetry(void)
handleSmartPortMspFrame(&smartPortRxBuffer);
}
}
while (smartPortHasRequest) {
// Ensure we won't get stuck in the loop if there happens to be nothing available to send in a timely manner - dump the slot if we loop in there for too long.
if ((millis() - smartPortLastServiceTime) > SMARTPORT_SERVICE_TIMEOUT_MS) {
@ -607,7 +607,7 @@ void handleSmartPortTelemetry(void)
smartPortHasRequest = 0;
return;
}
// we can send back any data we want, our table keeps track of the order and frequency of each data type we send
uint16_t id = frSkyDataIdTable[smartPortIdCnt];
if (id == 0) { // end of table reached, loop back
@ -627,7 +627,7 @@ void handleSmartPortTelemetry(void)
if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) {
//convert to knots: 1cm/s = 0.0194384449 knots
//Speed should be sent in knots/1000 (GPS speed is in cm/s)
uint32_t tmpui = GPS_speed * 1944 / 100;
uint32_t tmpui = GPS_speed * 1944 / 100;
smartPortSendPackage(id, tmpui);
smartPortHasRequest = 0;
}

View File

@ -30,7 +30,7 @@
#include "usb_desc.h"
/* USB Standard Device Descriptor */
const uint8_t Virtual_Com_Port_DeviceDescriptor[] = {
const uint8_t Virtual_Com_Port_DeviceDescriptor[] = {
0x12, /* bLength */
USB_DEVICE_DESCRIPTOR_TYPE, /* bDescriptorType */
0x00, 0x02, /* bcdUSB = 2.00 */

View File

@ -8,37 +8,37 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
@ -91,7 +91,7 @@ static int8_t CDC_Itf_Receive(uint8_t* pbuf, uint32_t *Len);
static void TIM_Config(void);
static void Error_Handler(void);
USBD_CDC_ItfTypeDef USBD_CDC_fops =
USBD_CDC_ItfTypeDef USBD_CDC_fops =
{
CDC_Itf_Init,
CDC_Itf_DeInit,
@ -117,7 +117,7 @@ static int8_t CDC_Itf_Init(void)
{
/*##-3- Configure the TIM Base generation #################################*/
TIM_Config();
/*##-4- Start the TIM Base generation in interrupt mode ####################*/
/* Start Channel1 */
if(HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK)
@ -125,11 +125,11 @@ static int8_t CDC_Itf_Init(void)
/* Starting Error */
Error_Handler();
}
/*##-5- Set Application Buffers ############################################*/
USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0);
USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer);
return (USBD_OK);
}
@ -148,13 +148,13 @@ static int8_t CDC_Itf_DeInit(void)
/**
* @brief CDC_Itf_Control
* Manage the CDC class requests
* @param Cmd: Command code
* @param Cmd: Command code
* @param Buf: Buffer containing command data (request parameters)
* @param Len: Number of data to be sent (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
*/
static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
{
{
UNUSED(length);
switch (cmd)
{
@ -184,7 +184,7 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
LineCoding.format = pbuf[4];
LineCoding.paritytype = pbuf[5];
LineCoding.datatype = pbuf[6];
break;
case CDC_GET_LINE_CODING:
@ -194,7 +194,7 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
pbuf[3] = (uint8_t)(LineCoding.bitrate >> 24);
pbuf[4] = LineCoding.format;
pbuf[5] = LineCoding.paritytype;
pbuf[6] = LineCoding.datatype;
pbuf[6] = LineCoding.datatype;
break;
case CDC_SET_CONTROL_LINE_STATE:
@ -203,12 +203,12 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
case CDC_SEND_BREAK:
/* Add your code here */
break;
break;
default:
break;
}
return (USBD_OK);
}
@ -220,25 +220,25 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
if(htim->Instance != TIMusb) return;
uint32_t buffptr;
uint32_t buffsize;
if(UserTxBufPtrOut != UserTxBufPtrIn)
{
if(UserTxBufPtrOut > UserTxBufPtrIn) /* Roll-back */
{
buffsize = APP_RX_DATA_SIZE - UserTxBufPtrOut;
}
else
else
{
buffsize = UserTxBufPtrIn - UserTxBufPtrOut;
}
buffptr = UserTxBufPtrOut;
USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[buffptr], buffsize);
if(USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK)
{
UserTxBufPtrOut += buffsize;
@ -252,7 +252,7 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
/**
* @brief CDC_Itf_DataRx
* Data received over USB OUT endpoint are sent over CDC interface
* Data received over USB OUT endpoint are sent over CDC interface
* through this function.
* @param Buf: Buffer of data to be transmitted
* @param Len: Number of data received (in bytes)
@ -271,10 +271,10 @@ static int8_t CDC_Itf_Receive(uint8_t* Buf, uint32_t *Len)
* @retval None
*/
static void TIM_Config(void)
{
{
/* Set TIMusb instance */
TimHandle.Instance = TIMusb;
/* Initialize TIMx peripheral as follow:
+ Period = 10000 - 1
+ Prescaler = ((SystemCoreClock/2)/10000) - 1
@ -290,14 +290,14 @@ static void TIM_Config(void)
/* Initialization Error */
Error_Handler();
}
/*##-6- Enable TIM peripherals Clock #######################################*/
TIMx_CLK_ENABLE();
/*##-7- Configure the NVIC for TIMx ########################################*/
/* Set Interrupt Group Priority */
/* Set Interrupt Group Priority */
HAL_NVIC_SetPriority(TIMx_IRQn, 6, 0);
/* Enable the TIMx global Interrupt */
HAL_NVIC_EnableIRQ(TIMx_IRQn);
}
@ -324,10 +324,10 @@ uint8_t vcpRead()
rxBuffPtr++;
rxAvailable--;
}
if(rxAvailable < 1)
USBD_CDC_ReceivePacket(&USBD_Device);
return ch;
}
@ -388,6 +388,6 @@ uint32_t vcpBaudrate()
uint8_t vcpIsConnected()
{
return ((USBD_Device.dev_state == USBD_STATE_CONFIGURED)
return ((USBD_Device.dev_state == USBD_STATE_CONFIGURED)
|| (USBD_Device.dev_state == USBD_STATE_SUSPENDED));
}

View File

@ -8,37 +8,37 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*

View File

@ -8,37 +8,37 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
@ -61,7 +61,7 @@ PCD_HandleTypeDef hpcd;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
PCD BSP Routines
*******************************************************************************/
@ -83,27 +83,27 @@ void OTG_HS_IRQHandler(void)
void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
{
GPIO_InitTypeDef GPIO_InitStruct;
if(hpcd->Instance == USB_OTG_FS)
{
/* Configure USB FS GPIOs */
__HAL_RCC_GPIOA_CLK_ENABLE();
/* Configure DM DP Pins */
GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12);
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
if(hpcd->Init.vbus_sensing_enable == 1)
{
/* Configure VBUS Pin */
GPIO_InitStruct.Pin = GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
}
#if USE_USB_ID
/* Configure ID pin */
@ -115,19 +115,19 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
#endif
/* Enable USB FS Clock */
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
/* Set USBFS Interrupt priority */
HAL_NVIC_SetPriority(OTG_FS_IRQn, 6, 0);
/* Enable USBFS Interrupt */
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
HAL_NVIC_EnableIRQ(OTG_FS_IRQn);
}
else if(hpcd->Instance == USB_OTG_HS)
{
#ifdef USE_USB_HS_IN_FS
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO for HS on FS mode*/
GPIO_InitStruct.Pin = GPIO_PIN_12 | GPIO_PIN_14 |GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
@ -135,7 +135,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF12_OTG_HS_FS;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
if(hpcd->Init.vbus_sensing_enable == 1)
{
/* Configure VBUS Pin */
@ -151,7 +151,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOH_CLK_ENABLE();
__HAL_RCC_GPIOI_CLK_ENABLE();
/* CLK */
GPIO_InitStruct.Pin = GPIO_PIN_5;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
@ -159,7 +159,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* D0 */
GPIO_InitStruct.Pin = GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
@ -167,7 +167,7 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* D1 D2 D3 D4 D5 D6 D7 */
GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_5 |\
GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13;
@ -175,21 +175,21 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* STP */
GPIO_InitStruct.Pin = GPIO_PIN_0;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/* NXT */
GPIO_InitStruct.Pin = GPIO_PIN_4;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
HAL_GPIO_Init(GPIOH, &GPIO_InitStruct);
/* DIR */
GPIO_InitStruct.Pin = GPIO_PIN_11;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
@ -197,16 +197,16 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
HAL_GPIO_Init(GPIOI, &GPIO_InitStruct);
__HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE();
#endif
#endif
/* Enable USB HS Clocks */
__HAL_RCC_USB_OTG_HS_CLK_ENABLE();
/* Set USBHS Interrupt to the lowest priority */
HAL_NVIC_SetPriority(OTG_HS_IRQn, 6, 0);
/* Enable USBHS Interrupt */
HAL_NVIC_EnableIRQ(OTG_HS_IRQn);
}
}
}
/**
@ -217,17 +217,17 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd)
void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd)
{
if(hpcd->Instance == USB_OTG_FS)
{
{
/* Disable USB FS Clock */
__HAL_RCC_USB_OTG_FS_CLK_DISABLE();
__HAL_RCC_SYSCFG_CLK_DISABLE();
}
else if(hpcd->Instance == USB_OTG_HS)
{
{
/* Disable USB HS Clocks */
__HAL_RCC_USB_OTG_HS_CLK_DISABLE();
__HAL_RCC_SYSCFG_CLK_DISABLE();
}
}
}
/*******************************************************************************
@ -282,28 +282,28 @@ void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd)
* @retval None
*/
void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd)
{
{
USBD_SpeedTypeDef speed = USBD_SPEED_FULL;
/* Set USB Current Speed */
switch(hpcd->Init.speed)
{
case PCD_SPEED_HIGH:
speed = USBD_SPEED_HIGH;
break;
case PCD_SPEED_FULL:
speed = USBD_SPEED_FULL;
break;
break;
default:
speed = USBD_SPEED_FULL;
break;
}
/* Reset Device */
USBD_LL_Reset(hpcd->pData);
USBD_LL_SetSpeed(hpcd->pData, speed);
}
@ -329,7 +329,7 @@ void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd)
/**
* @brief ISOOUTIncomplete callback.
* @param hpcd: PCD handle
* @param hpcd: PCD handle
* @param epnum: Endpoint Number
* @retval None
*/
@ -340,7 +340,7 @@ void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum)
/**
* @brief ISOINIncomplete callback.
* @param hpcd: PCD handle
* @param hpcd: PCD handle
* @param epnum: Endpoint Number
* @retval None
*/
@ -394,26 +394,26 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev)
hpcd.Init.speed = PCD_SPEED_FULL;
hpcd.Init.vbus_sensing_enable = 0;
hpcd.Init.lpm_enable = 0;
/* Link The driver to the stack */
hpcd.pData = pdev;
pdev->pData = &hpcd;
/* Initialize LL Driver */
HAL_PCD_Init(&hpcd);
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x40);
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x80);
#endif
#ifdef USE_USB_HS
/* Set LL Driver parameters */
hpcd.Instance = USB_OTG_HS;
hpcd.Init.dev_endpoints = 6;
hpcd.Init.use_dedicated_ep1 = 0;
hpcd.Init.ep0_mps = 0x40;
/* Be aware that enabling DMA mode will result in data being sent only by
multiple of 4 packet sizes. This is due to the fact that USB DMA does
not allow sending data from non word-aligned addresses.
@ -422,28 +422,28 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev)
hpcd.Init.dma_enable = 0;
hpcd.Init.low_power_enable = 0;
hpcd.Init.lpm_enable = 0;
#ifdef USE_USB_HS_IN_FS
hpcd.Init.phy_itface = PCD_PHY_EMBEDDED;
#else
hpcd.Init.phy_itface = PCD_PHY_ULPI;
#endif
hpcd.Init.phy_itface = PCD_PHY_EMBEDDED;
#else
hpcd.Init.phy_itface = PCD_PHY_ULPI;
#endif
hpcd.Init.Sof_enable = 0;
hpcd.Init.speed = PCD_SPEED_HIGH;
hpcd.Init.vbus_sensing_enable = 1;
/* Link The driver to the stack */
hpcd.pData = pdev;
pdev->pData = &hpcd;
/* Initialize LL Driver */
HAL_PCD_Init(&hpcd);
HAL_PCDEx_SetRxFiFo(&hpcd, 0x200);
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x80);
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x174);
#endif
#endif
return USBD_OK;
}
@ -459,7 +459,7 @@ USBD_StatusTypeDef USBD_LL_DeInit(USBD_HandleTypeDef *pdev)
}
/**
* @brief Starts the Low Level portion of the Device driver.
* @brief Starts the Low Level portion of the Device driver.
* @param pdev: Device handle
* @retval USBD Status
*/
@ -497,7 +497,7 @@ USBD_StatusTypeDef USBD_LL_OpenEP(USBD_HandleTypeDef *pdev,
ep_addr,
ep_mps,
ep_type);
return USBD_OK;
}
@ -546,7 +546,7 @@ USBD_StatusTypeDef USBD_LL_StallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
{
HAL_PCD_EP_ClrStall(pdev->pData, ep_addr);
return USBD_OK;
return USBD_OK;
}
/**
@ -558,7 +558,7 @@ USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_add
uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
{
PCD_HandleTypeDef *hpcd = pdev->pData;
if((ep_addr & 0x80) == 0x80)
{
return hpcd->IN_ep[ep_addr & 0x7F].is_stall;
@ -578,7 +578,7 @@ uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef *pdev, uint8_t dev_addr)
{
HAL_PCD_SetAddress(pdev->pData, dev_addr);
return USBD_OK;
return USBD_OK;
}
/**
@ -586,10 +586,10 @@ USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef *pdev, uint8_t dev_a
* @param pdev: Device handle
* @param ep_addr: Endpoint Number
* @param pbuf: Pointer to data to be sent
* @param size: Data size
* @param size: Data size
* @retval USBD Status
*/
USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev,
USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev,
uint8_t ep_addr,
uint8_t *pbuf,
uint16_t size)
@ -606,7 +606,7 @@ USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev,
* @param size: Data size
* @retval USBD Status
*/
USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev,
USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev,
uint8_t ep_addr,
uint8_t *pbuf,
uint16_t size)

View File

@ -8,37 +8,37 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
@ -61,41 +61,41 @@
#define USBD_MAX_NUM_INTERFACES 1
#define USBD_MAX_NUM_CONFIGURATION 1
#define USBD_MAX_STR_DESC_SIZ 0x100
#define USBD_SUPPORT_USER_STRING 0
#define USBD_SUPPORT_USER_STRING 0
#define USBD_SELF_POWERED 1
#define USBD_DEBUG_LEVEL 0
#define USE_USB_FS
/* Exported macro ------------------------------------------------------------*/
/* Memory management macros */
/* Memory management macros */
#define USBD_malloc malloc
#define USBD_free free
#define USBD_memset memset
#define USBD_memcpy memcpy
/* DEBUG macros */
/* DEBUG macros */
#if (USBD_DEBUG_LEVEL > 0)
#define USBD_UsrLog(...) printf(__VA_ARGS__);\
printf("\n");
#else
#define USBD_UsrLog(...)
#endif
#define USBD_UsrLog(...)
#endif
#if (USBD_DEBUG_LEVEL > 1)
#define USBD_ErrLog(...) printf("ERROR: ") ;\
printf(__VA_ARGS__);\
printf("\n");
#else
#define USBD_ErrLog(...)
#endif
#if (USBD_DEBUG_LEVEL > 2)
#define USBD_ErrLog(...)
#endif
#if (USBD_DEBUG_LEVEL > 2)
#define USBD_DbgLog(...) printf("DEBUG : ") ;\
printf(__VA_ARGS__);\
printf("\n");
#else
#define USBD_DbgLog(...)
#define USBD_DbgLog(...)
#endif
/* Exported functions ------------------------------------------------------- */

View File

@ -8,37 +8,37 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
@ -73,23 +73,23 @@ uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t *USBD_VCP_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
uint8_t *USBD_VCP_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
/* Private variables ---------------------------------------------------------*/
USBD_DescriptorsTypeDef VCP_Desc = {
USBD_VCP_DeviceDescriptor,
USBD_VCP_LangIDStrDescriptor,
USBD_VCP_LangIDStrDescriptor,
USBD_VCP_ManufacturerStrDescriptor,
USBD_VCP_ProductStrDescriptor,
USBD_VCP_SerialStrDescriptor,
USBD_VCP_ConfigStrDescriptor,
USBD_VCP_InterfaceStrDescriptor,
USBD_VCP_InterfaceStrDescriptor,
};
/* USB Standard Device Descriptor */
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#pragma data_alignment=4
#endif
__ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
0x12, /* bLength */
@ -114,23 +114,23 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
/* USB Standard Device Descriptor */
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#pragma data_alignment=4
#endif
__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END = {
USB_LEN_LANGID_STR_DESC,
USB_DESC_TYPE_STRING,
USB_LEN_LANGID_STR_DESC,
USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
};
uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] =
{
USB_SIZ_STRING_SERIAL,
USB_DESC_TYPE_STRING,
USB_SIZ_STRING_SERIAL,
USB_DESC_TYPE_STRING,
};
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#pragma data_alignment=4
#endif
__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
@ -139,7 +139,7 @@ static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len);
static void Get_SerialNum(void);
/**
* @brief Returns the device descriptor.
* @brief Returns the device descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -152,7 +152,7 @@ uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
}
/**
* @brief Returns the LangID string descriptor.
* @brief Returns the LangID string descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -160,12 +160,12 @@ uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
{
(void)speed;
*length = sizeof(USBD_LangIDDesc);
*length = sizeof(USBD_LangIDDesc);
return (uint8_t*)USBD_LangIDDesc;
}
/**
* @brief Returns the product string descriptor.
* @brief Returns the product string descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -173,18 +173,18 @@ uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
{
if(speed == USBD_SPEED_HIGH)
{
{
USBD_GetString((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
}
else
{
USBD_GetString((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
USBD_GetString((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
}
/**
* @brief Returns the manufacturer string descriptor.
* @brief Returns the manufacturer string descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -197,7 +197,7 @@ uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *l
}
/**
* @brief Returns the serial number string descriptor.
* @brief Returns the serial number string descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -206,15 +206,15 @@ uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
{
(void)speed;
*length = USB_SIZ_STRING_SERIAL;
/* Update the serial number string descriptor with the data from the unique ID*/
Get_SerialNum();
return (uint8_t*)USBD_StringSerial;
}
/**
* @brief Returns the configuration string descriptor.
* @brief Returns the configuration string descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -222,18 +222,18 @@ uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
{
if(speed == USBD_SPEED_HIGH)
{
{
USBD_GetString((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
}
else
{
USBD_GetString((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
USBD_GetString((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
return USBD_StrDesc;
}
/**
* @brief Returns the interface string descriptor.
* @brief Returns the interface string descriptor.
* @param speed: Current device speed
* @param length: Pointer to data length variable
* @retval Pointer to descriptor buffer
@ -248,24 +248,24 @@ uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *leng
{
USBD_GetString((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
}
return USBD_StrDesc;
return USBD_StrDesc;
}
/**
* @brief Create the serial number string descriptor
* @param None
* @brief Create the serial number string descriptor
* @param None
* @retval None
*/
static void Get_SerialNum(void)
{
uint32_t deviceserial0, deviceserial1, deviceserial2;
deviceserial0 = *(uint32_t*)DEVICE_ID1;
deviceserial1 = *(uint32_t*)DEVICE_ID2;
deviceserial2 = *(uint32_t*)DEVICE_ID3;
deviceserial0 += deviceserial2;
if (deviceserial0 != 0)
{
IntToUnicode (deviceserial0, &USBD_StringSerial[2] ,8);
@ -274,16 +274,16 @@ static void Get_SerialNum(void)
}
/**
* @brief Convert Hex 32Bits value into char
* @brief Convert Hex 32Bits value into char
* @param value: value to convert
* @param pbuf: pointer to the buffer
* @param pbuf: pointer to the buffer
* @param len: buffer length
* @retval None
*/
static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
{
uint8_t idx = 0;
for( idx = 0; idx < len; idx ++)
{
if( ((value >> 28)) < 0xA )
@ -292,11 +292,11 @@ static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
}
else
{
pbuf[2* idx] = (value >> 28) + 'A' - 10;
pbuf[2* idx] = (value >> 28) + 'A' - 10;
}
value = value << 4;
pbuf[ 2* idx + 1] = 0;
}
}

View File

@ -8,37 +8,37 @@
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
@ -64,5 +64,5 @@
extern USBD_DescriptorsTypeDef VCP_Desc;
#endif /* __USBD_DESC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -30,7 +30,7 @@
/** @addtogroup USB_OTG_DRIVER
* @{
*/
/** @defgroup USB_CONF
* @brief USB low level driver configuration file
* @{
@ -76,7 +76,7 @@
/*******************************************************************************
* FIFO Size Configuration in Device mode
*
*
* (i) Receive data FIFO size = RAM for setup packets +
* OUT endpoint control information +
* data OUT packets + miscellaneous
@ -215,16 +215,16 @@
#else
#define __ALIGN_END
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#elif defined (__TASKING__) /* TASKING Compiler */
#define __ALIGN_BEGIN __align(4)
#endif /* __CC_ARM */
#endif /* __CC_ARM */
#endif /* __GNUC__ */
#else
#define __ALIGN_BEGIN
#define __ALIGN_END
#define __ALIGN_END
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* __packed keyword used to decrease the data type alignment to 1-byte */

View File

@ -37,18 +37,18 @@ __IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
/* These are external variables imported from CDC core to be used for IN transfer management. */
/* This is the buffer for data received from the MCU to APP (i.e. MCU TX, APP RX) */
extern uint8_t APP_Rx_Buffer[];
extern uint8_t APP_Rx_Buffer[];
extern uint32_t APP_Rx_ptr_out;
/* Increment this buffer position or roll it back to
start address when writing received data
in the buffer APP_Rx_Buffer. */
extern uint32_t APP_Rx_ptr_in;
extern uint32_t APP_Rx_ptr_in;
/*
APP TX is the circular buffer for data that is transmitted from the APP (host)
to the USB device (flight controller).
*/
static uint8_t APP_Tx_Buffer[APP_TX_DATA_SIZE];
static uint8_t APP_Tx_Buffer[APP_TX_DATA_SIZE];
static uint32_t APP_Tx_ptr_out = 0;
static uint32_t APP_Tx_ptr_in = 0;
@ -110,7 +110,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
assert_param(Len>=sizeof(LINE_CODING));
switch (Cmd) {
/* Not needed for this driver, AT modem commands */
/* Not needed for this driver, AT modem commands */
case SEND_ENCAPSULATED_COMMAND:
case GET_ENCAPSULATED_RESPONSE:
break;
@ -164,9 +164,9 @@ uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint8_t sendLength)
uint32_t CDC_Send_FreeBytes(void)
{
/*
return the bytes free in the circular buffer
/*
return the bytes free in the circular buffer
functionally equivalent to:
(APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in)
but without the impact of the condition check.
@ -176,24 +176,24 @@ uint32_t CDC_Send_FreeBytes(void)
/**
* @brief VCP_DataTx
* CDC data to be sent to the Host (app) over USB
* CDC data to be sent to the Host (app) over USB
* @param Buf: Buffer of data to be sent
* @param Len: Number of data to be sent (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else VCP_FAIL
*/
static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len)
{
/*
/*
make sure that any paragraph end frame is not in play
could just check for: USB_CDC_ZLP, but better to be safe
and wait for any existing transmission to complete.
*/
while (USB_Tx_State != 0);
for (uint32_t i = 0; i < Len; i++) {
APP_Rx_Buffer[APP_Rx_ptr_in] = Buf[i];
APP_Rx_ptr_in = (APP_Rx_ptr_in + 1) % APP_RX_DATA_SIZE;
while (CDC_Send_FreeBytes() == 0) {
delay(1);
}

View File

@ -54,7 +54,7 @@
#define CDC_CMD_PACKET_SZE 8 /* Control Endpoint Packet size */
#define CDC_IN_FRAME_INTERVAL 15 /* Number of frames between IN transfers */
#define APP_RX_DATA_SIZE 2048 /* Total size of IN (outbound from FC) buffer:
#define APP_RX_DATA_SIZE 2048 /* Total size of IN (outbound from FC) buffer:
APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL */
#define APP_TX_DATA_SIZE 2048 /* total size of the OUT (inbound to FC) buffer */
#endif /* USE_USB_OTG_HS */

View File

@ -108,12 +108,12 @@ USBD_DEVICE USR_desc =
USBD_USR_SerialStrDescriptor,
USBD_USR_ConfigStrDescriptor,
USBD_USR_InterfaceStrDescriptor,
};
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
@ -137,7 +137,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END =
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
@ -157,14 +157,14 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
#pragma data_alignment=4
#endif
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
/* USB Standard Device Descriptor */
__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END =
{
USB_SIZ_STRING_LANGID,
USB_DESC_TYPE_STRING,
USB_DESC_TYPE_STRING,
LOBYTE(USBD_LANGID_STRING),
HIBYTE(USBD_LANGID_STRING),
};
@ -209,7 +209,7 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length)
uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
{
(void)speed;
*length = sizeof(USBD_LangIDDesc);
*length = sizeof(USBD_LangIDDesc);
return USBD_LangIDDesc;
}
@ -224,7 +224,7 @@ uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length)
{
if(speed == 0)
USBD_GetString ((uint8_t*)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
else
@ -278,7 +278,7 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length)
else
USBD_GetString ((uint8_t*)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
return USBD_StrDesc;
}
@ -296,7 +296,7 @@ uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length)
else
USBD_GetString ((uint8_t*)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
return USBD_StrDesc;
return USBD_StrDesc;
}
/**

View File

@ -30,7 +30,7 @@
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
* @{
*/
/** @defgroup USB_DESC
* @brief general defines for the usb device library file
* @{
@ -95,9 +95,9 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length);
uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length);
#ifdef USB_SUPPORT_USER_STRING_DESC
uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);
#endif /* USB_SUPPORT_USER_STRING_DESC */
/**
* @}
*/

View File

@ -29,7 +29,7 @@ USBD_Usr_cb_TypeDef USR_cb =
USBD_USR_DeviceConfigured,
USBD_USR_DeviceSuspended,
USBD_USR_DeviceResumed,
USBD_USR_DeviceConnected,
USBD_USR_DeviceDisconnected,
};
@ -42,7 +42,7 @@ USBD_Usr_cb_TypeDef USR_cb =
* @retval None
*/
void USBD_USR_Init(void)
{
{
}