Skip to content

Instantly share code, notes, and snippets.

@dotchang
Last active January 4, 2017 06:57
Show Gist options
  • Save dotchang/bed04d81003538c26b342f63caa37f74 to your computer and use it in GitHub Desktop.
Save dotchang/bed04d81003538c26b342f63caa37f74 to your computer and use it in GitHub Desktop.
/* --COPYRIGHT--,BSD
* Copyright (c) 2012, Texas Instruments Incorporated
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* * Neither the name of Texas Instruments Incorporated nor the names of
* its contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
* OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* --/COPYRIGHT--*/
//! \file solutions/instaspin_foc/src/proj_lab05b.c
//! \brief Adjusting the speed controller
//!
//! (C) Copyright 2011, Texas Instruments, Inc.
//! \defgroup PROJ_LAB05b PROJ_LAB05b
//@{
//! \defgroup PROJ_LAB05b_OVERVIEW Project Overview
//!
//! Adjusting the supplied speed controller
//!
//! https://github.com/256shadesofgrey/instaspin_foc-SCI-eCAP/blob/master/proj_lab05a_with_SCI_and_eCAP/proj_lab05a.c
// **************************************************************************
// the includes
// system includes
#include <math.h>
#include "main.h"
//#define HW_SW 1 in hal.h
//#define CAP
//#define SCI 1 in sci.h
#define _lab07
//#define _lab09
#ifdef FLASH
#pragma CODE_SECTION(mainISR,"ramfuncs");
#endif
// Include header files used in the main function
// **************************************************************************
// the defines
#define LED_BLINK_FREQ_Hz 5
#ifdef SCI
#define uint8_t char
#define ECHO_ON 1 // set 1 to show input and 0 to disable it
#define BUF_LEN 8 // length of the command buffer
#endif
#ifdef HW_POT
#define HAL_ADCINA6 ADC_ResultNumber_8
#define HAL_ADCINA4 ADC_ResultNumber_9
#define HAL_ADCINA2 ADC_ResultNumber_10
_iq gPotentiometerA = _IQ(0.0);
_iq gPotentiometerB = _IQ(0.0);
_iq gSw2 = _IQ(0.0);
#endif
#ifdef HW_SW
//! \brief Defines the GPIO pin number for f28027f and drv8305EVM external Switch1
//!
#define HAL_GPIO_SW1 GPIO_Number_34
bool gSw1 = false;
#endif
// **************************************************************************
// the globals
#ifdef CAP
uint32_t ECap1IntCount = 0;
uint32_t CAP_DATA[] = {0,0/*,0,0*/};
#endif // CAP
//Added by Maya
#ifdef SCI
char cmdBuf[BUF_LEN]; // Input/command buffer
uint8_t bufPos = 0; // Position of the next char in the buffer
uint8_t cmdReady = 0; // Indicates that a command is ready for execution and blocks further input until reset to 0.
char * msg;
uint16_t ReceivedChar = 0;
//uint16_t RXISRCount = 0;
//uint16_t SysCounter = 0;
#endif // SCI
uint_least16_t gCounter_updateGlobals = 0;
bool Flag_Latch_softwareUpdate = true;
CTRL_Handle ctrlHandle;
#ifdef CSM_ENABLE
#pragma DATA_SECTION(halHandle,"rom_accessed_data");
#endif
HAL_Handle halHandle;
#ifdef CSM_ENABLE
#pragma DATA_SECTION(gUserParams,"rom_accessed_data");
#endif
USER_Params gUserParams;
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)};
HAL_AdcData_t gAdcData;
#ifdef _lab07
FEM_Handle femHandle;
FEM_Obj fem;
uint32_t gNumFreqErrors = 0;
uint32_t gMaxDeltaCntObserved = 0;
CPU_USAGE_Handle cpu_usageHandle;
CPU_USAGE_Obj cpu_usage;
float_t gCpuUsagePercentageMin = 0.0;
float_t gCpuUsagePercentageAvg = 0.0;
float_t gCpuUsagePercentageMax = 0.0;
#endif // _lab07
_iq gMaxCurrentSlope = _IQ(0.0);
#ifdef FAST_ROM_V1p6
CTRL_Obj *controller_obj;
#else
#ifdef CSM_ENABLE
#pragma DATA_SECTION(ctrl,"rom_accessed_data");
#endif
CTRL_Obj ctrl; //v1p7 format
#endif
uint16_t gLEDcnt = 0;
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT;
#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 _lab09
FW_Obj fw;
FW_Handle fwHandle;
_iq Iq_Max_pu;
#endif //_lab09
#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;
// **************************************************************************
// the functions
void main(void)
{
uint_least8_t estNumber = 0;
#ifdef FAST_ROM_V1p6
uint_least8_t ctrlNumber = 1; // lab05 = 0, lab07, 09 = 1
#endif
// Only used if running from FLASH
// Note that the variable FLASH is defined by the project
#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
// initialize the hardware abstraction layer
halHandle = HAL_init(&hal,sizeof(hal));
// check for errors in user parameters
USER_checkForErrors(&gUserParams);
// store user parameter error in global variable
gMotorVars.UserErrorCode = USER_getErrorCode(&gUserParams);
// do not allow code execution if there is a user parameter error
if(gMotorVars.UserErrorCode != USER_ErrorCode_NoError)
{
for(;;)
{
gMotorVars.Flag_enableSys = false;
}
}
// initialize the user parameters
USER_setParams(&gUserParams);
// set the hardware abstraction layer parameters
HAL_setParams(halHandle,&gUserParams);
// initialize the controller
#ifdef FAST_ROM_V1p6
ctrlHandle = CTRL_initCtrl(ctrlNumber, estNumber); //v1p6 format (06xF and 06xM devices)
controller_obj = (CTRL_Obj *)ctrlHandle;
#else
ctrlHandle = CTRL_initCtrl(estNumber,&ctrl,sizeof(ctrl)); //v1p7 format default
#endif
{
CTRL_Version version;
// get the version number
CTRL_getVersion(ctrlHandle,&version);
gMotorVars.CtrlVersion = version;
}
// set the default controller parameters
CTRL_setParams(ctrlHandle,&gUserParams);
#ifdef _lab07
// initialize the frequency of execution monitoring module
femHandle = FEM_init(&fem,sizeof(fem));
FEM_setParams(femHandle,
USER_SYSTEM_FREQ_MHz * 1000000.0, // timer frequency, Hz
(uint32_t)USER_SYSTEM_FREQ_MHz * 1000000, // timer period, cnts
USER_CTRL_FREQ_Hz, // set point frequency, Hz
1000.0); // max frequency error, Hz
// initialize the CPU usage module
cpu_usageHandle = CPU_USAGE_init(&cpu_usage,sizeof(cpu_usage));
CPU_USAGE_setParams(cpu_usageHandle,
(uint32_t)USER_SYSTEM_FREQ_MHz * 1000000, // timer period, cnts
(uint32_t)USER_ISR_FREQ_Hz); // average over 1 second of ISRs
#endif // _lab07
#ifdef _lab09
// Initialize field weakening
fwHandle = FW_init(&fw,sizeof(fw));
// Disable field weakening
FW_setFlag_enableFw(fwHandle, false);
// Clear field weakening counter
FW_clearCounter(fwHandle);
// Set the number of ISR per field weakening ticks
FW_setNumIsrTicksPerFwTick(fwHandle, FW_NUM_ISR_TICKS_PER_CTRL_TICK);
// Set the deltas of field weakening
FW_setDeltas(fwHandle, FW_INC_DELTA, FW_DEC_DELTA);
// Set initial output of field weakening to zero
FW_setOutput(fwHandle, _IQ(0.0));
// Set the field weakening controller limits
FW_setMinMax(fwHandle,_IQ(USER_MAX_NEGATIVE_ID_REF_CURRENT_A/USER_IQ_FULL_SCALE_CURRENT_A),_IQ(0.0));
#endif // _lab09
// setup faults
HAL_setupFaults(halHandle);
// initialize the interrupt vector table
HAL_initIntVectorTable(halHandle);
// enable the ADC interrupts
HAL_enableAdcInts(halHandle);
#ifdef _lab07
// reload timer to start running frequency of execution monitoring
HAL_reloadTimer(halHandle,0);
#endif // _lab07
// enable global interrupts
HAL_enableGlobalInts(halHandle);
// enable debug interrupts
HAL_enableDebugInt(halHandle);
// disable the PWM
HAL_disablePwm(halHandle);
#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
// enable DC bus compensation
CTRL_setFlag_enableDcBusComp(ctrlHandle, true);
// 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();
for(;;)
{
// Waiting for enable system flag to be set
while(!(gMotorVars.Flag_enableSys));
#ifdef _lab09
Flag_Latch_softwareUpdate = true;
#endif // _lab09
// Enable the Library internal PI. Iq is referenced by the speed PI now
CTRL_setFlag_enableSpeedCtrl(ctrlHandle, true);
// loop while the enable system flag is true
while(gMotorVars.Flag_enableSys)
{
CTRL_Obj *obj = (CTRL_Obj *)ctrlHandle;
// increment counters
gCounter_updateGlobals++;
// enable/disable the use of motor parameters being loaded from user.h
CTRL_setFlag_enableUserMotorParams(ctrlHandle,gMotorVars.Flag_enableUserParams);
// enable/disable Rs recalibration during motor startup
EST_setFlag_enableRsRecalc(obj->estHandle,gMotorVars.Flag_enableRsRecalc);
// enable/disable automatic calculation of bias values
CTRL_setFlag_enableOffset(ctrlHandle,gMotorVars.Flag_enableOffsetcalc);
if(CTRL_isError(ctrlHandle))
{
// set the enable controller flag to false
CTRL_setFlag_enableCtrl(ctrlHandle,false);
// set the enable system flag to false
gMotorVars.Flag_enableSys = false;
// disable the PWM
HAL_disablePwm(halHandle);
}
else
{
// update the controller state
bool flag_ctrlStateChanged = CTRL_updateState(ctrlHandle);
// enable or disable the control
CTRL_setFlag_enableCtrl(ctrlHandle, gMotorVars.Flag_Run_Identify);
if(flag_ctrlStateChanged)
{
CTRL_State_e ctrlState = CTRL_getState(ctrlHandle);
if(ctrlState == CTRL_State_OffLine)
{
// enable the PWM
HAL_enablePwm(halHandle);
}
else if(ctrlState == CTRL_State_OnLine)
{
if(gMotorVars.Flag_enableOffsetcalc == true)
{
// update the ADC bias values
HAL_updateAdcBias(halHandle);
}
else
{
// set the current bias
HAL_setBias(halHandle,HAL_SensorType_Current,0,_IQ(I_A_offset));
HAL_setBias(halHandle,HAL_SensorType_Current,1,_IQ(I_B_offset));
HAL_setBias(halHandle,HAL_SensorType_Current,2,_IQ(I_C_offset));
// set the voltage bias
HAL_setBias(halHandle,HAL_SensorType_Voltage,0,_IQ(V_A_offset));
HAL_setBias(halHandle,HAL_SensorType_Voltage,1,_IQ(V_B_offset));
HAL_setBias(halHandle,HAL_SensorType_Voltage,2,_IQ(V_C_offset));
}
// Return the bias value for currents
gMotorVars.I_bias.value[0] = HAL_getBias(halHandle,HAL_SensorType_Current,0);
gMotorVars.I_bias.value[1] = HAL_getBias(halHandle,HAL_SensorType_Current,1);
gMotorVars.I_bias.value[2] = HAL_getBias(halHandle,HAL_SensorType_Current,2);
// Return the bias value for voltages
gMotorVars.V_bias.value[0] = HAL_getBias(halHandle,HAL_SensorType_Voltage,0);
gMotorVars.V_bias.value[1] = HAL_getBias(halHandle,HAL_SensorType_Voltage,1);
gMotorVars.V_bias.value[2] = HAL_getBias(halHandle,HAL_SensorType_Voltage,2);
// enable the PWM
HAL_enablePwm(halHandle);
}
else if(ctrlState == CTRL_State_Idle)
{
// disable the PWM
HAL_disablePwm(halHandle);
gMotorVars.Flag_Run_Identify = false;
}
if((CTRL_getFlag_enableUserMotorParams(ctrlHandle) == true) &&
(ctrlState > CTRL_State_Idle) &&
(gMotorVars.CtrlVersion.minor == 6))
{
// call this function to fix 1p6
USER_softwareUpdate1p6(ctrlHandle);
}
}
}
if(EST_isMotorIdentified(obj->estHandle))
{
#ifdef _lab09
_iq Is_Max_squared_pu = _IQ((USER_MOTOR_MAX_CURRENT*USER_MOTOR_MAX_CURRENT)/ \
(USER_IQ_FULL_SCALE_CURRENT_A*USER_IQ_FULL_SCALE_CURRENT_A));
_iq Id_squared_pu = _IQmpy(CTRL_getId_ref_pu(ctrlHandle),CTRL_getId_ref_pu(ctrlHandle));
// Take into consideration that Iq^2+Id^2 = Is^2
Iq_Max_pu = _IQsqrt(Is_Max_squared_pu-Id_squared_pu);
//Set new max trajectory
CTRL_setSpdMax(ctrlHandle, Iq_Max_pu);
#endif // _lab09
// set the current ramp
EST_setMaxCurrentSlope_pu(obj->estHandle,gMaxCurrentSlope);
gMotorVars.Flag_MotorIdentified = true;
#ifdef HW_POT
// SpeedRef from POT_A
_iq tmp_speed = _IQmpy(gPotentiometerA, _IQ(4.444))-_IQ(0.222);
if(tmp_speed < _IQ(0.0)) tmp_speed = _IQ(0.0);
if(gSw1){
gMotorVars.SpeedRef_krpm = _IQmpy(tmp_speed, _IQ(1.0));
}
elsee {
gMotorVars.SpeedRef_krpm = _IQmpy(tmp_speed, _IQ(-1.0));
}
gMotorVars.MaxAccel_krpms = _IQmpy(gPotentiometerB + _IQ(0.001), _IQ(20.0));
#endif
// set the speed reference
CTRL_setSpd_ref_krpm(ctrlHandle,gMotorVars.SpeedRef_krpm);
// set the speed acceleration
CTRL_setMaxAccel_pu(ctrlHandle,_IQmpy(MAX_ACCEL_KRPMPS_SF,gMotorVars.MaxAccel_krpmps));
if(Flag_Latch_softwareUpdate)
{
Flag_Latch_softwareUpdate = false;
USER_calcPIgains(ctrlHandle);
// initialize the watch window kp and ki current values with pre-calculated values
gMotorVars.Kp_Idq = CTRL_getKp(ctrlHandle,CTRL_Type_PID_Id);
gMotorVars.Ki_Idq = CTRL_getKi(ctrlHandle,CTRL_Type_PID_Id);
#ifndef _lab09
// initialize the watch window kp and ki values with pre-calculated values
gMotorVars.Kp_spd = CTRL_getKp(ctrlHandle,CTRL_Type_PID_spd);
gMotorVars.Ki_spd = CTRL_getKi(ctrlHandle,CTRL_Type_PID_spd);
#endif // _lab09
}
}
else
{
Flag_Latch_softwareUpdate = true;
#ifdef _lab09
// initialize the watch window kp and ki values with pre-calculated values
gMotorVars.Kp_spd = CTRL_getKp(ctrlHandle,CTRL_Type_PID_spd);
gMotorVars.Ki_spd = CTRL_getKi(ctrlHandle,CTRL_Type_PID_spd);
#endif // _lab09
// the estimator sets the maximum current slope during identification
gMaxCurrentSlope = EST_getMaxCurrentSlope_pu(obj->estHandle);
}
// when appropriate, update the global variables
if(gCounter_updateGlobals >= NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE)
{
// reset the counter
gCounter_updateGlobals = 0;
updateGlobalVariables_motor(ctrlHandle);
}
// update Kp and Ki gains
updateKpKiGains(ctrlHandle);
#ifdef _lab07
// run Rs online
runRsOnLine(ctrlHandle);
// update CPU usage
updateCPUusage();
#endif // _lab07
#ifdef _lab09
// set field weakening enable flag depending on user's input
FW_setFlag_enableFw(fwHandle,gMotorVars.Flag_enableFieldWeakening);
#endif // _lab09
// enable/disable the forced angle
EST_setFlag_enableForceAngle(obj->estHandle,gMotorVars.Flag_enableForceAngle);
// enable or disable power warp
CTRL_setFlag_enablePowerWarp(ctrlHandle,gMotorVars.Flag_enablePowerWarp);
#ifdef DRV8301_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8301Vars);
HAL_readDrvData(halHandle,&gDrvSpi8301Vars);
#endif
#ifdef DRV8305_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8305Vars);
HAL_readDrvData(halHandle,&gDrvSpi8305Vars);
#endif
#ifdef _lab07
// get the maximum delta count observed
gMaxDeltaCntObserved = FEM_getMaxDeltaCntObserved(femHandle);
// check for errors
if(FEM_isFreqError(femHandle))
{
gNumFreqErrors = FEM_getErrorCnt(femHandle);
}
#endif // _lab07
} // end of while(gFlag_enableSys) loop
// disable the PWM
HAL_disablePwm(halHandle);
// set the default controller parameters (Reset the control to re-identify the motor)
CTRL_setParams(ctrlHandle,&gUserParams);
gMotorVars.Flag_Run_Identify = false;
} // end of for(;;) loop
} // end of main() function
interrupt void mainISR(void)
{
#ifdef _lab07
uint32_t timer0Cnt;
uint32_t timer1Cnt;
// read the timer 1 value and update the CPU usage module
timer1Cnt = HAL_readTimerCnt(halHandle,1);
CPU_USAGE_updateCnts(cpu_usageHandle,timer1Cnt);
// read the timer 0 value and update the FEM
timer0Cnt = HAL_readTimerCnt(halHandle,0);
FEM_updateCnts(femHandle,timer0Cnt);
FEM_run(femHandle);
#endif
// toggle status LED
if(gLEDcnt++ > (uint_least32_t)(USER_ISR_FREQ_Hz / LED_BLINK_FREQ_Hz))
{
HAL_toggleLed(halHandle,(GPIO_Number_e)HAL_Gpio_LED2);
gLEDcnt = 0;
}
// acknowledge the ADC interrupt
HAL_acqAdcInt(halHandle,ADC_IntNumber_1);
// convert the ADC data
HAL_readAdcData(halHandle,&gAdcData);
// run the controller
CTRL_run(ctrlHandle,halHandle,&gAdcData,&gPwmData);
// write the PWM compare values
HAL_writePwmData(halHandle,&gPwmData);
#ifdef _lab09
if(FW_getFlag_enableFw(fwHandle) == true)
{
FW_incCounter(fwHandle);
if(FW_getCounter(fwHandle) > FW_getNumIsrTicksPerFwTick(fwHandle))
{
_iq refValue;
_iq fbackValue;
_iq output;
FW_clearCounter(fwHandle);
refValue = gMotorVars.VsRef;
fbackValue = gMotorVars.Vs;
FW_run(fwHandle, refValue, fbackValue, &output);
CTRL_setId_ref_pu(ctrlHandle, output);
gMotorVars.IdRef_A = _IQmpy(CTRL_getId_ref_pu(ctrlHandle), _IQ(USER_IQ_FULL_SCALE_CURRENT_A));
}
}
else
{
CTRL_setId_ref_pu(ctrlHandle, _IQmpy(gMotorVars.IdRef_A, _IQ(1.0/USER_IQ_FULL_SCALE_CURRENT_A)));
}
#endif // _lab09
// setup the controller
CTRL_setup(ctrlHandle);
#ifdef _lab07
// read the timer 1 value and update the CPU usage module
timer1Cnt = HAL_readTimerCnt(halHandle,1);
CPU_USAGE_updateCnts(cpu_usageHandle,timer1Cnt);
// run the CPU usage module
CPU_USAGE_run(cpu_usageHandle);
#endif // _lab07
#ifdef HW_POT
gPotentiometerA = HAL_readPotentiometerData(halHandle, HAL_ADCINA6);
gPotentiometerB = HAL_readPotentiometerData(halHandle, HAL_ADCINA4);
gSw2 = HAL_readPotentiometerData(halHandle, HAL_ADCINA2);
#endif
#ifdef HW_SW
gSw1 = HAL_readGpio(halHandle, HAL_GPIO_SW1);
#endif
return;
} // end of mainISR() function
void updateGlobalVariables_motor(CTRL_Handle handle)
{
CTRL_Obj *obj = (CTRL_Obj *)handle;
// get the speed estimate
gMotorVars.Speed_krpm = EST_getSpeed_krpm(obj->estHandle);
// get the real time speed reference coming out of the speed trajectory generator
gMotorVars.SpeedTraj_krpm = _IQmpy(CTRL_getSpd_int_ref_pu(handle),EST_get_pu_to_krpm_sf(obj->estHandle));
// get the torque estimate
gMotorVars.Torque_Nm = USER_computeTorque_Nm(handle, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf);
// get the magnetizing current
gMotorVars.MagnCurr_A = EST_getIdRated(obj->estHandle);
// get the rotor resistance
gMotorVars.Rr_Ohm = EST_getRr_Ohm(obj->estHandle);
// get the stator resistance
gMotorVars.Rs_Ohm = EST_getRs_Ohm(obj->estHandle);
#ifdef _lab07
// get the stator resistance online
gMotorVars.RsOnLine_Ohm = EST_getRsOnLine_Ohm(obj->estHandle);
#endif // _lab07
// get the stator inductance in the direct coordinate direction
gMotorVars.Lsd_H = EST_getLs_d_H(obj->estHandle);
// get the stator inductance in the quadrature coordinate direction
gMotorVars.Lsq_H = EST_getLs_q_H(obj->estHandle);
// get the flux in V/Hz in floating point
gMotorVars.Flux_VpHz = EST_getFlux_VpHz(obj->estHandle);
// get the flux in Wb in fixed point
gMotorVars.Flux_Wb = USER_computeFlux(handle, gFlux_pu_to_Wb_sf);
// get the controller state
gMotorVars.CtrlState = CTRL_getState(handle);
// get the estimator state
gMotorVars.EstState = EST_getState(obj->estHandle);
#ifdef _lab09
// read Vd and Vq vectors per units
gMotorVars.Vd = CTRL_getVd_out_pu(ctrlHandle);
gMotorVars.Vq = CTRL_getVq_out_pu(ctrlHandle);
// calculate vector Vs in per units
gMotorVars.Vs = _IQsqrt(_IQmpy(gMotorVars.Vd, gMotorVars.Vd) + _IQmpy(gMotorVars.Vq, gMotorVars.Vq));
// read Id and Iq vectors in amps
gMotorVars.Id_A = _IQmpy(CTRL_getId_in_pu(ctrlHandle), _IQ(USER_IQ_FULL_SCALE_CURRENT_A));
gMotorVars.Iq_A = _IQmpy(CTRL_getIq_in_pu(ctrlHandle), _IQ(USER_IQ_FULL_SCALE_CURRENT_A));
// calculate vector Is in amps
gMotorVars.Is_A = _IQsqrt(_IQmpy(gMotorVars.Id_A, gMotorVars.Id_A) + _IQmpy(gMotorVars.Iq_A, gMotorVars.Iq_A));
#endif
// Get the DC buss voltage
gMotorVars.VdcBus_kV = _IQmpy(gAdcData.dcBus,_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0));
return;
} // end of updateGlobalVariables_motor() function
void updateKpKiGains(CTRL_Handle handle)
{
if((gMotorVars.CtrlState == CTRL_State_OnLine) && (gMotorVars.Flag_MotorIdentified == true) && (Flag_Latch_softwareUpdate == false))
{
// set the kp and ki speed values from the watch window
CTRL_setKp(handle,CTRL_Type_PID_spd,gMotorVars.Kp_spd);
CTRL_setKi(handle,CTRL_Type_PID_spd,gMotorVars.Ki_spd);
// set the kp and ki current values for Id and Iq from the watch window
CTRL_setKp(handle,CTRL_Type_PID_Id,gMotorVars.Kp_Idq);
CTRL_setKi(handle,CTRL_Type_PID_Id,gMotorVars.Ki_Idq);
CTRL_setKp(handle,CTRL_Type_PID_Iq,gMotorVars.Kp_Idq);
CTRL_setKi(handle,CTRL_Type_PID_Iq,gMotorVars.Ki_Idq);
}
return;
} // end of updateKpKiGains() function
#ifdef _lab07
void runRsOnLine(CTRL_Handle handle)
{
CTRL_Obj *obj = (CTRL_Obj *)handle;
// execute Rs OnLine code
if(gMotorVars.Flag_Run_Identify == true)
{
if(EST_getState(obj->estHandle) == EST_State_OnLine)
{
float_t RsError_Ohm = gMotorVars.RsOnLine_Ohm - gMotorVars.Rs_Ohm;
EST_setFlag_enableRsOnLine(obj->estHandle,true);
EST_setRsOnLineId_mag_pu(obj->estHandle,_IQmpy(gMotorVars.RsOnLineCurrent_A,_IQ(1.0/USER_IQ_FULL_SCALE_CURRENT_A)));
if(abs(RsError_Ohm) < (gMotorVars.Rs_Ohm * 0.05))
{
EST_setFlag_updateRs(obj->estHandle,true);
}
}
else
{
EST_setRsOnLineId_mag_pu(obj->estHandle,_IQ(0.0));
EST_setRsOnLineId_pu(obj->estHandle,_IQ(0.0));
EST_setRsOnLine_pu(obj->estHandle,_IQ(0.0));
EST_setFlag_enableRsOnLine(obj->estHandle,false);
EST_setFlag_updateRs(obj->estHandle,false);
EST_setRsOnLine_qFmt(obj->estHandle,EST_getRs_qFmt(obj->estHandle));
}
}
return;
} // end of runRsOnLine() function
void updateCPUusage(void)
{
uint32_t minDeltaCntObserved = CPU_USAGE_getMinDeltaCntObserved(cpu_usageHandle);
uint32_t avgDeltaCntObserved = CPU_USAGE_getAvgDeltaCntObserved(cpu_usageHandle);
uint32_t maxDeltaCntObserved = CPU_USAGE_getMaxDeltaCntObserved(cpu_usageHandle);
uint16_t pwmPeriod = HAL_readPwmPeriod(halHandle,PWM_Number_1);
float_t cpu_usage_den = (float_t)pwmPeriod * (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK * 2.0;
// calculate the minimum cpu usage percentage
gCpuUsagePercentageMin = (float_t)minDeltaCntObserved / cpu_usage_den * 100.0;
// calculate the average cpu usage percentage
gCpuUsagePercentageAvg = (float_t)avgDeltaCntObserved / cpu_usage_den * 100.0;
// calculate the maximum cpu usage percentage
gCpuUsagePercentageMax = (float_t)maxDeltaCntObserved / cpu_usage_den * 100.0;
return;
} // end of updateCPUusage() function
#endif // _lab07
//Added by Maya
#ifdef SCI
interrupt void sciaISR(void) {
//RXISRCount++;
ReceivedChar = HAL_sciaRead(halHandle) & 0x00FF;
//Handling escape.
if(ReceivedChar != 27){
//Handling carriage return/new line.
if(ReceivedChar != '\r' && ReceivedChar != '\n' && cmdReady == 0){
//Show input.
if(ECHO_ON){
HAL_sciaWrite(halHandle, ReceivedChar);
}
//Handling backspace/delete.
if(ReceivedChar != 127 && ReceivedChar != 8){
bufPos++;
//If the end of the buffer wasn't reached, add new char to the buffer.
if(bufPos < BUF_LEN){
cmdBuf[bufPos-1] = (char)ReceivedChar; //Adding char.
cmdBuf[bufPos] = '\0'; //Appending null to indicate the end of the string.
}
}else{
//If the beginning of the buffer wasn't reached, remove the previous char from the buffer.
if(bufPos > 0){
bufPos--;
//Only delete if within buffer range.
if(bufPos < BUF_LEN){
cmdBuf[bufPos] = '\0';
}
}
}
}else if(cmdReady == 0){ //If enter was pressed, start new line and set cmdReady flag.
msg = "\n\r";
HAL_sciaWriteMsg(halHandle, msg);
cmdReady = 1;
}
}else{ //If escape is pressed, reset command buffer and clear cmdReady flag.
cmdReady = 0;
bufPos = 0;
cmdBuf[0] = '\0';
}
HAL_sciaClearRxFifoOvf(halHandle);
HAL_sciaClearRxFifoInt(halHandle);
HAL_pieAckInt(halHandle,PIE_GroupNumber_9); // Issue PIE ack INT9
return;
}
#endif
//Added by Dmitri Ranfft on 16.09.2015
#ifdef CAP
__interrupt void ecap1ISR(void)
{
//scia_msg("interrupt\n\r");
// Cap input is syc'ed to SYSCLKOUT so there may be
// a +/- 1 cycle variation
CAP_DATA[0] = CAP_getCap1(halHandle->capHandle);
CAP_DATA[1] = CAP_getCap2(halHandle->capHandle);
//CAP_DATA[2] = CAP_getCap3(halHandle->capHandle);
//CAP_DATA[3] = CAP_getCap4(halHandle->capHandle);
ECap1IntCount++;
CAP_clearInt(halHandle->capHandle, CAP_Int_Type_CEVT2);
CAP_clearInt(halHandle->capHandle, CAP_Int_Type_Global);
CAP_rearm(halHandle->capHandle);
// Acknowledge this interrupt to receive more interrupts from group 4
PIE_clearInt(halHandle->pieHandle, PIE_GroupNumber_4);
}
#endif
//@} //defgroup
// end of file
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment