ADD: dummy foc

SIMPLE

CLEAN: cleanup code and add printf handler

FIX: counters

ADD: motor

ENH: temporary disable can

ADD: dummy foc, but creepy work
This commit is contained in:
vanyabeat 2024-02-06 11:32:46 +03:00 committed by Igor Brylyov
parent 3af1d1a710
commit bd7f049b75
20 changed files with 629 additions and 567 deletions

View file

@ -1,55 +0,0 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file can.h
* @brief This file contains all the function prototypes for
* the can.c file
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __CAN_H__
#define __CAN_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
extern CAN_HandleTypeDef hcan1;
extern CAN_HandleTypeDef hcan2;
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_CAN1_Init(void);
void MX_CAN2_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /* __CAN_H__ */

View file

@ -29,13 +29,12 @@ extern "C" {
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx_hal.h"
#include "stm32f4xx_ll_usart.h"
#include "stm32f4xx_ll_rcc.h"
#include "stm32f4xx_ll_system.h"
#include "stm32f4xx_ll_gpio.h"
#include "stm32f4xx_ll_exti.h"
#include "stm32f4xx_ll_bus.h"
#include "stm32f4xx_ll_cortex.h"
#include "stm32f4xx_ll_rcc.h"
#include "stm32f4xx_ll_utils.h"
#include "stm32f4xx_ll_pwr.h"
#include "stm32f4xx_ll_dma.h"
@ -100,6 +99,7 @@ void Error_Handler(void);
typedef int bool;
#define true 1
#define false 0
#define nullptr ((void*)0)
/* USER CODE END Private defines */
#ifdef __cplusplus

View file

@ -39,7 +39,7 @@
#define HAL_ADC_MODULE_ENABLED
/* #define HAL_CRYP_MODULE_ENABLED */
#define HAL_CAN_MODULE_ENABLED
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
@ -64,7 +64,7 @@
/* #define HAL_MMC_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
/* #define HAL_UART_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */

View file

@ -38,6 +38,8 @@ extern TIM_HandleTypeDef htim2;
extern TIM_HandleTypeDef htim3;
extern TIM_HandleTypeDef htim5;
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
@ -45,6 +47,7 @@ extern TIM_HandleTypeDef htim3;
void MX_TIM1_Init(void);
void MX_TIM2_Init(void);
void MX_TIM3_Init(void);
void MX_TIM5_Init(void);
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);

View file

@ -29,19 +29,21 @@ extern "C" {
#include "main.h"
/* USER CODE BEGIN Includes */
#include <errno.h>
#include <stdio.h>
#include <unistd.h>
/* USER CODE END Includes */
extern UART_HandleTypeDef huart1;
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_USART1_UART_Init(void);
void MX_USART2_UART_Init(void);
/* USER CODE BEGIN Prototypes */
void USART1_PutString(char *str);
void SendFloatsWithLL(uint8_t *buffer);
int _write(int file, char *data, int len);
/* USER CODE END Prototypes */
#ifdef __cplusplus

188
firmware/Lib/foc/foc.c Normal file
View file

@ -0,0 +1,188 @@
#include "foc.h"
#include <stdio.h>
#include "pid.h"
foc_motor_t Motor_6208;
float _SIN(float theta) {
return sin(theta);
}
float _COS(float theta) {
return cos(theta);
}
#define SQRT_3 1.73205080757f
void get_Angle(foc_motor_t *__obj, float AbsoulteAngle) {
__obj->machine_angle = AbsoulteAngle - __obj->Encoder_ZeroPoint;
if (__obj->machine_angle < 0) {
__obj->machine_angle += (2 * PI);
}
__obj->electron_angle = __obj->polar_pair * __obj->machine_angle;
}
// Feedback Part
void Current_Sample(foc_motor_t *__obj) {}
void Clark_Trans(foc_motor_t *__obj) {}
void Park_Trans(foc_motor_t *__obj) {}
void Inv_Park_Trans(foc_motor_t *__obj) {
float theta = __obj->electron_angle;
__obj->inv_park_U_alpha = _COS(theta) * __obj->current_loop_Ud - _SIN(theta) * __obj->current_loop_Uq;
__obj->inv_park_U_beta = _SIN(theta) * __obj->current_loop_Ud + _COS(theta) * __obj->current_loop_Uq;
}
/// @brief Функция преобразования вектора напряжения в ШИМ сигнал для управления мотором
/// @param __obj
/// @param htim
void SVPWM_Trans(foc_motor_t *__obj, TIM_HandleTypeDef *htim) {
// float Udc = sqrtf(powf(__obj->inv_park_U_alpha, 2) + powf(__obj->inv_park_U_beta, 2)); // 总电压向量模值,即输出电压大小
float Udc = __obj->Udc;
float Ual = __obj->inv_park_U_alpha, Ubt = __obj->inv_park_U_beta;
float Ts = 2399.0f;
float X, Y, Z;
uint8_t A, B, C, N; // нужно ли оценивать сектор в котором находится вектор
float Ta, Tb, Tc, t1, t2; // промежутки времени для каждого сектора
X = SQRT_3 * Ts * Ubt / Udc;
Y = SQRT_3 * Ts * (SQRT_3 * Ual + Ubt) / Udc / 2;
Z = SQRT_3 * Ts * (-SQRT_3 * Ual + Ubt) / Udc / 2;
if (Ubt < -SQRT_3 * Ual) A = 1; else A = 0;
if (Ubt < SQRT_3 * Ual) B = 1; else B = 0;
if (Ubt > 0) C = 1; else C = 0;
N = 4 * A + 2 * B + C;
if (N == 3) {
t1 = -Z;
t2 = X;
Ta = 0.5f * (Ts - t1 - t2);
Tb = Ta + t1;
Tc = Tb + t2;
__obj->svpwm_Ua = (uint16_t) (Ts - Ta);
__obj->svpwm_Ub = (uint16_t) (Ts - Tb);
__obj->svpwm_Uc = (uint16_t) (Ts - Tc);
} else if (N == 1) {
t1 = Z;
t2 = Y;
Ta = 0.5f * (Ts - t1 - t2);
Tb = Ta + t1;
Tc = Tb + t2;
__obj->svpwm_Ua = (uint16_t) (Ts - Tb);
__obj->svpwm_Ub = (uint16_t) (Ts - Ta);
__obj->svpwm_Uc = (uint16_t) (Ts - Tc);
} else if (N == 5) {
t1 = X;
t2 = -Y;
Ta = 0.5f * (Ts - t1 - t2);
Tb = Ta + t1;
Tc = Tb + t2;
__obj->svpwm_Ua = (uint16_t) (Ts - Tc);
__obj->svpwm_Ub = (uint16_t) (Ts - Ta);
__obj->svpwm_Uc = (uint16_t) (Ts - Tb);
} else if (N == 4) {
t1 = -X;
t2 = Z;
Ta = 0.5f * (Ts - t1 - t2);
Tb = Ta + t1;
Tc = Tb + t2;
__obj->svpwm_Ua = (uint16_t) (Ts - Tc);
__obj->svpwm_Ub = (uint16_t) (Ts - Tb);
__obj->svpwm_Uc = (uint16_t) (Ts - Ta);
} else if (N == 6) {
t1 = -Y;
t2 = -Z;
Ta = 0.5f * (Ts - t1 - t2);
Tb = Ta + t1;
Tc = Tb + t2;
__obj->svpwm_Ua = (uint16_t) (Ts - Tb);
__obj->svpwm_Ub = (uint16_t) (Ts - Tc);
__obj->svpwm_Uc = (uint16_t) (Ts - Ta);
} else {
t1 = Y;
t2 = -X;
Ta = 0.5f * (Ts - t1 - t2);
Tb = Ta + t1;
Tc = Tb + t2;
__obj->svpwm_Ua = (uint16_t) (Ts - Ta);
__obj->svpwm_Ub = (uint16_t) (Ts - Tc);
__obj->svpwm_Uc = (uint16_t) (Ts - Tb);
}
__obj->set_pwm(htim, __obj->svpwm_Ua, __obj->svpwm_Ub, __obj->svpwm_Uc);
}
void set_torque(foc_motor_t *__obj, float Uq) {
__obj->current_loop_Ud = 0;
__obj->current_loop_Uq = Uq;
}
/// @brief Функция обработки границы для углов и токов
/// @param ref
/// @param exp
/// @param max
/// @return
float boundary_process(float ref, float exp, float max) {
if (ref - exp >= (max / 2)) {
return ref - max;
} else if (ref - exp <= -max / 2) {
return ref + max;
} else {
return ref;
}
}
pid_type_t position_loop;
void foc_init(foc_motor_t *__obj, float polar_pair, float Encoder_ZP, float Udc, set_pwm_handler set_pwm, get_raw_angle raw_angle) {
__obj->polar_pair = polar_pair;
__obj->machine_angle = 0;
__obj->electron_angle = 0;
__obj->Encoder_ZeroPoint = Encoder_ZP;
__obj->Udc = Udc;
__obj->set_pwm = set_pwm;
__obj->raw_angle = raw_angle;
pid_init(&position_loop, PID_POSITION, 5, 3, 3, __obj->Udc, __obj->Udc * 0.8f);
}
void foc_run(foc_motor_t *__obj, TIM_HandleTypeDef *htim, SPI_HandleTypeDef *hspi) {
get_Angle(__obj, 2.0f * PI * __obj->raw_angle(hspi, NULL) / 1024);
static float T_count = 0;
T_count += 0.07;
// static float target_angle = 1.5*_SIN(T_count) * _SIN(0.05*T_count);//expf(-0.01*T_count);
static float target_angle = 0;//expf(-0.01*T_count);
target_angle = 2.0f * PI * _SIN(T_count);
float angle_bias = boundary_process(__obj->machine_angle, target_angle, 2 * PI);
float torque = pid_calc(&position_loop, angle_bias, target_angle);
set_torque(__obj, torque);
// printf("%.2f, %.2f, %.2f\n", 180 / PI * __obj->Encoder_ZeroPoint, 180 / PI * __obj->machine_angle, target_angle);
// printf("%.2f, %.2f, %.2f\n", angle_bias, target_angle, torque);
Inv_Park_Trans(__obj);
SVPWM_Trans(__obj, htim);
// target_angle += PI / 3;
// printf("%d,%d,%d\n", __obj->svpwm_Ua, __obj->svpwm_Ub, __obj->svpwm_Uc);
printf("Machine Angle: %.2f, Target Angle: %.2f, Torque: %.2f\n", 180 / PI * __obj->machine_angle, 180 / PI * target_angle, torque);
// target_angle += 10;
}

52
firmware/Lib/foc/foc.h Normal file
View file

@ -0,0 +1,52 @@
#pragma once
#include "stm32f4xx_hal.h"
#include <math.h>
#include <stdint.h>
#define PI 3.14159265358979323846f
typedef void (*set_pwm_handler)(TIM_HandleTypeDef *htim, uint32_t phaseA, uint32_t phaseB, uint32_t phaseC);
typedef uint16_t (*get_raw_angle)(SPI_HandleTypeDef *hspi, uint8_t *status);
typedef struct __FOC_MOTOR_CONTROL
{
float polar_pair;
float machine_angle;
float electron_angle;
float Encoder_ZeroPoint;
float Udc;
// output
float current_loop_Ud;
float current_loop_Uq;
float inv_park_U_alpha;
float inv_park_U_beta;
uint16_t svpwm_Ua;
uint16_t svpwm_Ub;
uint16_t svpwm_Uc;
set_pwm_handler set_pwm;
get_raw_angle raw_angle;
#if 0
// input
float Phase_Ia;
float Phase_Ib;
float Phase_Ic;
float clark_I_alpha;
float clark_I_beta;
float park_Id;
float park_Iq;
#endif
} foc_motor_t;
void set_torque(foc_motor_t *__obj, float Uq);
void foc_init(foc_motor_t *__obj, float polar_pair, float Encoder_ZP, float Udc, set_pwm_handler set_pwm, get_raw_angle raw_angle);
void foc_run(foc_motor_t *__obj, TIM_HandleTypeDef *htim, SPI_HandleTypeDef *hspi);
extern foc_motor_t Motor_6208;

View file

@ -0,0 +1,13 @@
#include "helpers.h"
#include <string.h>
void print_for_debug(UART_HandleTypeDef *huart1, float values[4]) {
const uint8_t size = 4 + (sizeof(float) * 4);
char buffer[4 + (sizeof(float) * 4)];
buffer[0] = '\xDE';
buffer[1] = '\xAD';
memcpy(&buffer[2], values, sizeof(float) * 4);
buffer[2 + (sizeof(float) * 4)] = '\xBE';
buffer[2 + (sizeof(float) * 4) + 1] = '\xAF';
HAL_UART_Transmit(huart1, (uint8_t *) buffer, size, HAL_MAX_DELAY);
}

View file

@ -0,0 +1,4 @@
#pragma once
#include "stm32f4xx_hal.h"
void print_for_debug(UART_HandleTypeDef *huart1, float values[4]);

View file

@ -0,0 +1,22 @@
#include "motor.h"
void start_motor_control(TIM_HandleTypeDef *htim, uint32_t channel1, uint32_t channel2, uint32_t channel3)
{
HAL_TIM_PWM_Start(htim, channel1);
HAL_TIM_PWM_Start(htim, channel2);
HAL_TIM_PWM_Start(htim, channel3);
}
void stop_motor_control(TIM_HandleTypeDef *htim, uint32_t channel1, uint32_t channel2, uint32_t channel3)
{
HAL_TIM_PWM_Stop(htim, channel1);
HAL_TIM_PWM_Stop(htim, channel2);
HAL_TIM_PWM_Stop(htim, channel3);
}
void set_pwm(TIM_HandleTypeDef *htim, uint32_t phaseA, uint32_t phaseB, uint32_t phaseC)
{
__HAL_TIM_SET_COMPARE(htim, TIM_CHANNEL_1, phaseA);
__HAL_TIM_SET_COMPARE(htim, TIM_CHANNEL_2, phaseB);
__HAL_TIM_SET_COMPARE(htim, TIM_CHANNEL_3, phaseC);
}

View file

@ -0,0 +1,8 @@
#pragma once
#include "stm32f4xx_hal.h"
void start_motor_control(TIM_HandleTypeDef *htim, uint32_t channel1, uint32_t channel2, uint32_t channel3);
void stop_motor_control(TIM_HandleTypeDef *htim, uint32_t channel1, uint32_t channel2, uint32_t channel3);
void set_pwm(TIM_HandleTypeDef *htim, uint32_t phaseA, uint32_t phaseB, uint32_t phaseC);

82
firmware/Lib/pid/pid.c Normal file
View file

@ -0,0 +1,82 @@
#include "pid.h"
#include <stdint.h>
#include <stddef.h>
#define LimitMax(input, max) \
{ \
if (input > max) \
{ \
input = max; \
} \
else if (input < -max) \
{ \
input = -max; \
} \
}
void pid_init(pid_type_t *pid, uint8_t mode, float Kp, float Ki, float Kd, float max_out, float max_iout)
{
if (pid == NULL)
{
return;
}
pid->mode = mode;
pid->Kp = Kp;
pid->Ki = Ki;
pid->Kd = Kd;
pid->max_out = max_out;
pid->max_iout = max_iout;
pid->Dbuf[0] = pid->Dbuf[1] = pid->Dbuf[2] = 0.0f;
pid->error[0] = pid->error[1] = pid->error[2] = pid->Pout = pid->Iout = pid->Dout = pid->out = 0.0f;
}
float pid_calc(pid_type_t *pid, float ref, float set)
{
if (pid == NULL)
{
return 0.0f;
}
pid->error[2] = pid->error[1];
pid->error[1] = pid->error[0];
pid->set = set;
pid->fdb = ref;
pid->error[0] = set - ref;
if (pid->mode == PID_POSITION)
{
pid->Pout = pid->Kp * pid->error[0];
pid->Iout += pid->Ki * pid->error[0];
pid->Dbuf[2] = pid->Dbuf[1];
pid->Dbuf[1] = pid->Dbuf[0];
pid->Dbuf[0] = (pid->error[0] - pid->error[1]);
pid->Dout = pid->Kd * pid->Dbuf[0];
LimitMax(pid->Iout, pid->max_iout);
pid->out = pid->Pout + pid->Iout + pid->Dout;
LimitMax(pid->out, pid->max_out);
}
else if (pid->mode == PID_DELTA)
{
pid->Pout = pid->Kp * (pid->error[0] - pid->error[1]);
pid->Iout = pid->Ki * pid->error[0];
pid->Dbuf[2] = pid->Dbuf[1];
pid->Dbuf[1] = pid->Dbuf[0];
pid->Dbuf[0] = (pid->error[0] - 2.0f * pid->error[1] + pid->error[2]);
pid->Dout = pid->Kd * pid->Dbuf[0];
pid->out += pid->Pout + pid->Iout + pid->Dout;
LimitMax(pid->out, pid->max_out);
}
return pid->out;
}
void pid_clear(pid_type_t *pid)
{
if (pid == NULL)
{
return;
}
pid->error[0] = pid->error[1] = pid->error[2] = 0.0f;
pid->Dbuf[0] = pid->Dbuf[1] = pid->Dbuf[2] = 0.0f;
pid->out = pid->Pout = pid->Iout = pid->Dout = 0.0f;
pid->fdb = pid->set = 0.0f;
}

34
firmware/Lib/pid/pid.h Normal file
View file

@ -0,0 +1,34 @@
#pragma once
#include "stdint.h"
enum PID_MODE
{
PID_POSITION = 0,
PID_DELTA
};
typedef struct pid_type
{
uint8_t mode;
// PID parameters
float Kp;
float Ki;
float Kd;
float max_out; // max output
float max_iout; // max integral output
float set;
float fdb;
float out;
float Pout;
float Iout;
float Dout;
float Dbuf[3]; // diff buffer 0 save now 1 save last 2 save last last
float error[3]; //
} pid_type_t;
extern void pid_init(pid_type_t *pid, uint8_t mode, float Kp, float Ki, float Kd, float max_out, float max_iout);
extern float pid_calc(pid_type_t *pid, float ref, float set);
extern void pid_clear(pid_type_t *pid);

View file

@ -1,215 +0,0 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file can.c
* @brief This file provides code for the configuration
* of the CAN instances.
******************************************************************************
* @attention
*
* Copyright (c) 2024 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "can.h"
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
CAN_HandleTypeDef hcan1;
CAN_HandleTypeDef hcan2;
/* CAN1 init function */
void MX_CAN1_Init(void)
{
/* USER CODE BEGIN CAN1_Init 0 */
/* USER CODE END CAN1_Init 0 */
/* USER CODE BEGIN CAN1_Init 1 */
/* USER CODE END CAN1_Init 1 */
hcan1.Instance = CAN1;
hcan1.Init.Prescaler = 5;
hcan1.Init.Mode = CAN_MODE_LOOPBACK;
hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ;
hcan1.Init.TimeSeg1 = CAN_BS1_7TQ;
hcan1.Init.TimeSeg2 = CAN_BS2_1TQ;
hcan1.Init.TimeTriggeredMode = DISABLE;
hcan1.Init.AutoBusOff = ENABLE;
hcan1.Init.AutoWakeUp = DISABLE;
hcan1.Init.AutoRetransmission = ENABLE;
hcan1.Init.ReceiveFifoLocked = DISABLE;
hcan1.Init.TransmitFifoPriority = DISABLE;
if (HAL_CAN_Init(&hcan1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN CAN1_Init 2 */
/* USER CODE END CAN1_Init 2 */
}
/* CAN2 init function */
void MX_CAN2_Init(void)
{
/* USER CODE BEGIN CAN2_Init 0 */
/* USER CODE END CAN2_Init 0 */
/* USER CODE BEGIN CAN2_Init 1 */
/* USER CODE END CAN2_Init 1 */
hcan2.Instance = CAN2;
hcan2.Init.Prescaler = 5;
hcan2.Init.Mode = CAN_MODE_NORMAL;
hcan2.Init.SyncJumpWidth = CAN_SJW_1TQ;
hcan2.Init.TimeSeg1 = CAN_BS1_7TQ;
hcan2.Init.TimeSeg2 = CAN_BS2_1TQ;
hcan2.Init.TimeTriggeredMode = DISABLE;
hcan2.Init.AutoBusOff = ENABLE;
hcan2.Init.AutoWakeUp = DISABLE;
hcan2.Init.AutoRetransmission = ENABLE;
hcan2.Init.ReceiveFifoLocked = DISABLE;
hcan2.Init.TransmitFifoPriority = DISABLE;
if (HAL_CAN_Init(&hcan2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN CAN2_Init 2 */
/* USER CODE END CAN2_Init 2 */
}
static uint32_t HAL_RCC_CAN1_CLK_ENABLED=0;
void HAL_CAN_MspInit(CAN_HandleTypeDef* canHandle)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(canHandle->Instance==CAN1)
{
/* USER CODE BEGIN CAN1_MspInit 0 */
/* USER CODE END CAN1_MspInit 0 */
/* CAN1 clock enable */
HAL_RCC_CAN1_CLK_ENABLED++;
if(HAL_RCC_CAN1_CLK_ENABLED==1){
__HAL_RCC_CAN1_CLK_ENABLE();
}
__HAL_RCC_GPIOB_CLK_ENABLE();
/**CAN1 GPIO Configuration
PB8 ------> CAN1_RX
PB9 ------> CAN1_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_9;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN CAN1_MspInit 1 */
/* USER CODE END CAN1_MspInit 1 */
}
else if(canHandle->Instance==CAN2)
{
/* USER CODE BEGIN CAN2_MspInit 0 */
/* USER CODE END CAN2_MspInit 0 */
/* CAN2 clock enable */
__HAL_RCC_CAN2_CLK_ENABLE();
HAL_RCC_CAN1_CLK_ENABLED++;
if(HAL_RCC_CAN1_CLK_ENABLED==1){
__HAL_RCC_CAN1_CLK_ENABLE();
}
__HAL_RCC_GPIOB_CLK_ENABLE();
/**CAN2 GPIO Configuration
PB12 ------> CAN2_RX
PB13 ------> CAN2_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_13;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN2;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN CAN2_MspInit 1 */
/* USER CODE END CAN2_MspInit 1 */
}
}
void HAL_CAN_MspDeInit(CAN_HandleTypeDef* canHandle)
{
if(canHandle->Instance==CAN1)
{
/* USER CODE BEGIN CAN1_MspDeInit 0 */
/* USER CODE END CAN1_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_CAN1_CLK_ENABLED--;
if(HAL_RCC_CAN1_CLK_ENABLED==0){
__HAL_RCC_CAN1_CLK_DISABLE();
}
/**CAN1 GPIO Configuration
PB8 ------> CAN1_RX
PB9 ------> CAN1_TX
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_8|GPIO_PIN_9);
/* USER CODE BEGIN CAN1_MspDeInit 1 */
/* USER CODE END CAN1_MspDeInit 1 */
}
else if(canHandle->Instance==CAN2)
{
/* USER CODE BEGIN CAN2_MspDeInit 0 */
/* USER CODE END CAN2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CAN2_CLK_DISABLE();
HAL_RCC_CAN1_CLK_ENABLED--;
if(HAL_RCC_CAN1_CLK_ENABLED==0){
__HAL_RCC_CAN1_CLK_DISABLE();
}
/**CAN2 GPIO Configuration
PB12 ------> CAN2_RX
PB13 ------> CAN2_TX
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_12|GPIO_PIN_13);
/* USER CODE BEGIN CAN2_MspDeInit 1 */
/* USER CODE END CAN2_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View file

@ -38,6 +38,8 @@
* Output
* EVENT_OUT
* EXTI
PB8 ------> CAN1_RX
PB9 ------> CAN1_TX
*/
void MX_GPIO_Init(void)
{
@ -47,8 +49,8 @@ void MX_GPIO_Init(void)
/* GPIO Ports Clock Enable */
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOH);
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOC);
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA);
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOB);
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA);
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOD);
/**/
@ -111,6 +113,24 @@ void MX_GPIO_Init(void)
GPIO_InitStruct.Pull = LL_GPIO_PULL_DOWN;
LL_GPIO_Init(spi1_cs_GPIO_Port, &GPIO_InitStruct);
/**/
GPIO_InitStruct.Pin = LL_GPIO_PIN_8;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_UP;
GPIO_InitStruct.Alternate = LL_GPIO_AF_9;
LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/**/
GPIO_InitStruct.Pin = LL_GPIO_PIN_9;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
GPIO_InitStruct.Alternate = LL_GPIO_AF_9;
LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
/* USER CODE BEGIN 2 */

View file

@ -19,7 +19,6 @@
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "adc.h"
#include "can.h"
#include "spi.h"
#include "tim.h"
#include "usart.h"
@ -27,7 +26,14 @@
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include <errno.h>
#include <helpers.h>
#include <math.h>
#include <stdio.h>
#include <sys/unistd.h>
#include <motor.h>
#include <foc.h>
#include <pid.h>
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
@ -37,6 +43,7 @@
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
@ -59,50 +66,7 @@ static void MX_NVIC_Init(void);
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
#define PI 3.14159265359f
#define TWO_PI (2 * PI)
#define MAX_CURRENT 3.0f // Max phase current
#define POLE_PAIRS 3 // Motor's number of pole pairs
#define TARGET_ANGLE 120.0f // Target angle in degrees
#define TARGET_ANGLE_RAD (TARGET_ANGLE * PI / 180.0f) //
void StartMotorControl(void) {
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1);
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2);
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3);
}
void StopMotorControl(void) {
HAL_TIM_PWM_Stop(&htim1, TIM_CHANNEL_1);
HAL_TIM_PWM_Stop(&htim1, TIM_CHANNEL_2);
HAL_TIM_PWM_Stop(&htim1, TIM_CHANNEL_3);
}
void UpdateMotor(float a, float b, float c) {
uint32_t pwm_value_a = (uint32_t)((a / MAX_CURRENT) * ((float)htim1.Init.Period));
uint32_t pwm_value_b = (uint32_t)((b / MAX_CURRENT) * ((float)htim1.Init.Period));
uint32_t pwm_value_c = (uint32_t)((c / MAX_CURRENT) * ((float)htim1.Init.Period));
__HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, pwm_value_a);
__HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, pwm_value_b);
__HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, pwm_value_c);
}
void RunMotorToAngle(float rotorAngle) {
float phaseA, phaseB, phaseC;
float rotorRadians = fmod(rotorAngle, 360.0f) * (PI / 180.0f);
if (rotorAngle >= TARGET_ANGLE) {
// StopMotor(); // Stop the motor
}
phaseA = MAX_CURRENT * sinf(rotorRadians);
phaseB = MAX_CURRENT * sinf(rotorRadians - TWO_PI / 3.0f);
phaseC = MAX_CURRENT * sinf(rotorRadians + TWO_PI / 3.0f);
// char buf[100];
// /// print all phases currents
// sprintf(buf, "Phase A B C: %f %f %f\n", phaseA, phaseB, phaseC);
// USART1_PutString(buf);
UpdateMotor(phaseA, phaseB, phaseC);
}
/* USER CODE END 0 */
/**
@ -135,96 +99,35 @@ int main(void)
MX_GPIO_Init();
MX_TIM1_Init();
MX_USART1_UART_Init();
MX_USART2_UART_Init();
MX_TIM2_Init();
MX_SPI2_Init();
MX_CAN1_Init();
MX_CAN2_Init();
MX_TIM3_Init();
MX_ADC2_Init();
MX_TIM5_Init();
/* Initialize interrupts */
MX_NVIC_Init();
/* USER CODE BEGIN 2 */
AS5045_CS_Init();
/// INIT DRV8313
/// INIT DRV8313
HAL_GPIO_WritePin(DRV_RESET_GPIO_Port, DRV_RESET_Pin, GPIO_PIN_SET);
HAL_GPIO_WritePin(DRV_SLEEP_GPIO_Port, DRV_SLEEP_Pin, GPIO_PIN_SET);
HAL_Delay(100);
HAL_GPIO_WritePin(EN_U_GPIO_Port, EN_U_Pin, GPIO_PIN_SET);
HAL_GPIO_WritePin(EN_V_GPIO_Port, EN_V_Pin, GPIO_PIN_SET);
HAL_GPIO_WritePin(EN_W_GPIO_Port, EN_W_Pin, GPIO_PIN_SET);
/* USER CODE END 2 */
start_motor_control(&htim1, TIM_CHANNEL_1, TIM_CHANNEL_2, TIM_CHANNEL_3);
foc_init(&Motor_6208, 12, 0.0, 24.0, set_pwm, AS5045_ReadAngle);
/* Infinite loop */
/* USER CODE BEGIN WHILE */
float angle_values[200];
uint8_t angle_index = 0;
float ADC123_ANGLE[4] = {0, 0, 0, 0};
StartMotorControl();
while (1)
{
// Ready to MERGE
RunMotorToAngle(ADC123_ANGLE[3] + 10.0f);
if (flag_10kHz == SET)
{
foc_run(&Motor_6208, &htim1, &hspi2);
flag_10kHz = RESET;
// Do something every 10 kHz
// BLINK LED1
HAL_GPIO_TogglePin(LED1_GPIO_Port, LED1_Pin);
uint8_t status = 0;
uint16_t angle = AS5045_ReadAngle(&hspi2, &status);
if (angle_index == 200)
{
angle_index = 0;
float average = 0;
for (int i = 0; i < 200; i++)
{
average += angle_values[i];
}
average /= 200.0;
ADC123_ANGLE[0] = GetCurrentFromADC(ReadADCValue(&hadc2, ADC_CHANNEL_15)); // Read ADC
ADC123_ANGLE[1] = GetCurrentFromADC(ReadADCValue(&hadc2, ADC_CHANNEL_8)); // Read ADC
ADC123_ANGLE[2] = GetCurrentFromADC(ReadADCValue(&hadc2, ADC_CHANNEL_9)); // Read ADC
ADC123_ANGLE[3] = average;
USART1_PutString("\xDE\xAD");
SendFloatsWithLL((uint8_t *)ADC123_ANGLE);
USART1_PutString("\xBE\xAF");
// break;
}
if (status == 0)
{
float degrees = NormalizeToDegrees(angle);
angle_values[angle_index] = degrees;
angle_index++;
}
else
{
// Handle the error
if (status & AS5040_DIAG_OC_FAULT)
{
// Offset Compensation not finished
}
if (status & AS5040_DIAG_CO_FAULT)
{
// Cordic Overflow error
}
if (status & AS5040_DIAG_LIN_FAULT)
{
// Linearity Alarm error
}
// StopMotorControl();
}
// sprintf(buf, "Average: %f\r\n", degrees);
// USART1_PutString(buf);
// HAL_Delay(100);
}
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */

View file

@ -22,6 +22,7 @@
#include "stm32f4xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include <foc.h>
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/

View file

@ -27,6 +27,7 @@
TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim2;
TIM_HandleTypeDef htim3;
TIM_HandleTypeDef htim5;
/* TIM1 init function */
void MX_TIM1_Init(void)
@ -197,6 +198,46 @@ void MX_TIM3_Init(void)
}
/* USER CODE END TIM3_Init 2 */
}
/* TIM5 init function */
void MX_TIM5_Init(void)
{
/* USER CODE BEGIN TIM5_Init 0 */
/* USER CODE END TIM5_Init 0 */
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM5_Init 1 */
/* USER CODE END TIM5_Init 1 */
htim5.Instance = TIM5;
htim5.Init.Prescaler = 0;
htim5.Init.CounterMode = TIM_COUNTERMODE_UP;
htim5.Init.Period = 4294967295;
htim5.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim5.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim5) != HAL_OK)
{
Error_Handler();
}
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&htim5, &sClockSourceConfig) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim5, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM5_Init 2 */
/* USER CODE END TIM5_Init 2 */
}
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
@ -239,6 +280,17 @@ void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
/* USER CODE END TIM3_MspInit 1 */
}
else if(tim_baseHandle->Instance==TIM5)
{
/* USER CODE BEGIN TIM5_MspInit 0 */
/* USER CODE END TIM5_MspInit 0 */
/* TIM5 clock enable */
__HAL_RCC_TIM5_CLK_ENABLE();
/* USER CODE BEGIN TIM5_MspInit 1 */
/* USER CODE END TIM5_MspInit 1 */
}
}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
{
@ -316,6 +368,17 @@ void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle)
/* USER CODE END TIM3_MspDeInit 1 */
}
else if(tim_baseHandle->Instance==TIM5)
{
/* USER CODE BEGIN TIM5_MspDeInit 0 */
/* USER CODE END TIM5_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM5_CLK_DISABLE();
/* USER CODE BEGIN TIM5_MspDeInit 1 */
/* USER CODE END TIM5_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */

View file

@ -21,32 +21,11 @@
#include "usart.h"
/* USER CODE BEGIN 0 */
void USART1_PutChar(char ch)
{
while (!LL_USART_IsActiveFlag_TXE(USART1));
LL_USART_TransmitData8(USART1, (uint8_t)ch);
}
void USART1_PutString(char *str)
{
while (*str)
{
USART1_PutChar(*str++);
}
}
void SendFloatsWithLL(uint8_t *buffer)
{
// Send each byte using LL drivers
for (size_t i = 0; i < (sizeof(float) * 4); i++)
{
while (!LL_USART_IsActiveFlag_TXE(USART1)); // Wait for TXE flag to be set
LL_USART_TransmitData8(USART1, buffer[i]); // Transmit byte
}
while (!LL_USART_IsActiveFlag_TC(USART1)); // Wait for TC flag to be set
}
/* USER CODE END 0 */
UART_HandleTypeDef huart1;
/* USART1 init function */
void MX_USART1_UART_Init(void)
@ -56,94 +35,99 @@ void MX_USART1_UART_Init(void)
/* USER CODE END USART1_Init 0 */
LL_USART_InitTypeDef USART_InitStruct = {0};
LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
/* Peripheral clock enable */
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_USART1);
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOB);
/**USART1 GPIO Configuration
PB6 ------> USART1_TX
PB7 ------> USART1_RX
*/
GPIO_InitStruct.Pin = LL_GPIO_PIN_6|LL_GPIO_PIN_7;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
GPIO_InitStruct.Alternate = LL_GPIO_AF_7;
LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN USART1_Init 1 */
/* USER CODE END USART1_Init 1 */
USART_InitStruct.BaudRate = 115200;
USART_InitStruct.DataWidth = LL_USART_DATAWIDTH_8B;
USART_InitStruct.StopBits = LL_USART_STOPBITS_1;
USART_InitStruct.Parity = LL_USART_PARITY_NONE;
USART_InitStruct.TransferDirection = LL_USART_DIRECTION_TX_RX;
USART_InitStruct.HardwareFlowControl = LL_USART_HWCONTROL_NONE;
USART_InitStruct.OverSampling = LL_USART_OVERSAMPLING_16;
LL_USART_Init(USART1, &USART_InitStruct);
LL_USART_ConfigAsyncMode(USART1);
LL_USART_Enable(USART1);
huart1.Instance = USART1;
huart1.Init.BaudRate = 115200;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
if (HAL_UART_Init(&huart1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART1_Init 2 */
/* USER CODE END USART1_Init 2 */
}
/* USART2 init function */
void MX_USART2_UART_Init(void)
void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
{
/* USER CODE BEGIN USART2_Init 0 */
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(uartHandle->Instance==USART1)
{
/* USER CODE BEGIN USART1_MspInit 0 */
/* USER CODE END USART2_Init 0 */
/* USER CODE END USART1_MspInit 0 */
/* USART1 clock enable */
__HAL_RCC_USART1_CLK_ENABLE();
LL_USART_InitTypeDef USART_InitStruct = {0};
__HAL_RCC_GPIOB_CLK_ENABLE();
/**USART1 GPIO Configuration
PB6 ------> USART1_TX
PB7 ------> USART1_RX
*/
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART1;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
/* USER CODE BEGIN USART1_MspInit 1 */
/* Peripheral clock enable */
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_USART2);
/* USER CODE END USART1_MspInit 1 */
}
}
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_GPIOA);
/**USART2 GPIO Configuration
PA0-WKUP ------> USART2_CTS
PA1 ------> USART2_RTS
PA2 ------> USART2_TX
PA3 ------> USART2_RX
*/
GPIO_InitStruct.Pin = LL_GPIO_PIN_0|LL_GPIO_PIN_1|LL_GPIO_PIN_2|LL_GPIO_PIN_3;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
GPIO_InitStruct.Alternate = LL_GPIO_AF_7;
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle)
{
/* USER CODE BEGIN USART2_Init 1 */
if(uartHandle->Instance==USART1)
{
/* USER CODE BEGIN USART1_MspDeInit 0 */
/* USER CODE END USART2_Init 1 */
USART_InitStruct.BaudRate = 115200;
USART_InitStruct.DataWidth = LL_USART_DATAWIDTH_8B;
USART_InitStruct.StopBits = LL_USART_STOPBITS_1;
USART_InitStruct.Parity = LL_USART_PARITY_NONE;
USART_InitStruct.TransferDirection = LL_USART_DIRECTION_TX_RX;
USART_InitStruct.HardwareFlowControl = LL_USART_HWCONTROL_RTS_CTS;
USART_InitStruct.OverSampling = LL_USART_OVERSAMPLING_16;
LL_USART_Init(USART2, &USART_InitStruct);
LL_USART_ConfigAsyncMode(USART2);
LL_USART_Enable(USART2);
/* USER CODE BEGIN USART2_Init 2 */
/* USER CODE END USART1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USART1_CLK_DISABLE();
/* USER CODE END USART2_Init 2 */
/**USART1 GPIO Configuration
PB6 ------> USART1_TX
PB7 ------> USART1_RX
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6|GPIO_PIN_7);
/* USER CODE BEGIN USART1_MspDeInit 1 */
/* USER CODE END USART1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
int _write(int file, char *data, int len)
{
// Only redirect stdout and stderr
if (file != STDOUT_FILENO && file != STDERR_FILENO)
{
errno = EBADF;
return -1;
}
// UART transmit function
if (HAL_UART_Transmit(&huart1, (uint8_t *)data, len, HAL_MAX_DELAY) == HAL_OK)
{
return len;
}
else
{
return 0;
}
}
/* USER CODE END 1 */

View file

@ -13,83 +13,56 @@ ADC2.Rank-6\#ChannelRegularConversion=3
ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC2.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC2.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
CAN1.ABOM=ENABLE
CAN1.BS1=CAN_BS1_7TQ
CAN1.CalculateBaudRate=1000000
CAN1.CalculateTimeBit=1000
CAN1.CalculateTimeQuantum=111.11111111111111
CAN1.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,Prescaler,Mode,SJW,ABOM,NART,BS1
CAN1.Mode=CAN_MODE_LOOPBACK
CAN1.NART=ENABLE
CAN1.Prescaler=5
CAN1.SJW=CAN_SJW_1TQ
CAN2.ABOM=ENABLE
CAN2.BS1=CAN_BS1_7TQ
CAN2.CalculateBaudRate=1000000
CAN2.CalculateTimeBit=1000
CAN2.CalculateTimeQuantum=111.11111111111111
CAN2.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,Prescaler,BS1,ABOM,NART
CAN2.NART=ENABLE
CAN2.Prescaler=5
File.Version=6
GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=false
Mcu.CPN=STM32F446RET6
Mcu.Family=STM32F4
Mcu.IP0=ADC2
Mcu.IP1=CAN1
Mcu.IP10=USART1
Mcu.IP11=USART2
Mcu.IP2=CAN2
Mcu.IP3=NVIC
Mcu.IP4=RCC
Mcu.IP5=SPI2
Mcu.IP6=SYS
Mcu.IP7=TIM1
Mcu.IP8=TIM2
Mcu.IP9=TIM3
Mcu.IPNb=12
Mcu.IP1=NVIC
Mcu.IP2=RCC
Mcu.IP3=SPI2
Mcu.IP4=SYS
Mcu.IP5=TIM1
Mcu.IP6=TIM2
Mcu.IP7=TIM3
Mcu.IP8=TIM5
Mcu.IP9=USART1
Mcu.IPNb=10
Mcu.Name=STM32F446R(C-E)Tx
Mcu.Package=LQFP64
Mcu.Pin0=PH0-OSC_IN
Mcu.Pin1=PH1-OSC_OUT
Mcu.Pin10=PB10
Mcu.Pin11=PB12
Mcu.Pin12=PB13
Mcu.Pin13=PB14
Mcu.Pin14=PB15
Mcu.Pin15=PC6
Mcu.Pin16=PC7
Mcu.Pin17=PC8
Mcu.Pin18=PC9
Mcu.Pin19=PA8
Mcu.Pin10=PC7
Mcu.Pin11=PC8
Mcu.Pin12=PC9
Mcu.Pin13=PA8
Mcu.Pin14=PA9
Mcu.Pin15=PA10
Mcu.Pin16=PA11
Mcu.Pin17=PA12
Mcu.Pin18=PA13
Mcu.Pin19=PA14
Mcu.Pin2=PC1
Mcu.Pin20=PA9
Mcu.Pin21=PA10
Mcu.Pin22=PA11
Mcu.Pin23=PA12
Mcu.Pin24=PA13
Mcu.Pin25=PA14
Mcu.Pin26=PC10
Mcu.Pin27=PC11
Mcu.Pin28=PC12
Mcu.Pin29=PD2
Mcu.Pin3=PA0-WKUP
Mcu.Pin30=PB6
Mcu.Pin31=PB7
Mcu.Pin32=PB8
Mcu.Pin33=PB9
Mcu.Pin34=VP_SYS_VS_Systick
Mcu.Pin35=VP_TIM1_VS_ClockSourceINT
Mcu.Pin36=VP_TIM2_VS_ClockSourceINT
Mcu.Pin37=VP_TIM3_VS_ClockSourceINT
Mcu.Pin4=PA1
Mcu.Pin5=PA2
Mcu.Pin6=PA3
Mcu.Pin7=PC5
Mcu.Pin8=PB0
Mcu.Pin9=PB1
Mcu.PinsNb=38
Mcu.Pin20=PC10
Mcu.Pin21=PC11
Mcu.Pin22=PC12
Mcu.Pin23=PD2
Mcu.Pin24=PB6
Mcu.Pin25=PB7
Mcu.Pin26=VP_SYS_VS_Systick
Mcu.Pin27=VP_TIM1_VS_ClockSourceINT
Mcu.Pin28=VP_TIM2_VS_ClockSourceINT
Mcu.Pin29=VP_TIM3_VS_ClockSourceINT
Mcu.Pin3=PC5
Mcu.Pin30=VP_TIM5_VS_ClockSourceINT
Mcu.Pin4=PB0
Mcu.Pin5=PB1
Mcu.Pin6=PB10
Mcu.Pin7=PB14
Mcu.Pin8=PB15
Mcu.Pin9=PC6
Mcu.PinsNb=31
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F446RETx
@ -112,10 +85,6 @@ NVIC.TIM1_CC_IRQn=true\:3\:0\:true\:true\:true\:2\:true\:true\:true
NVIC.TIM2_IRQn=true\:4\:0\:true\:true\:true\:3\:true\:true\:true
NVIC.TIM3_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA0-WKUP.Mode=CTS_RTS
PA0-WKUP.Signal=USART2_CTS
PA1.Mode=CTS_RTS
PA1.Signal=USART2_RTS
PA10.Signal=S_TIM1_CH3
PA11.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PA11.GPIO_Label=EN_U
@ -133,10 +102,6 @@ PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
PA14.Signal=SYS_JTCK-SWCLK
PA2.Mode=Asynchronous
PA2.Signal=USART2_TX
PA3.Mode=Asynchronous
PA3.Signal=USART2_RX
PA8.Signal=S_TIM1_CH1
PA9.Signal=S_TIM1_CH2
PB0.GPIOParameters=GPIO_Label
@ -150,10 +115,6 @@ PB1.Signal=ADCx_IN9
PB10.Locked=true
PB10.Mode=Full_Duplex_Master
PB10.Signal=SPI2_SCK
PB12.Mode=CAN_Activate
PB12.Signal=CAN2_RX
PB13.Mode=CAN_Activate
PB13.Signal=CAN2_TX
PB14.Locked=true
PB14.Mode=Full_Duplex_Master
PB14.Signal=SPI2_MISO
@ -168,14 +129,6 @@ PB6.Mode=Asynchronous
PB6.Signal=USART1_TX
PB7.Mode=Asynchronous
PB7.Signal=USART1_RX
PB8.GPIOParameters=GPIO_PuPd
PB8.GPIO_PuPd=GPIO_PULLUP
PB8.Locked=true
PB8.Mode=CAN_Activate
PB8.Signal=CAN1_RX
PB9.Locked=true
PB9.Mode=CAN_Activate
PB9.Signal=CAN1_TX
PC1.Mode=Full_Duplex_Master
PC1.Signal=SPI2_MOSI
PC10.GPIOParameters=GPIO_Label
@ -250,7 +203,7 @@ ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=Other Toolchains (GPDSC)
ProjectManager.ToolChainLocation=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-LL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_TIM1_Init-TIM1-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-LL-true,5-MX_USART2_UART_Init-USART2-false-LL-true,6-MX_TIM2_Init-TIM2-false-HAL-true,7-MX_SPI2_Init-SPI2-false-HAL-true,8-MX_CAN1_Init-CAN1-false-HAL-true,9-MX_CAN2_Init-CAN2-false-HAL-true,10-MX_TIM3_Init-TIM3-false-HAL-true,11-MX_ADC2_Init-ADC2-false-HAL-true
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-LL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_TIM1_Init-TIM1-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-HAL-true,5-MX_TIM2_Init-TIM2-false-HAL-true,6-MX_SPI2_Init-SPI2-false-HAL-true,7-MX_TIM3_Init-TIM3-false-HAL-true,8-MX_ADC2_Init-ADC2-false-HAL-true,9-MX_TIM5_Init-TIM5-false-HAL-true
RCC.AHBFreq_Value=180000000
RCC.APB1CLKDivider=RCC_HCLK_DIV4
RCC.APB1Freq_Value=45000000
@ -337,8 +290,6 @@ TIM3.Period=99
TIM3.Prescaler=89
USART1.IPParameters=VirtualMode
USART1.VirtualMode=VM_ASYNC
USART2.IPParameters=VirtualMode
USART2.VirtualMode=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
VP_TIM1_VS_ClockSourceINT.Mode=Internal
@ -347,4 +298,6 @@ VP_TIM2_VS_ClockSourceINT.Mode=Internal
VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
VP_TIM3_VS_ClockSourceINT.Mode=Internal
VP_TIM3_VS_ClockSourceINT.Signal=TIM3_VS_ClockSourceINT
VP_TIM5_VS_ClockSourceINT.Mode=Internal
VP_TIM5_VS_ClockSourceINT.Signal=TIM5_VS_ClockSourceINT
board=custom