TI的官方对于DRV8305电机驱动的综合例程,理解这个例程是学习这个FOC的最佳的途径
多余的话不说,理解程序如下,本程序是采用 TMS320F2807,:
/**********************************************************************************/
//版权声明
/**********************************************************************************/
//BY zhang bo QWMIDN. By Glassine.zhang.
//www.iotman.link 天津时序电子科技有限公司
/**********************************************************************************/
//内容概述,注意,本程序不包含motor ID,即电机参数的辨识。
/**********************************************************************************/
//文件位置:solutions/instaspin_foc/src/proj_lab011.c
//无控制器模块的简化实例 (brief A Simplified Example without Controller Module)
/**********************************************************************************/
//头文件
/**********************************************************************************/
// the includes
// system includes
#include
#include "main.h"
/**********************************************************************************/
//预定义
/**********************************************************************************/
#ifdef FLASH
#pragma CODE_SECTION(mainISR,"ramfuncs");
#endif
// Include header files used in the main function
// **************************************************************************
// the defines
// **************************************************************************
// 全局变量
CLARKE_Handle clarkeHandle_I; //!< the handle for the current Clarke
//!< transform
CLARKE_Obj clarke_I; //!< the current Clarke transform object
CLARKE_Handle clarkeHandle_V; //!< the handle for the voltage Clarke
//!< transform
CLARKE_Obj clarke_V; //!< the voltage Clarke transform object
EST_Handle estHandle; //!< the handle for the estimator
PID_Obj pid[3]; //!< three objects for PID controllers
//!< 0 - Speed, 1 - Id, 2 - Iq
PID_Handle pidHandle[3]; //!< three handles for PID controllers
//!< 0 - Speed, 1 - Id, 2 - Iq
uint16_t pidCntSpeed; //!< count variable to decimate the execution
//!< of the speed PID controller
IPARK_Handle iparkHandle; //!< the handle for the inverse Park
//!< transform
IPARK_Obj ipark; //!< the inverse Park transform object
SVGEN_Handle svgenHandle; //!< the handle for the space vector generator
SVGEN_Obj svgen; //!< the space vector generator object
#ifdef CSM_ENABLE
#pragma DATA_SECTION(halHandle,"rom_accessed_data");
#endif
HAL_Handle halHandle; //!< the handle for the hardware abstraction
//!< layer (HAL)
HAL_PwmData_t gPwmData = {_IQ(0.0),_IQ(0.0),_IQ(0.0)}; //!< contains the
//!< pwm values for each phase.
//!< -1.0 is 0%, 1.0 is 100%
HAL_AdcData_t gAdcData; //!< contains three current values, three
//!< voltage values and one DC buss value
MATH_vec3 gOffsets_I_pu = {_IQ(0.0),_IQ(0.0),_IQ(0.0)}; //!< contains
//!< the offsets for the current feedback
MATH_vec3 gOffsets_V_pu = {_IQ(0.0),_IQ(0.0),_IQ(0.0)}; //!< contains
//!< the offsets for the voltage feedback
MATH_vec2 gIdq_ref_pu = {_IQ(0.0),_IQ(0.0)}; //!< contains the Id and
//!< Iq references
MATH_vec2 gVdq_out_pu = {_IQ(0.0),_IQ(0.0)}; //!< contains the output
//!< Vd and Vq from the current controllers
MATH_vec2 gIdq_pu = {_IQ(0.0),_IQ(0.0)}; //!< contains the Id and Iq
//!< measured values
#ifdef CSM_ENABLE
#pragma DATA_SECTION(gUserParams,"rom_accessed_data");
#endif
USER_Params gUserParams;
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT; //!< the global motor
//!< variables that are defined in main.h and
//!< used for display in the debugger's watch
//!< window
#ifdef FLASH
// Used for running BackGround in flash, and ISR in RAM
extern uint16_t *RamfuncsLoadStart, *RamfuncsLoadEnd, *RamfuncsRunStart;
#ifdef CSM_ENABLE
extern uint16_t *econst_start, *econst_end, *econst_ram_load;
extern uint16_t *switch_start, *switch_end, *switch_ram_load;
#endif
#endif
#ifdef DRV8301_SPI
// Watch window interface to the 8301 SPI
DRV_SPI_8301_Vars_t gDrvSpi8301Vars;
#endif
#ifdef DRV8305_SPI
// Watch window interface to the 8305 SPI
DRV_SPI_8305_Vars_t gDrvSpi8305Vars;
#endif
_iq gFlux_pu_to_Wb_sf;
_iq gFlux_pu_to_VpHz_sf;
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf;
_iq gTorque_Flux_Iq_pu_to_Nm_sf;
_iq gSpeed_krpm_to_pu_sf = _IQ((float_t)USER_MOTOR_NUM_POLE_PAIRS * 1000.0
/ (USER_IQ_FULL_SCALE_FREQ_Hz * 60.0));
_iq gSpeed_hz_to_krpm_sf = _IQ(60.0 / (float_t)USER_MOTOR_NUM_POLE_PAIRS
/ 1000.0);
/***********************************************************************************************/
//主函数
/***********************************************************************************************/
void main(void)
{
// 如果您不熟悉motorware编码指南请参考以下文档:
// C:/ti/motorware/motorware_1_01_00_1x/docs/motorware_coding_standards.pdf
//仅在从闪存运行时使用,注意变量flash是由项目定义的
#ifdef FLASH
// Copy time critical code and Flash setup code to RAM
// The RamfuncsLoadStart, RamfuncsLoadEnd, and RamfuncsRunStart
// symbols are created by the linker. Refer to the linker files.
memCopy((uint16_t *)&RamfuncsLoadStart,(uint16_t *)&RamfuncsLoadEnd,
(uint16_t *)&RamfuncsRunStart);
#ifdef CSM_ENABLE
//copy .econst to unsecure RAM
if(*econst_end - *econst_start)
{
memCopy((uint16_t *)&econst_start,(uint16_t *)&econst_end,(uint16_t *)&econst_ram_load);
}
//copy .switch ot unsecure RAM
if(*switch_end - *switch_start)
{
memCopy((uint16_t *)&switch_start,(uint16_t *)&switch_end,(uint16_t *)&switch_ram_load);
}
#endif
#endif
//初始化硬件抽象层(HAL在整个代码中将使用halhandle来与hal接口
//(设置参数、获取和设置函数等)需要halhandle,因为这是所有对象的接口方式,
//它允许与通过简单地传递一个不同的句柄来实现多个对象。使用本文档解释了句柄:
// C:/ti/motorware/motorware_1_01_00_1x/docs/motorware_coding_standards.pdf
halHandle = HAL_init(&hal,sizeof(hal));
// 检查用户参数错误。
USER_checkForErrors(&gUserParams);
// 在全局变量中存储用户参数错误。
gMotorVars.UserErrorCode = USER_getErrorCode(&gUserParams);
// 如果存在用户参数错误,不允许运行, 如果有错误,那就在这里面一直循环。
if(gMotorVars.UserErrorCode != USER_ErrorCode_NoError)
{
for(;;)
{
gMotorVars.Flag_enableSys = false;
}
}
// 初始化Clarke模块
// Clarke handle initialization for current signals
clarkeHandle_I = CLARKE_init(&clarke_I,sizeof(clarke_I));
// Clarke handle initialization for voltage signals
clarkeHandle_V = CLARKE_init(&clarke_V,sizeof(clarke_V));
// 初始化估计器 initialize the estimator
estHandle = EST_init((void *)USER_EST_HANDLE_ADDRESS,0x200);
// 初始化用户参数
// 这个函数初始化在user.h中的所有gUserParams结构体的用户参数, gUserParams的这些
//参数将被用在HAL层去配置MCU的外围,例如PWM,ADC,中断等等其他。
USER_setParams(&gUserParams);
//设置这个硬件抽象层参数,这个函数的功能就是通过硬件抽象层去初始化所有外设
//他用的所有参数存储在gUserParams中。
HAL_setParams(halHandle,&gUserParams);
/***************************************************/
#ifdef FAST_ROM_V1p6
{
// These function calls are used to initialize the estimator with ROM
// function calls. It needs the specific address where the controller
// object is declared by the ROM code.
CTRL_Handle ctrlHandle = CTRL_init((void *)USER_CTRL_HANDLE_ADDRESS
,0x200);
CTRL_Obj *obj = (CTRL_Obj *)ctrlHandle;
// this sets the estimator handle (part of the controller object) to
// the same value initialized above by the EST_init() function call.
// This is done so the next function implemented in ROM, can
// successfully initialize the estimator as part of the controller
// object.
obj->estHandle = estHandle;
// initialize the estimator through the controller. These three
// function calls are needed for the F2806xF/M implementation of
// InstaSPIN.
CTRL_setParams(ctrlHandle,&gUserParams);
CTRL_setUserMotorParams(ctrlHandle);
CTRL_setupEstIdleState(ctrlHandle);
}
#else
{
// initialize the estimator. These two function calls are needed for
// the F2802xF implementation of InstaSPIN using the estimator handle
// initialized by EST_init(), these two function calls configure the
// estimator, and they set the estimator in a proper state prior to
// spinning a motor.
EST_setEstParams(estHandle,&gUserParams);
EST_setupEstIdleState(estHandle);
}
#endif
/***************************************************/
// disable Rs recalculation
// **NOTE: changing the input parameter from 'false' to 'true' will cause
// ** run time issues. Lab11 does not support Rs Online function
//
EST_setFlag_enableRsRecalc(estHandle,false);
// set the number of current sensors
setupClarke_I(clarkeHandle_I,USER_NUM_CURRENT_SENSORS);
// set the number of voltage sensors
setupClarke_V(clarkeHandle_V,USER_NUM_VOLTAGE_SENSORS);
// set the pre-determined current and voltage feeback offset values
gOffsets_I_pu.value[0] = _IQ(I_A_offset);
gOffsets_I_pu.value[1] = _IQ(I_B_offset);
gOffsets_I_pu.value[2] = _IQ(I_C_offset);
gOffsets_V_pu.value[0] = _IQ(V_A_offset);
gOffsets_V_pu.value[1] = _IQ(V_B_offset);
gOffsets_V_pu.value[2] = _IQ(V_C_offset);
// initialize the PID controllers
{
// This equation defines the relationship between per unit current and
// real-world current. The resulting value in per units (pu) is then
// used to configure the controllers
_iq maxCurrent_pu = _IQ(USER_MOTOR_MAX_CURRENT
/ USER_IQ_FULL_SCALE_CURRENT_A);
// This equation uses the scaled maximum voltage vector, which is
// already in per units, hence there is no need to include the #define
// for USER_IQ_FULL_SCALE_VOLTAGE_V
_iq maxVoltage_pu = _IQ(USER_MAX_VS_MAG_PU * USER_VD_SF);
float_t fullScaleCurrent = USER_IQ_FULL_SCALE_CURRENT_A;
float_t fullScaleVoltage = USER_IQ_FULL_SCALE_VOLTAGE_V;
float_t IsrPeriod_sec = 1.0 / USER_ISR_FREQ_Hz;
float_t Ls_d = USER_MOTOR_Ls_d;
float_t Ls_q = USER_MOTOR_Ls_q;
float_t Rs = USER_MOTOR_Rs;
// This lab assumes that motor parameters are known, and it does not
// perform motor ID, so the R/L parameters are known and defined in
// user.h
float_t RoverLs_d = Rs / Ls_d;
float_t RoverLs_q = Rs / Ls_q;
// For the current controller, Kp = Ls*bandwidth(rad/sec) But in order
// to be used, it must be converted to per unit values by multiplying
// by fullScaleCurrent and then dividing by fullScaleVoltage. From the
// statement below, we see that the bandwidth in rad/sec is equal to
// 0.25/IsrPeriod_sec, which is equal to USER_ISR_FREQ_HZ/4. This means
// that by setting Kp as described below, the bandwidth in Hz is
// USER_ISR_FREQ_HZ/(8*pi).
_iq Kp_Id = _IQ((0.25 * Ls_d * fullScaleCurrent) / (IsrPeriod_sec
* fullScaleVoltage));
// In order to achieve pole/zero cancellation (which reduces the
// closed-loop transfer function from a second-order system to a
// first-order system), Ki must equal Rs/Ls. Since the output of the
// Ki gain stage is integrated by a DIGITAL integrator, the integrator
// input must be scaled by 1/IsrPeriod_sec. That's just the way
// digital integrators work. But, since IsrPeriod_sec is a constant,
// we can save an additional multiplication operation by lumping this
// term with the Ki value.
_iq Ki_Id = _IQ(RoverLs_d * IsrPeriod_sec);
// Now do the same thing for Kp for the q-axis current controller.
// If the motor is not an IPM motor, Ld and Lq are the same, which
// means that Kp_Iq = Kp_Id
_iq Kp_Iq = _IQ((0.25 * Ls_q * fullScaleCurrent) / (IsrPeriod_sec
* fullScaleVoltage));
// Do the same thing for Ki for the q-axis current controller. If the
// motor is not an IPM motor, Ld and Lq are the same, which means that
// Ki_Iq = Ki_Id.
_iq Ki_Iq = _IQ(RoverLs_q * IsrPeriod_sec);
// There are three PI controllers; one speed controller and two current
// controllers. Each PI controller has two coefficients; Kp and Ki.
// So you have a total of six coefficients that must be defined.
// This is for the speed controller
pidHandle[0] = PID_init(&pid[0],sizeof(pid[0]));
// This is for the Id current controller
pidHandle[1] = PID_init(&pid[1],sizeof(pid[1]));
// This is for the Iq current controller
pidHandle[2] = PID_init(&pid[2],sizeof(pid[2]));
// The following instructions load the parameters for the speed PI
// controller.
PID_setGains(pidHandle[0],_IQ(1.0),_IQ(0.01),_IQ(0.0));
// The current limit is performed by the limits placed on the speed PI
// controller output. In the following statement, the speed
// controller's largest negative current is set to -maxCurrent_pu, and
// the largest positive current is set to maxCurrent_pu.
PID_setMinMax(pidHandle[0],-maxCurrent_pu,maxCurrent_pu);
PID_setUi(pidHandle[0],_IQ(0.0)); // Set the initial condition value
// for the integrator output to 0
pidCntSpeed = 0; // Set the counter for decimating the speed
// controller to 0
// The following instructions load the parameters for the d-axis
// current controller.
// P term = Kp_Id, I term = Ki_Id, D term = 0
PID_setGains(pidHandle[1],Kp_Id,Ki_Id,_IQ(0.0));
// Largest negative voltage = -maxVoltage_pu, largest positive
// voltage = maxVoltage_pu
PID_setMinMax(pidHandle[1],-maxVoltage_pu,maxVoltage_pu);
// Set the initial condition value for the integrator output to 0
PID_setUi(pidHandle[1],_IQ(0.0));
// The following instructions load the parameters for the q-axis
// current controller.
// P term = Kp_Iq, I term = Ki_Iq, D term = 0
PID_setGains(pidHandle[2],Kp_Iq,Ki_Iq,_IQ(0.0));
// The largest negative voltage = 0 and the largest positive
// voltage = 0. But these limits are updated every single ISR before
// actually executing the Iq controller. The limits depend on how much
// voltage is left over after the Id controller executes. So having an
// initial value of 0 does not affect Iq current controller execution.
PID_setMinMax(pidHandle[2],_IQ(0.0),_IQ(0.0));
// Set the initial condition value for the integrator output to 0
PID_setUi(pidHandle[2],_IQ(0.0));
}
// initialize the speed reference in kilo RPM where base speed is
// USER_IQ_FULL_SCALE_FREQ_Hz.
// Set 10 Hz electrical frequency as initial value, so the kRPM value would
// be: 10 * 60 / motor pole pairs / 1000.
gMotorVars.SpeedRef_krpm = _IQmpy(_IQ(10.0),gSpeed_hz_to_krpm_sf);
// initialize the inverse Park module
iparkHandle = IPARK_init(&ipark,sizeof(ipark));
// initialize the space vector generator module
svgenHandle = SVGEN_init(&svgen,sizeof(svgen));
// setup faults
HAL_setupFaults(halHandle);
// initialize the interrupt vector table
HAL_initIntVectorTable(halHandle);
// enable the ADC interrupts
HAL_enableAdcInts(halHandle);
// enable global interrupts
HAL_enableGlobalInts(halHandle);
// enable debug interrupts
HAL_enableDebugInt(halHandle);
// disable the PWM
HAL_disablePwm(halHandle);
// compute scaling factors for flux and torque calculations
gFlux_pu_to_Wb_sf = USER_computeFlux_pu_to_Wb_sf();
gFlux_pu_to_VpHz_sf = USER_computeFlux_pu_to_VpHz_sf();
gTorque_Ls_Id_Iq_pu_to_Nm_sf = USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf();
gTorque_Flux_Iq_pu_to_Nm_sf = USER_computeTorque_Flux_Iq_pu_to_Nm_sf();
// enable the system by default
gMotorVars.Flag_enableSys = true;
#ifdef DRV8301_SPI
// turn on the DRV8301 if present
HAL_enableDrv(halHandle);
// initialize the DRV8301 interface
HAL_setupDrvSpi(halHandle,&gDrvSpi8301Vars);
#endif
#ifdef DRV8305_SPI
// turn on the DRV8305 if present
HAL_enableDrv(halHandle);
// initialize the DRV8305 interface
HAL_setupDrvSpi(halHandle,&gDrvSpi8305Vars);
#endif
// 开始后台循环运行
for(;;)
{
// 正在等待设置启用系统标志。Waiting for enable system flag to be set
while(!(gMotorVars.Flag_enableSys));
// 启用系统标志为真时循环。 loop while the enable system flag is true
while(gMotorVars.Flag_enableSys)
{
//如果设置了flag_enablesys并设置了flag_run_identification,则
//启用PWMS并设置速度参考。
if(gMotorVars.Flag_Run_Identify)
{
// 更新估计状态 update estimator state
EST_updateState(estHandle,0);
#ifdef FAST_ROM_V1p6
// call this function to fix 1p6. This is only used for
// F2806xF/M implementation of InstaSPIN (version 1.6 of
// ROM), since the inductance calculation is not done
// correctly in ROM, so this function fixes that ROM bug.
softwareUpdate1p6(estHandle);
#endif
// 启用脉宽调制 enable the PWM
HAL_enablePwm(halHandle);
}
// Flag_enableSys is set AND Flag_Run_Identify is not set
//设置了flag_enablesys且未设置flag_run_identification
else
{
// 将估计器设置为空闲 set estimator to Idle
EST_setIdle(estHandle);
// 失能 PWM
HAL_disablePwm(halHandle);
// 清除integrator输出。 clear integrator outputs
PID_setUi(pidHandle[0],_IQ(0.0));
PID_setUi(pidHandle[1],_IQ(0.0));
PID_setUi(pidHandle[2],_IQ(0.0));
// clear Id and Iq references
gIdq_ref_pu.value[0] = _IQ(0.0);
gIdq_ref_pu.value[1] = _IQ(0.0);
}
// 更新全局变量
updateGlobalVariables(estHandle);
// 启用/禁用强制角度 enable/disable the forced angle
EST_setFlag_enableForceAngle(estHandle,
gMotorVars.Flag_enableForceAngle);
// 设定目标速度 set target speed
gMotorVars.SpeedRef_pu = _IQmpy(gMotorVars.SpeedRef_krpm,
gSpeed_krpm_to_pu_sf);
/***************************************************/
#ifdef DRV8301_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8301Vars);
HAL_readDrvData(halHandle,&gDrvSpi8301Vars);
#endif
/***************************************************/
#ifdef DRV8305_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8305Vars);
HAL_readDrvData(halHandle,&gDrvSpi8305Vars);
#endif
/***************************************************/
} // end of while(gFlag_enableSys) loop
// 失能 PWM
HAL_disablePwm(halHandle);
gMotorVars.Flag_Run_Identify = false;
}
}
/**********************************************************************************/
//实现电机控制的主要ISR。
//The main ISR that implements the motor control.
/**********************************************************************************/
interrupt void mainISR(void)
{
// 声明局部变量
_iq angle_pu = _IQ(0.0);
_iq speed_pu = _IQ(0.0);
_iq oneOverDcBus;
MATH_vec2 Iab_pu;
MATH_vec2 Vab_pu;
MATH_vec2 phasor;
// 确认ADC中断 acknowledge the ADC interrupt
HAL_acqAdcInt(halHandle,ADC_IntNumber_1);
// 转换ADC数据 convert the ADC data
HAL_readAdcDataWithOffsets(halHandle,&gAdcData);
// 删除偏移 remove offsets
gAdcData.I.value[0] = gAdcData.I.value[0] - gOffsets_I_pu.value[0];
gAdcData.I.value[1] = gAdcData.I.value[1] - gOffsets_I_pu.value[1];
gAdcData.I.value[2] = gAdcData.I.value[2] - gOffsets_I_pu.value[2];
gAdcData.V.value[0] = gAdcData.V.value[0] - gOffsets_V_pu.value[0];
gAdcData.V.value[1] = gAdcData.V.value[1] - gOffsets_V_pu.value[1];
gAdcData.V.value[2] = gAdcData.V.value[2] - gOffsets_V_pu.value[2];
// run Clarke transform on current. Three values are passed, two values are returned.
//在current运行Clarke变换。传递三个值,返回两个值。
CLARKE_run(clarkeHandle_I,&gAdcData.I,&Iab_pu);
// run Clarke transform on voltage. Three values are passed, two values are returned.
//在voltage运行Clarke变换。传递三个值,返回两个值。
CLARKE_run(clarkeHandle_V,&gAdcData.V,&Vab_pu);
// run the estimator。The speed reference is needed so that the proper sign of the forced
// angle is calculated. When the estimator does not do motor ID as in this lab,
//only the sign of the speed reference is used
//运行估计器。需要速度参考,以便计算角度。当估计器没有像这样做马达ID时,
//只使用速度参考的符号。
EST_run(estHandle,&Iab_pu,&Vab_pu,gAdcData.dcBus,gMotorVars.SpeedRef_pu);
// 产生电机电角。generate the motor electrical angle
angle_pu = EST_getAngle_pu(estHandle);
speed_pu = EST_getFm_pu(estHandle);
// get Idq from estimator to avoid sin and cos, and a Park transform,which saves CPU cycles
//从估计器中获取idq以避免sin和cos以及park变换,节省CPU周期。
EST_getIdq_pu(estHandle,&gIdq_pu);
// 运行适当的控制器。run the appropriate controller
if(gMotorVars.Flag_Run_Identify)
{
// 局部变量声明 Declaration of local variables.
_iq refValue; //??
_iq fbackValue; //??
_iq outMax_pu; //??
// 适当时,运行PID速度控制器 。when appropriate, run the PID speed controller
// 这个机制为速度环提供抽取。This mechanism provides the decimation for the speed loop.
if(pidCntSpeed >= USER_NUM_CTRL_TICKS_PER_SPEED_TICK)
{
// 重置速度PID执行计数器 。Reset the Speed PID execution counter.
pidCntSpeed = 0;
// The next instruction executes the PI speed controller and places
// its output in Idq_ref_pu.value[1], which is the input reference
// value for the q-axis current controller.
//下一条指令执行pi速度控制器并放置其输出结果在idq_ref_pu.value[1],
//它是输入参考,q-axis电流控制器的值。
PID_run_spd(pidHandle[0],gMotorVars.SpeedRef_pu,speed_pu,
&(gIdq_ref_pu.value[1]));
}
else
{
// 累加计数器。
pidCntSpeed++;
}
// Get the reference value for the d-axis current controller.
//获得d-axis电流控制器的参考值。
refValue = gIdq_ref_pu.value[0];
// 获取id的实际值 。Get the actual value of Id
fbackValue = gIdq_pu.value[0];
//The next instruction executes the PI current controller for the d axis and places its
//output in Vdq_pu.value[0], which is the control voltage along the d-axis (Vd)。
//下一个指令执行d axis的PI电流控制器,并将其输出置于VDQPU PU.值[0 ],
//这是沿d-axis(VD)的控制电压。
PID_run(pidHandle[1],refValue,fbackValue,&(gVdq_out_pu.value[0]));
// 获取Iq参考值。
refValue = gIdq_ref_pu.value[1];
// 获取Iq实际值。
fbackValue = gIdq_pu.value[1];
// The voltage limits on the output of the q-axis current controller
// are dynamic, and are dependent on the output voltage from the d-axis
// current controller. In other words, the d-axis current controller
// gets first dibs on the available voltage, and the q-axis current
// controller gets what's left over. That is why the d-axis current
// controller executes first. The next instruction calculates the
// maximum limits for this voltage as:
// Vq_min_max = +/- sqrt(Vbus^2 - Vd^2)
//以上这段话自己领悟。
outMax_pu = _IQsqrt(_IQ(USER_MAX_VS_MAG_PU * USER_MAX_VS_MAG_PU)
- _IQmpy(gVdq_out_pu.value[0],gVdq_out_pu.value[0]));
// Set the limits to +/- outMax_pu
PID_setMinMax(pidHandle[2],-outMax_pu,outMax_pu);
// The next instruction executes the PI current controller for the
// q axis and places its output in Vdq_pu.value[1], which is the
// control voltage vector along the q-axis (Vq)
PID_run(pidHandle[2],refValue,fbackValue,&(gVdq_out_pu.value[1]));
// The voltage vector is now calculated and ready to be applied to the
// motor in the form of three PWM signals. However, even though the
// voltages may be supplied to the PWM module now, they won't be
// applied to the motor until the next PWM cycle. By this point, the
// motor will have moved away from the angle that the voltage vector
// was calculated for, by an amount which is proportional to the
// sampling frequency and the speed of the motor. For steady-state
// speeds, we can calculate this angle delay and compensate for it.
angle_pu = angleDelayComp(speed_pu,angle_pu);
// compute the sine and cosine phasor values which are part of the inverse
// Park transform calculations. Once these values are computed,
// they are copied into the IPARK module, which then uses them to
// transform the voltages from DQ to Alpha/Beta reference frames.
phasor.value[0] = _IQcosPU(angle_pu);
phasor.value[1] = _IQsinPU(angle_pu);
// set the phasor in the inverse Park transform
IPARK_setPhasor(iparkHandle,&phasor);
// Run the inverse Park module. This converts the voltage vector from
// synchronous frame values to stationary frame values.
IPARK_run(iparkHandle,&gVdq_out_pu,&Vab_pu);
// These 3 statements compensate for variations in the DC bus by adjusting the
// PWM duty cycle. The goal is to achieve the same volt-second product
// regardless of the DC bus value. To do this, we must divide the desired voltage
// values by the DC bus value. Or...it is easier to multiply by 1/(DC bus value).
oneOverDcBus = EST_getOneOverDcBus_pu(estHandle);
Vab_pu.value[0] = _IQmpy(Vab_pu.value[0],oneOverDcBus);
Vab_pu.value[1] = _IQmpy(Vab_pu.value[1],oneOverDcBus);
// Now run the space vector generator (SVGEN) module.
// There is no need to do an inverse CLARKE transform, as this is handled in the SVGEN_run function.
//现在运行空间矢量发生器(svgen)模块。
//不需要进行逆CLARKE变换,因为这是在svgen_run函数中处理的。
SVGEN_run(svgenHandle,&Vab_pu,&(gPwmData.Tabc));
}
// 当Flag_Run_Identify为0时。gMotorVars.Flag_Run_Identify = 0
else
{
// 失能 PWM
HAL_disablePwm(halHandle);
// 设置PWMS为50%的占空比。Set the PWMs to 50% duty cycle
gPwmData.Tabc.value[0] = _IQ(0.0);
gPwmData.Tabc.value[1] = _IQ(0.0);
gPwmData.Tabc.value[2] = _IQ(0.0);
}
// write to the PWM compare registers, and then we are done!
//写入脉冲宽度调制比较寄存器,然后我们就完成了!
HAL_writePwmData(halHandle,&gPwmData);
return;
}
/**********************************************************************************/
//角度延迟的补偿工作模块。
//The angleDelayComp function compensates for the delay introduced
//from the time when the system inputs are sampled to when the PWM
//voltages are applied to the motor windings.
//angelaycomp函数补偿从系统输入采样到将pwm电压施加到电机绕组时所引入的延迟。
/**********************************************************************************/
_iq angleDelayComp(const _iq fm_pu,const _iq angleUncomp_pu)
{
_iq angleDelta_pu = _IQmpy(fm_pu,_IQ(USER_IQ_FULL_SCALE_FREQ_Hz
/ (USER_PWM_FREQ_kHz*1000.0)));
_iq angleCompFactor = _IQ(1.0 + (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK
* 0.5);
_iq angleDeltaComp_pu = _IQmpy(angleDelta_pu,angleCompFactor);
uint32_t angleMask = ((uint32_t)0xFFFFFFFF >> (32 - GLOBAL_Q));
_iq angleComp_pu;
_iq angleTmp_pu;
// 增加角度 increment the angle
angleTmp_pu = angleUncomp_pu + angleDeltaComp_pu;
// 遮住环绕的角度 mask the angle for wrap around
// 注:必须说明角度符号 note: must account for the sign of the angle
angleComp_pu = _IQabs(angleTmp_pu) & angleMask;
// account for sign
if(angleTmp_pu < _IQ(0.0))
{
angleComp_pu = -angleComp_pu;
}
return(angleComp_pu);
}
/**********************************************************************************/
//本模块仅仅用在F2806xF/M的相关套件的参数设置。
//! \brief Call this function to fix 1p6. This is only used for F2806xF/M
//! \brief implementation of InstaSPIN (version 1.6 of ROM) since the
//! \brief inductance calculation is not done correctly in ROM, so this
//! \brief function fixes that ROM bug.
/**********************************************************************************/
void softwareUpdate1p6(EST_Handle handle)
{
float_t fullScaleInductance = USER_IQ_FULL_SCALE_VOLTAGE_V
/ (USER_IQ_FULL_SCALE_CURRENT_A
* USER_VOLTAGE_FILTER_POLE_rps);
float_t Ls_coarse_max = _IQ30toF(EST_getLs_coarse_max_pu(handle));
int_least8_t lShift = ceil(log(USER_MOTOR_Ls_d / (Ls_coarse_max
* fullScaleInductance)) / log(2.0));
uint_least8_t Ls_qFmt = 30 - lShift;
float_t L_max = fullScaleInductance * pow(2.0,lShift);
_iq Ls_d_pu = _IQ30(USER_MOTOR_Ls_d / L_max);
_iq Ls_q_pu = _IQ30(USER_MOTOR_Ls_q / L_max);
// store the results
EST_setLs_d_pu(handle,Ls_d_pu);
EST_setLs_q_pu(handle,Ls_q_pu);
EST_setLs_qFmt(handle,Ls_qFmt);
return;
}
/**********************************************************************************/
//为2个或3个传感器设置Clarke变换。电流。
//param[in] handle The clarke (CLARKE) handle
//param[in] numCurrentSensors The number of current sensors
/**********************************************************************************/
void setupClarke_I(CLARKE_Handle handle,const uint_least8_t numCurrentSensors)
{
_iq alpha_sf,beta_sf;
// initialize the Clarke transform module for current
if(numCurrentSensors == 3)
{
alpha_sf = _IQ(MATH_ONE_OVER_THREE);
beta_sf = _IQ(MATH_ONE_OVER_SQRT_THREE);
}
else if(numCurrentSensors == 2)
{
alpha_sf = _IQ(1.0);
beta_sf = _IQ(MATH_ONE_OVER_SQRT_THREE);
}
else
{
alpha_sf = _IQ(0.0);
beta_sf = _IQ(0.0);
}
// set the parameters
CLARKE_setScaleFactors(handle,alpha_sf,beta_sf);
CLARKE_setNumSensors(handle,numCurrentSensors);
return;
}
/**********************************************************************************/
//为2个或3个传感器设置Clarke变换。电压。
//Setup the Clarke transform for either 2 or 3 sensors.
//param[in] handle The clarke (CLARKE) handle
//param[in] numVoltageSensors The number of voltage sensors
/**********************************************************************************/
void setupClarke_V(CLARKE_Handle handle,const uint_least8_t numVoltageSensors)
{
_iq alpha_sf,beta_sf;
// initialize the Clarke transform module for voltage
if(numVoltageSensors == 3)
{
alpha_sf = _IQ(MATH_ONE_OVER_THREE);
beta_sf = _IQ(MATH_ONE_OVER_SQRT_THREE);
}
else
{
alpha_sf = _IQ(0.0);
beta_sf = _IQ(0.0);
}
// In other words, the only acceptable number of voltage sensors is three.
// set the parameters
CLARKE_setScaleFactors(handle,alpha_sf,beta_sf);
CLARKE_setNumSensors(handle,numVoltageSensors);
return;
}
/**********************************************************************************/
//Update the global variables (gMotorVars).更新全局变量(gmotorvars)。
//param[in] handle The estimator (EST) handle。param[in]handle估计量(est)handle
/**********************************************************************************/
void updateGlobalVariables(EST_Handle handle)
{
// 得到速度估计值,get the speed estimate
gMotorVars.Speed_krpm = EST_getSpeed_krpm(handle);
/***************************************************/
// 得到扭矩估计值 get the torque estimate
{
_iq Flux_pu = EST_getFlux_pu(handle);
_iq Id_pu = PID_getFbackValue(pidHandle[1]);
_iq Iq_pu = PID_getFbackValue(pidHandle[2]);
_iq Ld_minus_Lq_pu = _IQ30toIQ(EST_getLs_d_pu(handle)
- EST_getLs_q_pu(handle));
// 电抗转矩 Reactance Torque
_iq Torque_Flux_Iq_Nm = _IQmpy(_IQmpy(Flux_pu,Iq_pu),
gTorque_Flux_Iq_pu_to_Nm_sf);
// 磁阻转矩 Reluctance Torque
_iq Torque_Ls_Id_Iq_Nm = _IQmpy(_IQmpy(_IQmpy(Ld_minus_Lq_pu,Id_pu),
Iq_pu),gTorque_Ls_Id_Iq_pu_to_Nm_sf);
// 总转矩是电抗转矩和磁阻转矩之和 Total torque is sum of reactance torque and reluctance torque
_iq Torque_Nm = Torque_Flux_Iq_Nm + Torque_Ls_Id_Iq_Nm;
gMotorVars.Torque_Nm = Torque_Nm;
}
/***************************************************/
// 得到磁化电流 get the magnetizing current
gMotorVars.MagnCurr_A = EST_getIdRated(handle);
// 得到转子电阻 get the rotor resistance
gMotorVars.Rr_Ohm = EST_getRr_Ohm(handle);
// 得到定子电阻 get the stator resistance
gMotorVars.Rs_Ohm = EST_getRs_Ohm(handle);
// 直接坐标方向的定子电感 get the stator inductance in the direct coordinate direction
gMotorVars.Lsd_H = EST_getLs_d_H(handle);
// 求出正交坐标方向上的定子电感 get the stator inductance in the quadrature coordinate direction
gMotorVars.Lsq_H = EST_getLs_q_H(handle);
// 求出浮点数的磁通量,单位为V/Hz get the flux in V/Hz in floating point
gMotorVars.Flux_VpHz = EST_getFlux_VpHz(handle);
// 得到固定点wb中的通量 get the flux in Wb in fixed point
gMotorVars.Flux_Wb = _IQmpy(EST_getFlux_pu(handle),gFlux_pu_to_Wb_sf);
// 得到估计状态get the estimator state
gMotorVars.EstState = EST_getState(handle);
// 获取直流母线电压 Get the DC buss voltage
gMotorVars.VdcBus_kV = _IQmpy(gAdcData.dcBus,
_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V / 1000.0));
// 每单位读取vd和vq矢量 read Vd and Vq vectors per units
gMotorVars.Vd = gVdq_out_pu.value[0];
gMotorVars.Vq = gVdq_out_pu.value[1];
// 以单位计算矢量vs:(vs=sqrt(vd^2+vq^2)) calculate vector Vs in per units: (Vs = sqrt(Vd^2 + Vq^2))
gMotorVars.Vs = _IQsqrt(_IQmpy(gMotorVars.Vd,gMotorVars.Vd)
+ _IQmpy(gMotorVars.Vq,gMotorVars.Vq));
// 以安培为单位读取id和iq矢量 read Id and Iq vectors in amps
gMotorVars.Id_A = _IQmpy(gIdq_pu.value[0],
_IQ(USER_IQ_FULL_SCALE_CURRENT_A));
gMotorVars.Iq_A = _IQmpy(gIdq_pu.value[1],
_IQ(USER_IQ_FULL_SCALE_CURRENT_A));
// 计算矢量单位为安培:(Is_a=sqrt(id_a^2+iq_a^2)) calculate vector Is in amps: (Is_A = sqrt(Id_A^2 + Iq_A^2))
gMotorVars.Is_A = _IQsqrt(_IQmpy(gMotorVars.Id_A,gMotorVars.Id_A)
+ _IQmpy(gMotorVars.Iq_A,gMotorVars.Iq_A));
return;
}