Move telemetry displayport init and cms device registering
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F30x_StdPeriph_Driver / src / stm32f30x_syscfg.c
blob67a17f34c65ed477354c16414639a23bfb509d66
1 /**
2 ******************************************************************************
3 * @file stm32f30x_syscfg.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 04-April-2014
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the SYSCFG peripheral:
9 * + Remapping the memory mapped at 0x00000000
10 * + Remapping the DMA channels
11 * + Enabling I2C fast mode plus driving capability for I2C plus
12 * + Remapping USB interrupt line
13 * + Configuring the EXTI lines connection to the GPIO port
14 * + Configuring the CLASSB requirements
16 @verbatim
18 ===============================================================================
19 ##### How to use this driver #####
20 ===============================================================================
21 [..] The SYSCFG registers can be accessed only when the SYSCFG
22 interface APB clock is enabled.
23 [..] To enable SYSCFG APB clock use:
24 RCC_APBPeriphClockCmd(RCC_APBPeriph_SYSCFG, ENABLE);
26 @endverbatim
28 ******************************************************************************
29 * @attention
31 * <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
33 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
34 * You may not use this file except in compliance with the License.
35 * You may obtain a copy of the License at:
37 * http://www.st.com/software_license_agreement_liberty_v2
39 * Unless required by applicable law or agreed to in writing, software
40 * distributed under the License is distributed on an "AS IS" BASIS,
41 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
42 * See the License for the specific language governing permissions and
43 * limitations under the License.
45 ******************************************************************************
48 /* Includes ------------------------------------------------------------------*/
49 #include "stm32f30x_syscfg.h"
51 /** @addtogroup STM32F30x_StdPeriph_Driver
52 * @{
55 /** @defgroup SYSCFG
56 * @brief SYSCFG driver modules
57 * @{
58 */
60 /* Private typedef -----------------------------------------------------------*/
61 /* Private define ------------------------------------------------------------*/
62 /* Reset value od SYSCFG_CFGR1 register */
63 #define CFGR1_CLEAR_MASK ((uint32_t)0x7C000000)
65 /* ------------ SYSCFG registers bit address in the alias region -------------*/
66 #define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE)
68 /* --- CFGR1 Register ---*/
69 /* Alias word address of USB_IT_RMP bit */
70 #define CFGR1_OFFSET (SYSCFG_OFFSET + 0x00)
71 #define USBITRMP_BitNumber 0x05
72 #define CFGR1_USBITRMP_BB (PERIPH_BB_BASE + (CFGR1_OFFSET * 32) + (USBITRMP_BitNumber * 4))
74 /* --- CFGR2 Register ---*/
75 /* Alias word address of BYP_ADDR_PAR bit */
76 #define CFGR2_OFFSET (SYSCFG_OFFSET + 0x18)
77 #define BYPADDRPAR_BitNumber 0x04
78 #define CFGR1_BYPADDRPAR_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (BYPADDRPAR_BitNumber * 4))
80 /* Private macro -------------------------------------------------------------*/
81 /* Private variables ---------------------------------------------------------*/
82 /* Private function prototypes -----------------------------------------------*/
83 /* Private functions ---------------------------------------------------------*/
85 /** @defgroup SYSCFG_Private_Functions
86 * @{
87 */
89 /** @defgroup SYSCFG_Group1 SYSCFG Initialization and Configuration functions
90 * @brief SYSCFG Initialization and Configuration functions
92 @verbatim
93 ===============================================================================
94 ##### SYSCFG Initialization and Configuration functions #####
95 ===============================================================================
97 @endverbatim
98 * @{
102 * @brief Deinitializes the SYSCFG registers to their default reset values.
103 * @param None
104 * @retval None
105 * @note MEM_MODE bits are not affected by APB reset.
106 * MEM_MODE bits took the value from the user option bytes.
108 void SYSCFG_DeInit(void)
110 /* Reset SYSCFG_CFGR1 register to reset value without affecting MEM_MODE bits */
111 SYSCFG->CFGR1 &= SYSCFG_CFGR1_MEM_MODE;
112 /* Set FPU Interrupt Enable bits to default value */
113 SYSCFG->CFGR1 |= 0x7C000000;
114 /* Reset RAM Write protection bits to default value */
115 SYSCFG->RCR = 0x00000000;
116 /* Set EXTICRx registers to reset value */
117 SYSCFG->EXTICR[0] = 0;
118 SYSCFG->EXTICR[1] = 0;
119 SYSCFG->EXTICR[2] = 0;
120 SYSCFG->EXTICR[3] = 0;
121 /* Set CFGR2 register to reset value */
122 SYSCFG->CFGR2 = 0;
123 /* Set CFGR3 register to reset value */
124 SYSCFG->CFGR3 = 0;
128 * @brief Configures the memory mapping at address 0x00000000.
129 * @param SYSCFG_MemoryRemap: selects the memory remapping.
130 * This parameter can be one of the following values:
131 * @arg SYSCFG_MemoryRemap_Flash: Main Flash memory mapped at 0x00000000
132 * @arg SYSCFG_MemoryRemap_SystemMemory: System Flash memory mapped at 0x00000000
133 * @arg SYSCFG_MemoryRemap_SRAM: Embedded SRAM mapped at 0x00000000
134 * @retval None
136 void SYSCFG_MemoryRemapConfig(uint32_t SYSCFG_MemoryRemap)
138 uint32_t tmpcfgr1 = 0;
140 /* Check the parameter */
141 assert_param(IS_SYSCFG_MEMORY_REMAP(SYSCFG_MemoryRemap));
143 /* Get CFGR1 register value */
144 tmpcfgr1 = SYSCFG->CFGR1;
146 /* Clear MEM_MODE bits */
147 tmpcfgr1 &= (uint32_t) (~SYSCFG_CFGR1_MEM_MODE);
149 /* Set the new MEM_MODE bits value */
150 tmpcfgr1 |= (uint32_t) SYSCFG_MemoryRemap;
152 /* Set CFGR1 register with the new memory remap configuration */
153 SYSCFG->CFGR1 = tmpcfgr1;
157 * @brief Configures the DMA channels remapping.
158 * @param SYSCFG_DMARemap: selects the DMA channels remap.
159 * This parameter can be one of the following values:
160 * @arg SYSCFG_DMARemap_TIM17: Remap TIM17 DMA requests from DMA1 channel1 to channel2
161 * @arg SYSCFG_DMARemap_TIM16: Remap TIM16 DMA requests from DMA1 channel3 to channel4
162 * @arg SYSCFG_DMARemap_TIM6DAC1Ch1: Remap TIM6/DAC1 DMA requests from DMA2 channel 3 to DMA1 channel 3
163 * @arg SYSCFG_DMARemap_TIM7DAC1Ch2: Remap TIM7/DAC2 DMA requests from DMA2 channel 4 to DMA1 channel 4
164 * @arg SYSCFG_DMARemap_ADC2ADC4: Remap ADC2 and ADC4 DMA requests from DMA2 channel1/channel3 to channel3/channel4
165 * @arg SYSCFG_DMARemap_DAC2Ch1: Remap DAC2 DMA requests to DMA1 channel5
166 * @arg SYSCFG_DMARemapCh2_SPI1_RX: Remap SPI1 RX DMA1 CH2 requests
167 * @arg SYSCFG_DMARemapCh4_SPI1_RX: Remap SPI1 RX DMA CH4 requests
168 * @arg SYSCFG_DMARemapCh6_SPI1_RX: Remap SPI1 RX DMA CH6 requests
169 * @arg SYSCFG_DMARemapCh3_SPI1_TX: Remap SPI1 TX DMA CH2 requests
170 * @arg SYSCFG_DMARemapCh5_SPI1_TX: Remap SPI1 TX DMA CH5 requests
171 * @arg SYSCFG_DMARemapCh7_SPI1_TX: Remap SPI1 TX DMA CH7 requests
172 * @arg SYSCFG_DMARemapCh7_I2C1_RX: Remap I2C1 RX DMA CH7 requests
173 * @arg SYSCFG_DMARemapCh3_I2C1_RX: Remap I2C1 RX DMA CH3 requests
174 * @arg SYSCFG_DMARemapCh5_I2C1_RX: Remap I2C1 RX DMA CH5 requests
175 * @arg SYSCFG_DMARemapCh6_I2C1_TX: Remap I2C1 TX DMA CH6 requests
176 * @arg SYSCFG_DMARemapCh2_I2C1_TX: Remap I2C1 TX DMA CH2 requests
177 * @arg SYSCFG_DMARemapCh4_I2C1_TX: Remap I2C1 TX DMA CH4 requests
178 * @arg SYSCFG_DMARemapCh4_ADC2: Remap ADC2 DMA1 Ch4 requests
179 * @arg SYSCFG_DMARemapCh2_ADC2: Remap ADC2 DMA1 Ch2 requests
180 * @param NewState: new state of the DMA channel remapping.
181 * This parameter can be: Enable or Disable.
182 * @note When enabled, DMA channel of the selected peripheral is remapped
183 * @note When disabled, Default DMA channel is mapped to the selected peripheral
184 * @note
185 * By default TIM17 DMA requests is mapped to channel 1
186 * use SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, Enable)
187 * to remap TIM17 DMA requests to DMA1 channel 2
188 * use SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, Disable)
189 * to map TIM17 DMA requests to DMA1 channel 1 (default mapping)
190 * @retval None
192 void SYSCFG_DMAChannelRemapConfig(uint32_t SYSCFG_DMARemap, FunctionalState NewState)
194 /* Check the parameters */
195 assert_param(IS_SYSCFG_DMA_REMAP(SYSCFG_DMARemap));
196 assert_param(IS_FUNCTIONAL_STATE(NewState));
198 if ((SYSCFG_DMARemap & 0x80000000)!= 0x80000000)
200 if (NewState != DISABLE)
202 /* Remap the DMA channel */
203 SYSCFG->CFGR1 |= (uint32_t)SYSCFG_DMARemap;
205 else
207 /* use the default DMA channel mapping */
208 SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_DMARemap);
211 else
213 if (NewState != DISABLE)
215 /* Remap the DMA channel */
216 SYSCFG->CFGR3 |= (uint32_t)SYSCFG_DMARemap;
218 else
220 /* use the default DMA channel mapping */
221 SYSCFG->CFGR3 &= (uint32_t)(~SYSCFG_DMARemap);
227 * @brief Configures the remapping capabilities of DAC/TIM triggers.
228 * @param SYSCFG_TriggerRemap: selects the trigger to be remapped.
229 * This parameter can be one of the following values:
230 * @arg SYSCFG_TriggerRemap_DACTIM3: Remap DAC trigger from TIM8 to TIM3
231 * @arg SYSCFG_TriggerRemap_TIM1TIM17: Remap TIM1 ITR3 from TIM4 TRGO to TIM17 OC
232 * @arg SYSCFG_TriggerRemap_DACHRTIM1_TRIG1: Remap DAC trigger to HRTIM1 TRIG1
233 * @arg SYSCFG_TriggerRemap_DACHRTIM1_TRIG2: Remap DAC trigger to HRTIM1 TRIG2
234 * @param NewState: new state of the trigger mapping.
235 * This parameter can be: ENABLE or DISABLE.
236 * @note ENABLE: Enable fast mode plus driving capability for selected pin
237 * @note DISABLE: Disable fast mode plus driving capability for selected pin
238 * @retval None
240 void SYSCFG_TriggerRemapConfig(uint32_t SYSCFG_TriggerRemap, FunctionalState NewState)
242 /* Check the parameters */
243 assert_param(IS_SYSCFG_TRIGGER_REMAP(SYSCFG_TriggerRemap));
244 assert_param(IS_FUNCTIONAL_STATE(NewState));
246 if ((SYSCFG_TriggerRemap & 0x80000000)!= 0x80000000)
248 if (NewState != DISABLE)
250 /* Remap the trigger */
251 SYSCFG->CFGR1 |= (uint32_t)SYSCFG_TriggerRemap;
253 else
255 /* Use the default trigger mapping */
256 SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_TriggerRemap);
259 else
261 if (NewState != DISABLE)
263 /* Remap the trigger */
264 SYSCFG->CFGR3 |= (uint32_t)SYSCFG_TriggerRemap;
266 else
268 /* Use the default trigger mapping */
269 SYSCFG->CFGR3 &= (uint32_t)(~SYSCFG_TriggerRemap);
275 * @brief Configures the remapping capabilities of encoder mode.
276 * @ note This feature implement the so-called M/T method for measuring speed
277 * and position using quadrature encoders.
278 * @param SYSCFG_EncoderRemap: selects the remap option for encoder mode.
279 * This parameter can be one of the following values:
280 * @arg SYSCFG_EncoderRemap_No: No remap
281 * @arg SYSCFG_EncoderRemap_TIM2: Timer 2 IC1 and IC2 connected to TIM15 IC1 and IC2
282 * @arg SYSCFG_EncoderRemap_TIM3: Timer 3 IC1 and IC2 connected to TIM15 IC1 and IC2
283 * @arg SYSCFG_EncoderRemap_TIM4: Timer 4 IC1 and IC2 connected to TIM15 IC1 and IC2
284 * @retval None
286 void SYSCFG_EncoderRemapConfig(uint32_t SYSCFG_EncoderRemap)
288 /* Check the parameter */
289 assert_param(IS_SYSCFG_ENCODER_REMAP(SYSCFG_EncoderRemap));
291 /* Reset the encoder mode remapping bits */
292 SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_CFGR1_ENCODER_MODE);
294 /* Set the selected configuration */
295 SYSCFG->CFGR1 |= (uint32_t)(SYSCFG_EncoderRemap);
299 * @brief Remaps the USB interrupt lines.
300 * @param NewState: new state of the mapping of USB interrupt lines.
301 * This parameter can be:
302 * @param ENABLE: Remap the USB interrupt line as following:
303 * @arg USB Device High Priority (USB_HP) interrupt mapped to line 74.
304 * @arg USB Device Low Priority (USB_LP) interrupt mapped to line 75.
305 * @arg USB Wakeup Interrupt (USB_WKUP) interrupt mapped to line 76.
306 * @param DISABLE: Use the default USB interrupt line:
307 * @arg USB Device High Priority (USB_HP) interrupt mapped to line 19.
308 * @arg USB Device Low Priority (USB_LP) interrupt mapped to line 20.
309 * @arg USB Wakeup Interrupt (USB_WKUP) interrupt mapped to line 42.
310 * @retval None
312 void SYSCFG_USBInterruptLineRemapCmd(FunctionalState NewState)
314 /* Check the parameter */
315 assert_param(IS_FUNCTIONAL_STATE(NewState));
317 /* Remap the USB interupt lines */
318 *(__IO uint32_t *) CFGR1_USBITRMP_BB = (uint32_t)NewState;
322 * @brief Configures the I2C fast mode plus driving capability.
323 * @param SYSCFG_I2CFastModePlus: selects the pin.
324 * This parameter can be one of the following values:
325 * @arg SYSCFG_I2CFastModePlus_PB6: Configure fast mode plus driving capability for PB6
326 * @arg SYSCFG_I2CFastModePlus_PB7: Configure fast mode plus driving capability for PB7
327 * @arg SYSCFG_I2CFastModePlus_PB8: Configure fast mode plus driving capability for PB8
328 * @arg SYSCFG_I2CFastModePlus_PB9: Configure fast mode plus driving capability for PB9
329 * @arg SYSCFG_I2CFastModePlus_I2C1: Configure fast mode plus driving capability for I2C1 pins
330 * @arg SYSCFG_I2CFastModePlus_I2C2: Configure fast mode plus driving capability for I2C2 pins
331 * @param NewState: new state of the DMA channel remapping.
332 * This parameter can be:
333 * @arg ENABLE: Enable fast mode plus driving capability for selected I2C pin
334 * @arg DISABLE: Disable fast mode plus driving capability for selected I2C pin
335 * @note For I2C1, fast mode plus driving capability can be enabled on all selected
336 * I2C1 pins using SYSCFG_I2CFastModePlus_I2C1 parameter or independently
337 * on each one of the following pins PB6, PB7, PB8 and PB9.
338 * @note For remaing I2C1 pins (PA14, PA15...) fast mode plus driving capability
339 * can be enabled only by using SYSCFG_I2CFastModePlus_I2C1 parameter.
340 * @note For all I2C2 pins fast mode plus driving capability can be enabled
341 * only by using SYSCFG_I2CFastModePlus_I2C2 parameter.
342 * @retval None
344 void SYSCFG_I2CFastModePlusConfig(uint32_t SYSCFG_I2CFastModePlus, FunctionalState NewState)
346 /* Check the parameters */
347 assert_param(IS_SYSCFG_I2C_FMP(SYSCFG_I2CFastModePlus));
348 assert_param(IS_FUNCTIONAL_STATE(NewState));
350 if (NewState != DISABLE)
352 /* Enable fast mode plus driving capability for selected I2C pin */
353 SYSCFG->CFGR1 |= (uint32_t)SYSCFG_I2CFastModePlus;
355 else
357 /* Disable fast mode plus driving capability for selected I2C pin */
358 SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_I2CFastModePlus);
363 * @brief Enables or disables the selected SYSCFG interrupts.
364 * @param SYSCFG_IT: specifies the SYSCFG interrupt sources to be enabled or disabled.
365 * This parameter can be one of the following values:
366 * @arg SYSCFG_IT_IXC: Inexact Interrupt
367 * @arg SYSCFG_IT_IDC: Input denormal Interrupt
368 * @arg SYSCFG_IT_OFC: Overflow Interrupt
369 * @arg SYSCFG_IT_UFC: Underflow Interrupt
370 * @arg SYSCFG_IT_DZC: Divide-by-zero Interrupt
371 * @arg SYSCFG_IT_IOC: Invalid operation Interrupt
372 * @param NewState: new state of the specified SYSCFG interrupts.
373 * This parameter can be: ENABLE or DISABLE.
374 * @retval None
376 void SYSCFG_ITConfig(uint32_t SYSCFG_IT, FunctionalState NewState)
378 /* Check the parameters */
379 assert_param(IS_FUNCTIONAL_STATE(NewState));
380 assert_param(IS_SYSCFG_IT(SYSCFG_IT));
382 if (NewState != DISABLE)
384 /* Enable the selected SYSCFG interrupts */
385 SYSCFG->CFGR1 |= SYSCFG_IT;
387 else
389 /* Disable the selected SYSCFG interrupts */
390 SYSCFG->CFGR1 &= ((uint32_t)~SYSCFG_IT);
395 * @brief Selects the GPIO pin used as EXTI Line.
396 * @param EXTI_PortSourceGPIOx : selects the GPIO port to be used as source
397 * for EXTI lines where x can be (A, B, C, D, E or F).
398 * @param EXTI_PinSourcex: specifies the EXTI line to be configured.
399 * This parameter can be EXTI_PinSourcex where x can be (0..15)
400 * @retval None
402 void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex)
404 uint32_t tmp = 0x00;
406 /* Check the parameters */
407 assert_param(IS_EXTI_PORT_SOURCE(EXTI_PortSourceGPIOx));
408 assert_param(IS_EXTI_PIN_SOURCE(EXTI_PinSourcex));
410 tmp = ((uint32_t)0x0F) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03));
411 SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] &= ~tmp;
412 SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] |= (((uint32_t)EXTI_PortSourceGPIOx) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03)));
416 * @brief Connects the selected parameter to the break input of TIM1.
417 * @note The selected configuration is locked and can be unlocked by system reset
418 * @param SYSCFG_Break: selects the configuration to be connected to break
419 * input of TIM1
420 * This parameter can be any combination of the following values:
421 * @arg SYSCFG_Break_PVD: PVD interrupt is connected to the break input of TIM1.
422 * @arg SYSCFG_Break_SRAMParity: SRAM Parity error is connected to the break input of TIM1.
423 * @arg SYSCFG_Break_HardFault: Lockup output of CortexM4 is connected to the break input of TIM1.
424 * @retval None
426 void SYSCFG_BreakConfig(uint32_t SYSCFG_Break)
428 /* Check the parameter */
429 assert_param(IS_SYSCFG_LOCK_CONFIG(SYSCFG_Break));
431 SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Break;
435 * @brief Disables the parity check on RAM.
436 * @note Disabling the parity check on RAM locks the configuration bit.
437 * To re-enable the parity check on RAM perform a system reset.
438 * @param None
439 * @retval None
441 void SYSCFG_BypassParityCheckDisable(void)
443 /* Disable the adddress parity check on RAM */
444 *(__IO uint32_t *) CFGR1_BYPADDRPAR_BB = (uint32_t)0x00000001;
448 * @brief Enables the ICODE SRAM write protection.
449 * @note Enabling the ICODE SRAM write protection locks the configuration bit.
450 * To disable the ICODE SRAM write protection perform a system reset.
451 * @param None
452 * @retval None
454 void SYSCFG_SRAMWRPEnable(uint32_t SYSCFG_SRAMWRP)
456 /* Check the parameter */
457 assert_param(IS_SYSCFG_PAGE(SYSCFG_SRAMWRP));
459 /* Enable the write-protection on the selected ICODE SRAM page */
460 SYSCFG->RCR |= (uint32_t)SYSCFG_SRAMWRP;
464 * @brief Checks whether the specified SYSCFG flag is set or not.
465 * @param SYSCFG_Flag: specifies the SYSCFG flag to check.
466 * This parameter can be one of the following values:
467 * @arg SYSCFG_FLAG_PE: SRAM parity error flag.
468 * @retval The new state of SYSCFG_Flag (SET or RESET).
470 FlagStatus SYSCFG_GetFlagStatus(uint32_t SYSCFG_Flag)
472 (void)SYSCFG_Flag;
473 FlagStatus bitstatus = RESET;
475 /* Check the parameter */
476 assert_param(IS_SYSCFG_FLAG(SYSCFG_Flag));
478 /* Check the status of the specified SPI flag */
479 if ((SYSCFG->CFGR2 & SYSCFG_CFGR2_SRAM_PE) != (uint32_t)RESET)
481 /* SYSCFG_Flag is set */
482 bitstatus = SET;
484 else
486 /* SYSCFG_Flag is reset */
487 bitstatus = RESET;
489 /* Return the SYSCFG_Flag status */
490 return bitstatus;
494 * @brief Clears the selected SYSCFG flag.
495 * @param SYSCFG_Flag: selects the flag to be cleared.
496 * This parameter can be any combination of the following values:
497 * @arg SYSCFG_FLAG_PE: SRAM parity error flag.
498 * @retval None
500 void SYSCFG_ClearFlag(uint32_t SYSCFG_Flag)
502 /* Check the parameter */
503 assert_param(IS_SYSCFG_FLAG(SYSCFG_Flag));
505 SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Flag;
509 * @}
513 * @}
517 * @}
521 * @}
523 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/