mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
trailing whitespace removal (#14026)
trailing space removal Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
This commit is contained in:
parent
0de6278433
commit
493b9bf819
78 changed files with 371 additions and 371 deletions
|
@ -20,21 +20,21 @@
|
|||
|
||||
/**
|
||||
* Read internal and external analog channels
|
||||
*
|
||||
*
|
||||
* Internal channels provide temperature and the internal voltage reference
|
||||
* External channels are for vbat, rssi, current and a generic 'external' inputs
|
||||
*
|
||||
* The ADC is free running and so doesn't require a timer. Samples are moved from
|
||||
*
|
||||
* The ADC is free running and so doesn't require a timer. Samples are moved from
|
||||
* the ADC output register to a buffer by DMA
|
||||
*
|
||||
*
|
||||
* The sample rate is kept low to reduce impact on the DMA controller, and the lowest
|
||||
* priority is set for the DMA transfer. It's also recommended to use the highest numbered
|
||||
* DMA channel on the dma controller for ADC, since that is the lowest priority channel
|
||||
* for transfers at the same DMA priority.
|
||||
*
|
||||
*
|
||||
* Sample rate is set between 1 and 2kHz by using a long input sampling time and reasonably
|
||||
* high hardware oversampling.
|
||||
*
|
||||
*
|
||||
* Note that only ADC1 is used, although the code contains remnants of support for all
|
||||
* three ADC.
|
||||
*/
|
||||
|
@ -123,12 +123,12 @@ static volatile DMA_DATA uint32_t adcConversionBuffer[ADC_CHANNEL_COUNT];
|
|||
|
||||
/**
|
||||
* Initialise the specified ADC to read multiple channels in repeat mode
|
||||
*
|
||||
*
|
||||
* Sets 12 bit resolution, right aligned
|
||||
*
|
||||
*
|
||||
* @param dev Specifies the ADC device to use
|
||||
* @param channelCount how many channels to repeat over
|
||||
*
|
||||
*
|
||||
*/
|
||||
void adcInitDevice(const adc_type *dev, const int channelCount)
|
||||
{
|
||||
|
@ -146,7 +146,7 @@ void adcInitDevice(const adc_type *dev, const int channelCount)
|
|||
|
||||
/**
|
||||
* Find a given pin (defined by ioTag) in the map
|
||||
*
|
||||
*
|
||||
* @param tag the ioTag to search for
|
||||
* @return the index in adcTagMap corresponding to the given ioTag or -1 if not found
|
||||
*/
|
||||
|
@ -164,12 +164,12 @@ int adcFindTagMapEntry(const ioTag_t tag)
|
|||
* Setup the scaling offsets and factors used in adc.c
|
||||
* @see src/main/drivers/adc.c
|
||||
* @see src/main/drivers/adc_impl.h
|
||||
*
|
||||
*
|
||||
* There are a number of global calibration/scaling factors used in src/main/drivers/adc.c that need to
|
||||
* be set to appropriate values if we want to re-use existing code, e.g. adcInternalComputeTemperature
|
||||
* (the alternative would be to duplicate the code into ST and AT specific versions).
|
||||
* This is made a little confusing since the implementation based on ST datasheets approaches the calculation with
|
||||
* different formula and express the scaling factors in different units compared to the AT datasheets.
|
||||
* different formula and express the scaling factors in different units compared to the AT datasheets.
|
||||
* The constants are defined in src/main/drivers/adc_impl.h. It seems clearest to use the units from
|
||||
* the datasheet when defining those values, so here we have to convert to what's expected in
|
||||
* adcInternalComputeTemperature.
|
||||
|
@ -196,36 +196,36 @@ void setScalingFactors(void)
|
|||
/**
|
||||
* Setup the ADC so that it's running in the background and ready to
|
||||
* provide channel data
|
||||
*
|
||||
*
|
||||
* Notes:
|
||||
* This code only uses ADC1 despite appearances to the contrary, and has not been tested with the other ADCs
|
||||
*
|
||||
*
|
||||
* From the RM:
|
||||
* ADCCLK must be less than 80 MHz, while the ADCCLK frequency must be lower than PCLK2
|
||||
*
|
||||
*
|
||||
* PCLK2 looks like it's running at 144Mhz, but should be confirmed
|
||||
*
|
||||
*
|
||||
* With HCLK of 288, a divider of 4 gives an ADCCLK of 72MHz
|
||||
*
|
||||
* sample time is
|
||||
*
|
||||
* sample time is
|
||||
* ADC_SAMPLE + nbits + 0.5 ADCCLK periods
|
||||
*
|
||||
*
|
||||
* So with 12bit samples and ADC_SAMPLE_92_5 that's 105 clks.
|
||||
*
|
||||
* We're using HCLK/4, so 288/4 = 72MHz, each tick is 14ns. Add 5 clks for the interval between conversions,
|
||||
*
|
||||
* We're using HCLK/4, so 288/4 = 72MHz, each tick is 14ns. Add 5 clks for the interval between conversions,
|
||||
* 110 clks total is 1.54us per channel.
|
||||
*
|
||||
*
|
||||
* Max 6 channels is a total of 9.24us, or a basic sample rate of 108kHz per channel
|
||||
*
|
||||
*
|
||||
* If we use 64x oversampling we'll get an effective rate of 1.7kHz per channel which should still be plenty.
|
||||
*
|
||||
*
|
||||
* (RM and DS mention fast and slow channels, but don't give details on how this affects the above.
|
||||
* It's not relevant to our use case, so ignore the difference for now)
|
||||
*
|
||||
*
|
||||
* Called from fc/init.c
|
||||
*
|
||||
*
|
||||
* @param config - defines the channels to use for each external input (vbat, rssi, current, external) and also has calibration values for the temperature sensor
|
||||
*
|
||||
*
|
||||
*/
|
||||
void adcInit(const adcConfig_t *config)
|
||||
{
|
||||
|
@ -276,7 +276,7 @@ void adcInit(const adcConfig_t *config)
|
|||
|
||||
// Since ADC1 can do all channels this will only ever return adc1 and is unnecessary
|
||||
|
||||
// Find an ADC instance that can be used for the given TagMap index.
|
||||
// Find an ADC instance that can be used for the given TagMap index.
|
||||
// for (dev = 0; dev < ADCDEV_COUNT; dev++) {
|
||||
// #ifndef USE_DMA_SPEC
|
||||
// if (!adcDevice[dev].ADCx || !adcDevice[dev].dmaResource) {
|
||||
|
@ -459,13 +459,13 @@ uint16_t adcInternalRead(int channel)
|
|||
|
||||
/**
|
||||
* Read the internal Vref and return raw value
|
||||
*
|
||||
*
|
||||
* The internal Vref is 1.2V and can be used to calculate the external Vref+
|
||||
* External Vref+ determines the scale for the raw ADC readings but since it
|
||||
* is often directly connected to Vdd (approx 3.3V) it isn't accurately controlled.
|
||||
* Calculating the actual value of Vref+ by using measurements of the known 1.2V
|
||||
* internal reference can improve overall accuracy.
|
||||
*
|
||||
*
|
||||
* @return the raw ADC reading for the internal voltage reference
|
||||
* @see adcInternalCompensateVref in src/main/drivers/adc.c
|
||||
*/
|
||||
|
@ -478,7 +478,7 @@ uint16_t adcInternalReadVrefint(void)
|
|||
|
||||
/**
|
||||
* Read the internal temperature sensor
|
||||
*
|
||||
*
|
||||
* @return the raw ADC reading
|
||||
*/
|
||||
uint16_t adcInternalReadTempsensor(void)
|
||||
|
|
|
@ -84,7 +84,7 @@ void bbTimerChannelInit(bbPort_t *bbPort)
|
|||
TIM_OCInitTypeDef TIM_OCStruct;
|
||||
|
||||
TIM_OCStructInit(&TIM_OCStruct);
|
||||
|
||||
|
||||
TIM_OCStruct.oc_mode = TMR_OUTPUT_CONTROL_PWM_MODE_A;
|
||||
TIM_OCStruct.oc_idle_state = TRUE;
|
||||
TIM_OCStruct.oc_output_state = TRUE;
|
||||
|
@ -106,7 +106,7 @@ void bbTimerChannelInit(bbPort_t *bbPort)
|
|||
if (timhw->tag) {
|
||||
IO_t io = IOGetByTag(timhw->tag);
|
||||
IOConfigGPIOAF(io, IOCFG_AF_PP, timhw->alternateFunction);
|
||||
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||
TIM_CtrlPWMOutputs(timhw->tim, TRUE);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -45,15 +45,15 @@
|
|||
|
||||
/**
|
||||
* Convert from BF channel to AT32 constants for timer output channels
|
||||
*
|
||||
*
|
||||
* The AT and ST apis take a different approach to naming channels, so just passing the bf
|
||||
* channel number to the AT calls doesn't work. This function maps between them.
|
||||
*
|
||||
*
|
||||
* @param bfChannel a channel number as used in timerHardware->channel (1 based)
|
||||
* @param useNChannel indicates that the desired channel should be the complementary output (only available for 1 through 3)
|
||||
* @return an AT32 tmr_channel_select_type constant
|
||||
* XXX what to return for invalid inputs? The tmr_channel_select_type enum doesn't have a suitable value
|
||||
*
|
||||
*
|
||||
* @see TIM_CH_TO_SELCHANNEL macro
|
||||
*/
|
||||
tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNChannel)
|
||||
|
@ -110,7 +110,7 @@ tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNC
|
|||
|
||||
/**
|
||||
* Enable the timer channels for all motors
|
||||
*
|
||||
*
|
||||
* Called once for every dshot update if telemetry is being used (not just enabled by #def)
|
||||
* Called from pwm_output_dshot_shared.c pwmTelemetryDecode
|
||||
*/
|
||||
|
@ -128,7 +128,7 @@ void dshotEnableChannels(uint8_t motorCount)
|
|||
|
||||
/**
|
||||
* Set the timer and dma of the specified motor for use as an output
|
||||
*
|
||||
*
|
||||
* Called from pwmDshotMotorHardwareConfig in this file and also from
|
||||
* pwmTelemetryDecode in src/main/drivers/pwm_output_dshot_shared.c
|
||||
*/
|
||||
|
@ -199,9 +199,9 @@ FAST_CODE void pwmDshotSetDirectionOutput(
|
|||
tmr_channel_enable(timer, toCHSelectType(channel, useCompOut), TRUE);
|
||||
timerOCPreloadConfig(timer, channel, TRUE);
|
||||
|
||||
pDmaInit->direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
|
||||
pDmaInit->direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
|
||||
xDMA_Init(dmaRef, pDmaInit);
|
||||
|
||||
|
||||
// Generate an interrupt when the transfer is complete
|
||||
xDMA_ITConfig(dmaRef, DMA_FDT_INT, TRUE);
|
||||
|
||||
|
@ -241,7 +241,7 @@ static void pwmDshotSetDirectionInput(motorDmaOutput_t * const motor)
|
|||
|
||||
/**
|
||||
* Start the timers and dma requests to send dshot data to all motors
|
||||
*
|
||||
*
|
||||
* Called after pwm_output_dshot_shared.c has finished setting up the buffers that represent the dshot packets.
|
||||
* Iterates over all the timers needed (note that there may be less timers than motors since a single timer can run
|
||||
* multiple motors) and enables each one.
|
||||
|
@ -298,8 +298,8 @@ void pwmCompleteDshotMotorUpdate(void)
|
|||
|
||||
/**
|
||||
* Interrupt handler called at the end of each packet
|
||||
*
|
||||
* Responsible for switching the dshot direction after sending a dshot command so that we
|
||||
*
|
||||
* Responsible for switching the dshot direction after sending a dshot command so that we
|
||||
* can receive dshot telemetry. If telemetry is not enabled, disables the dma and request generation.
|
||||
*/
|
||||
FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
|
@ -360,7 +360,7 @@ FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
|||
} // if DMA_IT_TCIF
|
||||
}
|
||||
|
||||
bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex,
|
||||
bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex,
|
||||
motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||
{
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
|
@ -422,7 +422,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
// Boolean configureTimer is always true when different channels of the same timer are processed in sequence,
|
||||
// causing the timer and the associated DMA initialized more than once.
|
||||
// To fix this, getTimerIndex must be expanded to return if a new timer has been requested.
|
||||
// However, since the initialization is idempotent (can be applied multiple times without changing the outcome),
|
||||
// However, since the initialization is idempotent (can be applied multiple times without changing the outcome),
|
||||
// it is left as is in a favor of flash space (for now).
|
||||
const uint8_t timerIndex = getTimerIndex(timer);
|
||||
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
||||
|
@ -571,7 +571,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
|
||||
{ // local scope
|
||||
const tmr_channel_select_type chSel = toCHSelectType(timerHardware->channel, output & TIMER_OUTPUT_N_CHANNEL);
|
||||
tmr_channel_enable(timer, chSel, TRUE);
|
||||
tmr_channel_enable(timer, chSel, TRUE);
|
||||
}
|
||||
|
||||
if (configureTimer) {
|
||||
|
@ -587,7 +587,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
*timerChCCR(timerHardware) = 0xffff;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
motor->configured = true;
|
||||
|
||||
return true;
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -43,7 +43,7 @@ extern "C" {
|
|||
/** @addtogroup AT32F435_437
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @addtogroup Library_configuration_section
|
||||
* @{
|
||||
*/
|
||||
|
@ -376,7 +376,7 @@ typedef __I uint16_t vuc16; /*!< read only */
|
|||
typedef __I uint8_t vuc8; /*!< read only */
|
||||
|
||||
typedef enum {RESET = 0, SET = !RESET} flag_status;
|
||||
typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state;
|
||||
typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state;
|
||||
typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
||||
|
||||
/**
|
||||
|
@ -480,7 +480,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
#define USART1_BASE (APB2PERIPH_BASE + 0x1000)
|
||||
#define TMR8_BASE (APB2PERIPH_BASE + 0x0400)
|
||||
#define TMR1_BASE (APB2PERIPH_BASE + 0x0000)
|
||||
/* ahb bus base address */
|
||||
/* ahb bus base address */
|
||||
#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000)
|
||||
#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400)
|
||||
#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00)
|
||||
|
@ -640,7 +640,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
#define USART1_BASE (APB2PERIPH_BASE + 0x1000)
|
||||
#define TMR8_BASE (APB2PERIPH_BASE + 0x0400)
|
||||
#define TMR1_BASE (APB2PERIPH_BASE + 0x0000)
|
||||
/* ahb bus base address */
|
||||
/* ahb bus base address */
|
||||
#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000)
|
||||
#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400)
|
||||
#define EMAC_BASE (AHBPERIPH1_BASE + 0x8000)
|
||||
|
@ -718,7 +718,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C)
|
||||
#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034)
|
||||
#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C)
|
||||
|
||||
|
||||
#define EDMA_LL_BASE (EDMA_BASE + 0x00D0)
|
||||
#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004)
|
||||
#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008)
|
||||
|
@ -760,7 +760,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -5,11 +5,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -51,7 +51,7 @@ void system_clock_config(void)
|
|||
|
||||
/* config ldo voltage */
|
||||
pwc_ldo_output_voltage_set(PWC_LDO_OUTPUT_1V3);
|
||||
|
||||
|
||||
/* set the flash clock divider */
|
||||
flash_clock_divider_set(FLASH_CLOCK_DIV_3);
|
||||
|
||||
|
|
|
@ -5,11 +5,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
|
|
@ -5,11 +5,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -38,7 +38,7 @@ extern "C" {
|
|||
#define NULL ((void *) 0)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @brief in the following line adjust the value of high speed exernal crystal (hext)
|
||||
* used in your application
|
||||
|
@ -172,7 +172,7 @@ extern "C" {
|
|||
#ifdef USB_MODULE_ENABLED
|
||||
#include "at32f435_437_usb.h"
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -175,7 +175,7 @@ extern void _init(void) {;}
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -39,7 +39,7 @@ extern "C" {
|
|||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup AT32F435_437_system_exported_variables
|
||||
/** @defgroup AT32F435_437_system_exported_variables
|
||||
* @{
|
||||
*/
|
||||
extern unsigned int system_core_clock; /*!< system clock frequency (core clock) */
|
||||
|
@ -48,10 +48,10 @@ extern unsigned int system_core_clock; /*!< system clock frequency (core clock)
|
|||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup AT32F435_437_system_exported_functions
|
||||
/** @defgroup AT32F435_437_system_exported_functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void system_core_clock_update(void);
|
||||
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -23,7 +23,7 @@
|
|||
*
|
||||
**************************************************************************
|
||||
*/
|
||||
|
||||
|
||||
/* define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __USB_CONF_H
|
||||
#define __USB_CONF_H
|
||||
|
@ -31,7 +31,7 @@
|
|||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
#include "at32f435_437_usb.h"
|
||||
#include "at32f435_437.h"
|
||||
//#include "stdio.h"
|
||||
|
@ -39,7 +39,7 @@ extern "C" {
|
|||
/** @addtogroup AT32F437_periph_examples
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @addtogroup 437_USB_device_vcp_loopback
|
||||
* @{
|
||||
*/
|
||||
|
@ -206,11 +206,11 @@ void usb_delay_ms(uint32_t ms);
|
|||
void usb_delay_us(uint32_t us);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue