MasterFOC 0.0.1
Data Fields
Motor Struct Reference

Motor parameter structure. More...

#include <control.h>

Data Fields

ADC_HandleTypeDef hMotorADC
 
TIM_HandleTypeDef hTimDriver
 
TIM_HandleTypeDef hTimEncoder
 
I2C_HandleTypeDef hI2CEncoder
 
ControlMode Mode
 
UserAPP APP
 
Coordinates Voltage
 
Coordinates Current
 
PID_para idPID
 
PID_para iqPID
 
PID_para speedPID
 
PID_para anglePID
 
uint8_t nCalibrationFlag
 
uint8_t Vdc
 
uint8_t nPhase
 
uint8_t nPolePairs
 
int16_t SpeedCNT
 
uint16_t M_angle
 
uint16_t M_angle_pre
 
int16_t E_angle
 
int16_t E_angle_pre
 
uint16_t Angle_offset
 
float speed
 
float speed_pre
 
float CurrentLimit
 
float VoltageLimit
 
float SpeedLimit
 
int32_t lapCNT
 
int32_t lapCNT_pre
 
uint8_t sector
 
float Uref1
 
float Uref2
 
float Uref3
 
float X
 
float Y
 
float Z
 
float T1
 
float T2
 
float Tx
 
float Ty
 
float Tz
 
float Ta
 
float Tb
 
float Tc
 
uint16_t ADC_DMA_RAW [3]
 
uint16_t DC_offset [2]
 
int16_t ADC_Filtered [3]
 
int16_t Current_lastValue [5]
 

Detailed Description

Motor parameter structure.

pid parameters and target, error, previous error, and sum of error

Definition at line 79 of file control.h.

Field Documentation

◆ ADC_DMA_RAW

uint16_t ADC_DMA_RAW[3]

raw data of phase current sample

Definition at line 118 of file control.h.

◆ ADC_Filtered

int16_t ADC_Filtered[3]

filtered data of phase current sample

Definition at line 120 of file control.h.

◆ Angle_offset

uint16_t Angle_offset

Difference between encoder 0 deg and motor electrical 0 deg(phase a 100%)

Definition at line 107 of file control.h.

◆ anglePID

PID_para anglePID

angle PID parameters for motor instance

Definition at line 95 of file control.h.

◆ APP

UserAPP APP

current user application for motor instance

Definition at line 87 of file control.h.

◆ Current

Coordinates Current

current components for motor instance

Definition at line 90 of file control.h.

◆ Current_lastValue

int16_t Current_lastValue[5]

[0,1,2] previous current sample of phase a,b,c [3,4] previous id,iq sample

Definition at line 122 of file control.h.

◆ CurrentLimit

float CurrentLimit

Definition at line 110 of file control.h.

◆ DC_offset

uint16_t DC_offset[2]

DC offset of the current shunt amplifiler, used for DC calibration

Definition at line 119 of file control.h.

◆ E_angle

int16_t E_angle

Current electrical angle

Definition at line 105 of file control.h.

◆ E_angle_pre

int16_t E_angle_pre

Previous electrical angle

Definition at line 106 of file control.h.

◆ hI2CEncoder

I2C_HandleTypeDef hI2CEncoder

I2C encoder handler for motor instance

Definition at line 84 of file control.h.

◆ hMotorADC

ADC_HandleTypeDef hMotorADC

ADC handler for motor instance

Definition at line 81 of file control.h.

◆ hTimDriver

TIM_HandleTypeDef hTimDriver

Driver timer handler for motor instance

Definition at line 82 of file control.h.

◆ hTimEncoder

TIM_HandleTypeDef hTimEncoder

PWM Encoder timer handler for motor instance

Definition at line 83 of file control.h.

◆ idPID

PID_para idPID

Id PID parameters for motor instance

Definition at line 92 of file control.h.

◆ iqPID

PID_para iqPID

Iq PID parameters for motor instance

Definition at line 93 of file control.h.

◆ lapCNT

int32_t lapCNT

Definition at line 111 of file control.h.

◆ lapCNT_pre

int32_t lapCNT_pre

Current and previous lap counter (count the lap of the motor)

Definition at line 111 of file control.h.

◆ M_angle

uint16_t M_angle

Current mechanical angle

Definition at line 103 of file control.h.

◆ M_angle_pre

uint16_t M_angle_pre

Previous mechanical angle

Definition at line 104 of file control.h.

◆ Mode

current control mode for motor instance

Definition at line 86 of file control.h.

◆ nCalibrationFlag

uint8_t nCalibrationFlag

flag to record motor calibration status

Definition at line 97 of file control.h.

◆ nPhase

uint8_t nPhase

number of phase of the motor

Definition at line 99 of file control.h.

◆ nPolePairs

uint8_t nPolePairs

number of pole pairs of the motor

Definition at line 100 of file control.h.

◆ sector

uint8_t sector

sector of space voltage vector

Definition at line 112 of file control.h.

◆ speed

float speed

Definition at line 109 of file control.h.

◆ speed_pre

float speed_pre

Current and previous motor speed

Definition at line 109 of file control.h.

◆ SpeedCNT

int16_t SpeedCNT

Counter to record mechanical angle difference to calculate speed

Definition at line 102 of file control.h.

◆ SpeedLimit

float SpeedLimit

Current, Volatge, Speed limit of the motor

Definition at line 110 of file control.h.

◆ speedPID

PID_para speedPID

speed PID parameters for motor instance

Definition at line 94 of file control.h.

◆ T1

float T1

Definition at line 115 of file control.h.

◆ T2

float T2

Definition at line 115 of file control.h.

◆ Ta

float Ta

Definition at line 116 of file control.h.

◆ Tb

float Tb

Definition at line 116 of file control.h.

◆ Tc

float Tc

intermediate variables of dwelling time calculation

Definition at line 116 of file control.h.

◆ Tx

float Tx

Definition at line 115 of file control.h.

◆ Ty

float Ty

Definition at line 115 of file control.h.

◆ Tz

float Tz

intermediate variables of dwelling time calculation

Definition at line 115 of file control.h.

◆ Uref1

float Uref1

Definition at line 113 of file control.h.

◆ Uref2

float Uref2

Definition at line 113 of file control.h.

◆ Uref3

float Uref3

sector of space voltage vector

Definition at line 113 of file control.h.

◆ Vdc

uint8_t Vdc

DC power supply for motor instance

Definition at line 98 of file control.h.

◆ Voltage

Coordinates Voltage

voltage components for motor instance

Definition at line 89 of file control.h.

◆ VoltageLimit

float VoltageLimit

Definition at line 110 of file control.h.

◆ X

float X

Definition at line 114 of file control.h.

◆ Y

float Y

Definition at line 114 of file control.h.

◆ Z

float Z

intermediate variables of dwelling time calculation

Definition at line 114 of file control.h.


The documentation for this struct was generated from the following file: