Implement rudimentary CAN communication
This commit is contained in:
parent
6a772179c1
commit
bc3771c39a
@ -55,6 +55,7 @@ void SVC_Handler(void);
|
||||
void DebugMon_Handler(void);
|
||||
void PendSV_Handler(void);
|
||||
void SysTick_Handler(void);
|
||||
void FDCAN1_IT0_IRQHandler(void);
|
||||
void I2C2_EV_IRQHandler(void);
|
||||
void EXTI15_10_IRQHandler(void);
|
||||
/* USER CODE BEGIN EFP */
|
||||
|
15
Core/Inc/vehicle.h
Normal file
15
Core/Inc/vehicle.h
Normal file
@ -0,0 +1,15 @@
|
||||
#ifndef __VEHICLE_H
|
||||
#define __VEHICLE_H
|
||||
|
||||
#include "state.h"
|
||||
#include "stm32g4xx_hal.h"
|
||||
#include "stm32g4xx_hal_fdcan.h"
|
||||
|
||||
#define CAN_ID_MISSION_SELECT 0x400
|
||||
#define CAN_ID_AS_MISSION_FB 0x410
|
||||
|
||||
void vehicle_init(FDCAN_HandleTypeDef *handle);
|
||||
|
||||
void vehicle_send_mission_select(Mission mission);
|
||||
|
||||
#endif // __VEHICLE_H
|
@ -24,6 +24,7 @@
|
||||
#include "events.h"
|
||||
#include "rpi.h"
|
||||
#include "state.h"
|
||||
#include "vehicle.h"
|
||||
|
||||
#include "stm32g4xx_hal.h"
|
||||
#include "stm32g4xx_hal_gpio.h"
|
||||
@ -105,6 +106,7 @@ int main(void) {
|
||||
MX_I2C2_Init();
|
||||
/* USER CODE BEGIN 2 */
|
||||
state_init();
|
||||
vehicle_init(&hfdcan1);
|
||||
rpi_init(&hi2c2);
|
||||
/* USER CODE END 2 */
|
||||
|
||||
@ -144,7 +146,13 @@ void SystemClock_Config(void) {
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
|
||||
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
||||
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
|
||||
RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
|
||||
RCC_OscInitStruct.PLL.PLLN = 10;
|
||||
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
|
||||
RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
|
||||
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
|
||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
@ -153,12 +161,12 @@ void SystemClock_Config(void) {
|
||||
*/
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK |
|
||||
RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
|
||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI;
|
||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
|
||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
|
||||
|
||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) {
|
||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
}
|
||||
@ -242,20 +250,20 @@ static void MX_FDCAN1_Init(void) {
|
||||
/* USER CODE END FDCAN1_Init 1 */
|
||||
hfdcan1.Instance = FDCAN1;
|
||||
hfdcan1.Init.ClockDivider = FDCAN_CLOCK_DIV1;
|
||||
hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
|
||||
hfdcan1.Init.FrameFormat = FDCAN_FRAME_FD_BRS;
|
||||
hfdcan1.Init.Mode = FDCAN_MODE_NORMAL;
|
||||
hfdcan1.Init.AutoRetransmission = DISABLE;
|
||||
hfdcan1.Init.TransmitPause = DISABLE;
|
||||
hfdcan1.Init.AutoRetransmission = ENABLE;
|
||||
hfdcan1.Init.TransmitPause = ENABLE;
|
||||
hfdcan1.Init.ProtocolException = DISABLE;
|
||||
hfdcan1.Init.NominalPrescaler = 1;
|
||||
hfdcan1.Init.NominalSyncJumpWidth = 1;
|
||||
hfdcan1.Init.NominalTimeSeg1 = 2;
|
||||
hfdcan1.Init.NominalTimeSeg2 = 2;
|
||||
hfdcan1.Init.NominalSyncJumpWidth = 16;
|
||||
hfdcan1.Init.NominalTimeSeg1 = 63;
|
||||
hfdcan1.Init.NominalTimeSeg2 = 16;
|
||||
hfdcan1.Init.DataPrescaler = 1;
|
||||
hfdcan1.Init.DataSyncJumpWidth = 1;
|
||||
hfdcan1.Init.DataTimeSeg1 = 1;
|
||||
hfdcan1.Init.DataTimeSeg2 = 1;
|
||||
hfdcan1.Init.StdFiltersNbr = 0;
|
||||
hfdcan1.Init.DataSyncJumpWidth = 4;
|
||||
hfdcan1.Init.DataTimeSeg1 = 5;
|
||||
hfdcan1.Init.DataTimeSeg2 = 4;
|
||||
hfdcan1.Init.StdFiltersNbr = 2;
|
||||
hfdcan1.Init.ExtFiltersNbr = 0;
|
||||
hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
|
||||
if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) {
|
||||
@ -281,7 +289,7 @@ static void MX_I2C2_Init(void) {
|
||||
|
||||
/* USER CODE END I2C2_Init 1 */
|
||||
hi2c2.Instance = I2C2;
|
||||
hi2c2.Init.Timing = 0x00303D5B;
|
||||
hi2c2.Init.Timing = 0x10909CEC;
|
||||
hi2c2.Init.OwnAddress1 = 64;
|
||||
hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
|
||||
hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
|
||||
|
@ -192,6 +192,9 @@ void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef* hfdcan)
|
||||
GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN1;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/* FDCAN1 interrupt Init */
|
||||
HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, 0, 0);
|
||||
HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn);
|
||||
/* USER CODE BEGIN FDCAN1_MspInit 1 */
|
||||
|
||||
/* USER CODE END FDCAN1_MspInit 1 */
|
||||
@ -221,6 +224,8 @@ void HAL_FDCAN_MspDeInit(FDCAN_HandleTypeDef* hfdcan)
|
||||
*/
|
||||
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
|
||||
|
||||
/* FDCAN1 interrupt DeInit */
|
||||
HAL_NVIC_DisableIRQ(FDCAN1_IT0_IRQn);
|
||||
/* USER CODE BEGIN FDCAN1_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END FDCAN1_MspDeInit 1 */
|
||||
|
@ -55,6 +55,7 @@
|
||||
/* USER CODE END 0 */
|
||||
|
||||
/* External variables --------------------------------------------------------*/
|
||||
extern FDCAN_HandleTypeDef hfdcan1;
|
||||
extern I2C_HandleTypeDef hi2c2;
|
||||
/* USER CODE BEGIN EV */
|
||||
|
||||
@ -198,6 +199,20 @@ void SysTick_Handler(void)
|
||||
/* please refer to the startup file (startup_stm32g4xx.s). */
|
||||
/******************************************************************************/
|
||||
|
||||
/**
|
||||
* @brief This function handles FDCAN1 interrupt 0.
|
||||
*/
|
||||
void FDCAN1_IT0_IRQHandler(void)
|
||||
{
|
||||
/* USER CODE BEGIN FDCAN1_IT0_IRQn 0 */
|
||||
|
||||
/* USER CODE END FDCAN1_IT0_IRQn 0 */
|
||||
HAL_FDCAN_IRQHandler(&hfdcan1);
|
||||
/* USER CODE BEGIN FDCAN1_IT0_IRQn 1 */
|
||||
|
||||
/* USER CODE END FDCAN1_IT0_IRQn 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief This function handles I2C2 event interrupt / I2C2 wake-up interrupt through EXTI line 24.
|
||||
*/
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include "main.h"
|
||||
#include "state.h"
|
||||
#include "stm32g4xx_hal_gpio.h"
|
||||
#include "vehicle.h"
|
||||
|
||||
void HAL_GPIO_EXTI_Callback(uint16_t pin) {
|
||||
Event ev;
|
||||
@ -60,9 +61,7 @@ void handle_button_press_mission_select(const ButtonPressEvent *ev) {
|
||||
case BTN_PRESS_R2D:
|
||||
break;
|
||||
case BTN_PRESS_OK:
|
||||
stw_state.view_state.ami.current_mission =
|
||||
stw_state.view_state.mission_select.selection;
|
||||
stw_state.view = VIEW_AMI;
|
||||
vehicle_send_mission_select(stw_state.view_state.mission_select.selection);
|
||||
break;
|
||||
case BTN_PRESS_NEXT: {
|
||||
Mission *selection = &stw_state.view_state.mission_select.selection;
|
||||
|
105
Core/Src/vehicle.c
Normal file
105
Core/Src/vehicle.c
Normal file
@ -0,0 +1,105 @@
|
||||
#include "vehicle.h"
|
||||
#include "main.h"
|
||||
#include "state.h"
|
||||
#include "stm32g4xx_hal_def.h"
|
||||
#include "stm32g4xx_hal_fdcan.h"
|
||||
|
||||
FDCAN_HandleTypeDef *can;
|
||||
|
||||
void handle_as_mission_fb(FDCAN_RxHeaderTypeDef *header, uint8_t *data);
|
||||
|
||||
void vehicle_init(FDCAN_HandleTypeDef *handle) {
|
||||
can = handle;
|
||||
|
||||
// RX Filter
|
||||
FDCAN_FilterTypeDef filter;
|
||||
filter.IdType = FDCAN_STANDARD_ID;
|
||||
filter.FilterIndex = 0;
|
||||
filter.FilterType = FDCAN_FILTER_MASK;
|
||||
filter.FilterConfig = FDCAN_FILTER_TO_RXFIFO0;
|
||||
filter.FilterID1 = CAN_ID_AS_MISSION_FB;
|
||||
filter.FilterID2 = filter.FilterID1;
|
||||
if (HAL_FDCAN_ConfigFilter(can, &filter) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
// Global filter: Filter all remote frames with STD & EXT ID, reject non
|
||||
// matching frames with STD & EXT ID
|
||||
|
||||
// TODO: What does that mean?
|
||||
if (HAL_FDCAN_ConfigGlobalFilter(can, FDCAN_REJECT, FDCAN_REJECT,
|
||||
FDCAN_FILTER_REMOTE,
|
||||
FDCAN_FILTER_REMOTE) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
// Start FDCAN module
|
||||
if (HAL_FDCAN_Start(can) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
// Enable RX interrupt
|
||||
if (HAL_FDCAN_ActivateNotification(can, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0) !=
|
||||
HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
}
|
||||
|
||||
void vehicle_send_mission_select(Mission mission) {
|
||||
// TODO: Automatically resend this until it's acknowledged
|
||||
FDCAN_TxHeaderTypeDef header;
|
||||
header.Identifier = CAN_ID_MISSION_SELECT;
|
||||
header.IdType = FDCAN_STANDARD_ID;
|
||||
header.TxFrameType = FDCAN_DATA_FRAME;
|
||||
header.DataLength = FDCAN_DLC_BYTES_1;
|
||||
header.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
|
||||
header.BitRateSwitch = FDCAN_BRS_OFF;
|
||||
header.FDFormat = FDCAN_CLASSIC_CAN;
|
||||
header.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
|
||||
header.MessageMarker = 0;
|
||||
|
||||
uint8_t data[1];
|
||||
data[0] = mission;
|
||||
if (HAL_FDCAN_AddMessageToTxFifoQ(can, &header, data) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
}
|
||||
|
||||
/* BEGIN CAN MESSAGE HANDLERS { */
|
||||
|
||||
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *handle,
|
||||
uint32_t interrupt_flags) {
|
||||
if (!(interrupt_flags & FDCAN_IT_RX_FIFO0_NEW_MESSAGE)) {
|
||||
return;
|
||||
}
|
||||
|
||||
static FDCAN_RxHeaderTypeDef header;
|
||||
static uint8_t data[64];
|
||||
|
||||
if (HAL_FDCAN_GetRxMessage(can, FDCAN_RX_FIFO0, &header, data) != HAL_OK) {
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
if (header.IdType != FDCAN_STANDARD_ID) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (header.Identifier) {
|
||||
case CAN_ID_AS_MISSION_FB:
|
||||
handle_as_mission_fb(&header, data);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void handle_as_mission_fb(FDCAN_RxHeaderTypeDef *header, uint8_t *data) {
|
||||
Mission mission_fb = data[0];
|
||||
if (mission_fb == MISSION_NONE) {
|
||||
return;
|
||||
}
|
||||
|
||||
stw_state.view_state.ami.current_mission = mission_fb;
|
||||
|
||||
stw_state.view = VIEW_AMI;
|
||||
}
|
||||
|
||||
/* } END CAN MESSAGE HANDLERS */
|
2
Makefile
2
Makefile
@ -1,5 +1,5 @@
|
||||
##########################################################################################################################
|
||||
# File automatically-generated by tool: [projectgenerator] version: [3.16.0] date: [Sat May 28 00:49:24 CEST 2022]
|
||||
# File automatically-generated by tool: [projectgenerator] version: [3.16.0] date: [Sat May 28 19:05:06 CEST 2022]
|
||||
##########################################################################################################################
|
||||
|
||||
# ------------------------------------------------
|
||||
|
@ -44,6 +44,7 @@ Core/Src/stm32g4xx_hal_msp.c \
|
||||
Core/Src/stm32g4xx_it.c \
|
||||
Core/Src/system_stm32g4xx.c \
|
||||
Core/Src/user_inputs.c \
|
||||
Core/Src/vehicle.c \
|
||||
Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c \
|
||||
Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_adc.c \
|
||||
Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_adc_ex.c \
|
||||
|
@ -6,10 +6,23 @@ ADC1.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.Rank-0\#ChannelRegularConversion=1
|
||||
ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_2CYCLES_5
|
||||
ADC1.master=1
|
||||
FDCAN1.AutoRetransmission=ENABLE
|
||||
FDCAN1.DataSyncJumpWidth=4
|
||||
FDCAN1.DataTimeSeg1=5
|
||||
FDCAN1.DataTimeSeg2=4
|
||||
FDCAN1.FrameFormat=FDCAN_FRAME_FD_BRS
|
||||
FDCAN1.IPParameters=StdFiltersNbr,Mode,FrameFormat,AutoRetransmission,TransmitPause,NominalSyncJumpWidth,NominalTimeSeg1,NominalTimeSeg2,DataSyncJumpWidth,DataTimeSeg1,DataTimeSeg2
|
||||
FDCAN1.Mode=FDCAN_MODE_NORMAL
|
||||
FDCAN1.NominalSyncJumpWidth=16
|
||||
FDCAN1.NominalTimeSeg1=63
|
||||
FDCAN1.NominalTimeSeg2=16
|
||||
FDCAN1.StdFiltersNbr=2
|
||||
FDCAN1.TransmitPause=ENABLE
|
||||
File.Version=6
|
||||
GPIO.groupedBy=
|
||||
I2C2.IPParameters=OwnAddress
|
||||
GPIO.groupedBy=Group By Peripherals
|
||||
I2C2.IPParameters=OwnAddress,Timing
|
||||
I2C2.OwnAddress=0x20
|
||||
I2C2.Timing=0x10909CEC
|
||||
KeepUserPlacement=false
|
||||
Mcu.CPN=STM32G441CBT6
|
||||
Mcu.Family=STM32G4
|
||||
@ -56,6 +69,7 @@ MxDb.Version=DB.6.0.50
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.EXTI15_10_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
NVIC.FDCAN1_IT0_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
NVIC.ForceEnableDMAVector=true
|
||||
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true
|
||||
NVIC.I2C2_EV_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
|
||||
@ -185,45 +199,48 @@ ProjectManager.TargetToolchain=Makefile
|
||||
ProjectManager.ToolChainLocation=
|
||||
ProjectManager.UnderRoot=false
|
||||
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_ADC1_Init-ADC1-false-HAL-true,4-MX_FDCAN1_Init-FDCAN1-false-HAL-true,5-MX_I2C2_Init-I2C2-false-HAL-true
|
||||
RCC.AHBFreq_Value=16000000
|
||||
RCC.APB1Freq_Value=16000000
|
||||
RCC.APB1TimFreq_Value=16000000
|
||||
RCC.APB2Freq_Value=16000000
|
||||
RCC.APB2TimFreq_Value=16000000
|
||||
RCC.ADC12Freq_Value=80000000
|
||||
RCC.AHBFreq_Value=80000000
|
||||
RCC.APB1Freq_Value=80000000
|
||||
RCC.APB1TimFreq_Value=80000000
|
||||
RCC.APB2Freq_Value=80000000
|
||||
RCC.APB2TimFreq_Value=80000000
|
||||
RCC.CRSFreq_Value=48000000
|
||||
RCC.CortexFreq_Value=16000000
|
||||
RCC.CortexFreq_Value=80000000
|
||||
RCC.EXTERNAL_CLOCK_VALUE=12288000
|
||||
RCC.FCLKCortexFreq_Value=16000000
|
||||
RCC.FDCANFreq_Value=16000000
|
||||
RCC.FCLKCortexFreq_Value=80000000
|
||||
RCC.FDCANFreq_Value=80000000
|
||||
RCC.FamilyName=M
|
||||
RCC.HCLKFreq_Value=16000000
|
||||
RCC.HCLKFreq_Value=80000000
|
||||
RCC.HSE_VALUE=8000000
|
||||
RCC.HSI48_VALUE=48000000
|
||||
RCC.HSI_VALUE=16000000
|
||||
RCC.I2C1Freq_Value=16000000
|
||||
RCC.I2C2Freq_Value=16000000
|
||||
RCC.I2C3Freq_Value=16000000
|
||||
RCC.I2SFreq_Value=16000000
|
||||
RCC.IPParameters=AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,EXTERNAL_CLOCK_VALUE,FCLKCortexFreq_Value,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2SFreq_Value,LPTIM1Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSE_VALUE,LSI_VALUE,MCO1PinFreq_Value,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PWRFreq_Value,RNGFreq_Value,SAI1Freq_Value,SYSCLKFreq_VALUE,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value
|
||||
RCC.LPTIM1Freq_Value=16000000
|
||||
RCC.LPUART1Freq_Value=16000000
|
||||
RCC.I2C1Freq_Value=80000000
|
||||
RCC.I2C2Freq_Value=80000000
|
||||
RCC.I2C3Freq_Value=80000000
|
||||
RCC.I2SFreq_Value=80000000
|
||||
RCC.IPParameters=ADC12Freq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,EXTERNAL_CLOCK_VALUE,FCLKCortexFreq_Value,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2SFreq_Value,LPTIM1Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSE_VALUE,LSI_VALUE,MCO1PinFreq_Value,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PWRFreq_Value,RNGFreq_Value,SAI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value
|
||||
RCC.LPTIM1Freq_Value=80000000
|
||||
RCC.LPUART1Freq_Value=80000000
|
||||
RCC.LSCOPinFreq_Value=32000
|
||||
RCC.LSE_VALUE=32768
|
||||
RCC.LSI_VALUE=32000
|
||||
RCC.MCO1PinFreq_Value=16000000
|
||||
RCC.PLLPoutputFreq_Value=64000000
|
||||
RCC.PLLQoutputFreq_Value=64000000
|
||||
RCC.PLLRCLKFreq_Value=64000000
|
||||
RCC.PWRFreq_Value=16000000
|
||||
RCC.RNGFreq_Value=64000000
|
||||
RCC.SAI1Freq_Value=16000000
|
||||
RCC.SYSCLKFreq_VALUE=16000000
|
||||
RCC.USART1Freq_Value=16000000
|
||||
RCC.USART2Freq_Value=16000000
|
||||
RCC.USART3Freq_Value=16000000
|
||||
RCC.USBFreq_Value=64000000
|
||||
RCC.PLLN=10
|
||||
RCC.PLLPoutputFreq_Value=80000000
|
||||
RCC.PLLQoutputFreq_Value=80000000
|
||||
RCC.PLLRCLKFreq_Value=80000000
|
||||
RCC.PWRFreq_Value=80000000
|
||||
RCC.RNGFreq_Value=80000000
|
||||
RCC.SAI1Freq_Value=80000000
|
||||
RCC.SYSCLKFreq_VALUE=80000000
|
||||
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
|
||||
RCC.USART1Freq_Value=80000000
|
||||
RCC.USART2Freq_Value=80000000
|
||||
RCC.USART3Freq_Value=80000000
|
||||
RCC.USBFreq_Value=80000000
|
||||
RCC.VCOInputFreq_Value=16000000
|
||||
RCC.VCOOutputFreq_Value=128000000
|
||||
RCC.VCOOutputFreq_Value=160000000
|
||||
SH.GPXTI12.0=GPIO_EXTI12
|
||||
SH.GPXTI12.ConfNb=1
|
||||
SH.GPXTI13.0=GPIO_EXTI13
|
||||
|
Loading…
x
Reference in New Issue
Block a user