Other Parts Discussed in Thread: MOTORWARE
Tool/software: Code Composer Studio
/* --COPYRIGHT--,BSD * Copyright (c) 2012, LineStream Technologies Incorporated * 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 names of Texas Instruments Incorporated, LineStream * Technologies 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_motion/src/proj_lab05d.c //! \brief InstaSPIN-MOTION SpinTAC Speed Controller //! //! (C) Copyright 2012, LineStream Technologies, Inc. //! (C) Copyright 2011, Texas Instruments, Inc. //! \defgroup PROJ_LAB05d PROJ_LAB05d //@{ //! \defgroup PROJ_LAB05d_OVERVIEW Project Overview //! //! Running the SpinTAC Velocity Controller //! // ************************************************************************** // the includes // system includes #include <math.h> #include "main.h" //#include "DSP28x_Project.h" // Device Headerfile and Examples Include File //#include "stdio.h" //#include "sw/drivers/can/src/32b/f28x/f2806x/can.h" //#pragma DATA_SECTION(ECanaRegs,"ECanaRegsFile"); //volatile struct ECAN_REGS ECanaRegs; //#pragma DATA_SECTION(ECanaMboxes,"ECanaMboxesFile"); //volatile struct ECAN_MBOXES ECanaMboxes; #ifdef FLASH #pragma CODE_SECTION(mainISR,"ramfuncs"); #endif // Include header files used in the main function // ************************************************************************ // the defines #define LED_BLINK_FREQ_Hz 5 // ************************************************************************** // the globals uint_least16_t gCounter_updateGlobals = 0; bool Flag_Latch_softwareUpdate = true; CTRL_Handle ctrlHandle; HAL_Handle halHandle; USER_Params gUserParams; HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}; HAL_AdcData_t gAdcData; _iq gMaxCurrentSlope = _IQ(0.0); #ifdef FAST_ROM_V1p6 CTRL_Obj *controller_obj; #else CTRL_Obj ctrl; //v1p7 format #endif ST_Obj st_obj; ST_Handle stHandle; 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; #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; // ************************************************************************** // In future declare variables over here void InitECana(void); void InitECanaGpio(void); void spi_init(void); void spi_fifo_init(void); void delay(float n); unsigned long spi_xmit(unsigned long a); Uint16 sdata=0x0000; // s3end data Uint16 rdata1=0; // received data Uint16 rdata2=0; Uint16 rdata3=0; Uint16 rdata4=0; Uint16 rdata5=0; Uint16 rdata6=0; Uint32 byte7=0; Uint32 fbyte3=0; Uint16 fbyte4=0; Uint32 fibyte3=0; Uint32 fiibyte3=0; Uint32 fibyte4=0; Uint32 fibyte5=0; long i; //long loopcount=0; //volatile struct ECAN_REGS ECanaShadow; void main(void) { //struct ECAN_REGS ECanaShadow; uint_least8_t estNumber = 0; #ifdef FAST_ROM_V1p6 uint_least8_t ctrlNumber = 0; #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); #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); // 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); // initialize the SpinTAC Components stHandle = ST_init(&st_obj, sizeof(st_obj)); // setup the SpinTAC Components ST_setupVelCtl(stHandle); #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(); InitSysCtrl(); // EALLOW; // InitECana(); // InitECanaGpio(); EALLOW; /* Write to the MSGID field */ // ECanaMboxes.MBOX25.MSGID.all = 0x95555555; // EDIS; // Configure Mailbox under test as a Transmit mailbox // ECanaShadow.CANMD.all = ECanaRegs.CANMD.all; //ECanaShadow.CANMD.bit.MD25 = 0; // ECanaRegs.CANMD.all = ECanaShadow.CANMD.all; // Enable Mailbox under test // ECanaShadow.CANME.all = ECanaRegs.CANME.all; // ECanaShadow.CANME.bit.ME25 = 1; // ECanaRegs.CANME.all = ECanaShadow.CANME.all; /* Write to DLC field in Message Control reg */ // ECanaMboxes.MBOX25.MSGCTRL.bit.DLC = 8; void spi_init(void); for(;;) { // Waiting for enable system flag to be set while(!(gMotorVars.Flag_enableSys)); // Dis-able the Library internal PI. Iq has no reference now CTRL_setFlag_enableSpeedCtrl(ctrlHandle, false); // loop while the enable system flag is true while(gMotorVars.Flag_enableSys) { CTRL_Obj *obj = (CTRL_Obj *)ctrlHandle; ST_Obj *stObj = (ST_Obj *)stHandle; // 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)) { // set the current ramp EST_setMaxCurrentSlope_pu(obj->estHandle,gMaxCurrentSlope); gMotorVars.Flag_MotorIdentified = true; // 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)); // enable the SpinTAC Speed Controller STVELCTL_setEnable(stObj->velCtlHandle, true); if(EST_getState(obj->estHandle) != EST_State_OnLine) { // if the estimator is not running, place SpinTAC into reset STVELCTL_setEnable(stObj->velCtlHandle, false); } 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); // initialize the watch window with maximum and minimum Iq reference gMotorVars.SpinTAC.VelCtlOutputMax_A = _IQmpy(STVELCTL_getOutputMaximum(stObj->velCtlHandle), _IQ(USER_IQ_FULL_SCALE_CURRENT_A)); gMotorVars.SpinTAC.VelCtlOutputMin_A = _IQmpy(STVELCTL_getOutputMinimum(stObj->velCtlHandle), _IQ(USER_IQ_FULL_SCALE_CURRENT_A)); } } else { Flag_Latch_softwareUpdate = true; // 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, stHandle); } // update Kp and Ki gains updateKpKiGains(ctrlHandle); // set the maximum and minimum values for Iq reference STVELCTL_setOutputMaximums(stObj->velCtlHandle, _IQmpy(gMotorVars.SpinTAC.VelCtlOutputMax_A, _IQ(1.0/USER_IQ_FULL_SCALE_CURRENT_A)), _IQmpy(gMotorVars.SpinTAC.VelCtlOutputMin_A, _IQ(1.0/USER_IQ_FULL_SCALE_CURRENT_A))); // 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 } // 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; // setup the SpinTAC Components ST_setupVelCtl(stHandle); } // end of for(;;) loop // asm(" ESTOP0"); } // end of main() function interrupt void mainISR(void) { static uint16_t stCnt = 0; // 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 SpinTAC Components if(stCnt++ >= ISR_TICKS_PER_SPINTAC_TICK) { ST_runVelCtl(stHandle, ctrlHandle); stCnt = 1; } // run the controller CTRL_run(ctrlHandle,halHandle,&gAdcData,&gPwmData); // write the PWM compare values HAL_writePwmData(halHandle,&gPwmData); // setup the controller CTRL_setup(ctrlHandle); // Transmit data spi_xmit(sdata); // Wait until data is received while(SpiaRegs.SPIFFRX.bit.RXFFST !=1) { } // while(SpiaRegs.SPISTS.bit.INT_FLAG !=1) { } // Check against sent data rdata1 = SpiaRegs.SPIRXBUF ; delay(10); spi_xmit(sdata); // Wait until data is received while(SpiaRegs.SPIFFRX.bit.RXFFST !=1) { } //while(SpiaRegs.SPISTS.bit.INT_FLAG !=1) { } // Check against sent data rdata2 = SpiaRegs.SPIRXBUF ; delay(10); spi_xmit(sdata); // Wait until data is received while(SpiaRegs.SPIFFRX.bit.RXFFST !=1) { } //while(SpiaRegs.SPISTS.bit.INT_FLAG !=1) { } // Check against sent data rdata3 = SpiaRegs.SPIRXBUF ; delay(10); spi_xmit(sdata); // Wait until data is received while(SpiaRegs.SPIFFRX.bit.RXFFST !=1) { } //while(SpiaRegs.SPISTS.bit.INT_FLAG !=1) { } // Check against sent data rdata4 = SpiaRegs.SPIRXBUF; delay(10); spi_xmit(sdata); // Wait until data is received while(SpiaRegs.SPIFFRX.bit.RXFFST !=1) { } //while(SpiaRegs.SPISTS.bit.INT_FLAG !=1) { } // Check against sent data rdata5 = SpiaRegs.SPIRXBUF ; delay(10); spi_xmit(sdata); // Wait until data is received while(SpiaRegs.SPIFFRX.bit.RXFFST !=1) { } //while(SpiaRegs.SPISTS.bit.INT_FLAG !=1) { } // Check against sent data rdata6 = SpiaRegs.SPIRXBUF ; delay(10); fbyte3 = rdata3 & 0x03; fibyte3 = fbyte3<< 0x08; fiibyte3= fibyte3<<0x08; fbyte4 = rdata4<< 0x08; fibyte4 = fiibyte3 | fbyte4; fibyte5 = (rdata5 | fibyte4); byte7 = (fibyte5*360)/262144;// position data // ECanaMboxes.MBOX25.MDL.all = byte7; // ECanaMboxes.MBOX25.MDH.all = 0x00000000; return; } // end of mainISR() function asm(" ESTOP0"); void spi_init() { SpiaRegs.SPICCR.all =0x0007; // Reset on, rising edge, 16-bit char bits SpiaRegs.SPICTL.all =0x0007; // Enable master mode, normal phase, // enable talk, and SPI int disabled. SpiaRegs.SPIBRR =0X0004; SpiaRegs.SPICCR.all =0x00C7; // Relinquish SPI from Reset SpiaRegs.SPIPRI.bit.FREE = 1; // Set so breakpoints don't disturb xmission } /*void InitECanaGpio(void) { EALLOW; /* Enable internal pull-up for the selected CAN pins */ // Pull-ups can be enabled or disabled by the user. // This will enable the pullups for the specified pins. // Comment out other unwanted lines. /*GpioCtrlRegs.GPAPUD.bit.GPIO30 = 0; // Enable pull-up for GPIO30 (CANRXA) GpioCtrlRegs.GPAPUD.bit.GPIO31 = 0; // Enable pull-up for GPIO31 (CANTXA) /* Set qualification for selected CAN pins to asynch only */ // Inputs are synchronized to SYSCLKOUT by default. // This will select asynch (no qualification) for the selected pins. /* GpioCtrlRegs.GPAQSEL2.bit.GPIO30 = 3; // Asynch qual for GPIO30 (CANRXA) GpioCtrlRegs.GPAQSEL2.bit.GPIO31 = 3; // Asynch qual for GPIO31 (CANTXA) /* Configure eCAN-A pins using GPIO regs*/ // This specifies which of the possible GPIO pins will be eCAN functional pins. /* GpioCtrlRegs.GPAMUX2.bit.GPIO30 = 1; // Configure GPIO30 for CANRXA operation GpioCtrlRegs.GPAMUX2.bit.GPIO31 = 1; // Configure GPIO31 for CANTXA operation EDIS; } void InitECana(void) // Initialize eCAN-A module { /* Create a shadow register structure for the CAN control registers. This is needed, since only 32-bit access is allowed to these registers. 16-bit access to these registers could potentially corrupt the register contents or return false data. */ /* struct ECAN_REGS ECanaShadow; EALLOW; // EALLOW enables access to protected bits /* Configure eCAN RX and TX pins for CAN operation using eCAN regs*/ /* ECanaShadow.CANTIOC.all = ECanaRegs.CANTIOC.all; ECanaShadow.CANTIOC.bit.TXFUNC = 1; ECanaRegs.CANTIOC.all = ECanaShadow.CANTIOC.all; ECanaShadow.CANRIOC.all = ECanaRegs.CANRIOC.all; ECanaShadow.CANRIOC.bit.RXFUNC = 1; ECanaRegs.CANRIOC.all = ECanaShadow.CANRIOC.all; /* Configure eCAN for HECC mode - (reqd to access mailboxes 16 thru 31) */ // HECC mode also enables time-stamping feature /* ECanaShadow.CANMC.all = ECanaRegs.CANMC.all; ECanaShadow.CANMC.bit.SCB = 1; ECanaRegs.CANMC.all = ECanaShadow.CANMC.all; /* Initialize all bits of 'Message Control Register' to zero */ // Some bits of MSGCTRL register come up in an unknown state. For proper operation, // all bits (including reserved bits) of MSGCTRL must be initialized to zero /* ECanaMboxes.MBOX0.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX1.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX2.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX3.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX4.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX5.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX6.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX7.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX8.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX9.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX10.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX11.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX12.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX13.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX14.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX15.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX16.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX17.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX18.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX19.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX20.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX21.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX22.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX23.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX24.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX25.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX26.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX27.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX28.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX29.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX30.MSGCTRL.all = 0x00000000; ECanaMboxes.MBOX31.MSGCTRL.all = 0x00000000; // TAn, RMPn, GIFn bits are all zero upon reset and are cleared again // as a matter of precaution. ECanaRegs.CANTA.all = 0xFFFFFFFF; /* Clear all TAn bits */ /* ECanaRegs.CANRMP.all = 0xFFFFFFFF; /* Clear all RMPn bits */ /* ECanaRegs.CANGIF0.all = 0xFFFFFFFF; /* Clear all interrupt flag bits */ /* ECanaRegs.CANGIF1.all = 0xFFFFFFFF; /* Configure bit timing parameters for eCANA*/ /* ECanaShadow.CANMC.all = ECanaRegs.CANMC.all; ECanaShadow.CANMC.bit.CCR = 1 ; // Set CCR = 1 ECanaRegs.CANMC.all = ECanaShadow.CANMC.all; // Wait until the CPU has been granted permission to change the configuration registers do { ECanaShadow.CANES.all = ECanaRegs.CANES.all; } while(ECanaShadow.CANES.bit.CCE != 1 ); // Wait for CCE bit to be set.. ECanaShadow.CANBTC.all = 0; /* The following block is for 80 MHz SYSCLKOUT. (40 MHz CAN module clock Bit rate = 1 Mbps See Note at end of file. */ //ECanaShadow.CANBTC.all = 0x000503BD; // 500k /* ECanaShadow.CANBTC.bit.BRPREG = 1; ECanaShadow.CANBTC.bit.TSEG2REG = 2;//4 ECanaShadow.CANBTC.bit.TSEG1REG = 10;//13 ECanaShadow.CANBTC.bit.SAM = 0; // ECanaShadow.CANME.bit.SJW = 4; ECanaRegs.CANBTC.all = ECanaShadow.CANBTC.all; ECanaShadow.CANMC.all = ECanaRegs.CANMC.all; ECanaShadow.CANMC.bit.CCR = 0 ; // Set CCR = 0 ECanaRegs.CANMC.all = ECanaShadow.CANMC.all; // Wait until the CPU no longer has permission to change the configuration registers do { ECanaShadow.CANES.all = ECanaRegs.CANES.all; } while(ECanaShadow.CANES.bit.CCE != 0 ); // Wait for CCE bit to be cleared.. /* Disable all Mailboxes */ /* ECanaRegs.CANME.all = 0; // Required before writing the MSGIDs EDIS; }*/ void spi_fifo_init() { // Initialize SPI FIFO registers SpiaRegs.SPIFFTX.all=0xE040; SpiaRegs.SPIFFRX.all=0x2044; SpiaRegs.SPIFFCT.all=0x0; } void delay(float n) { short i; for (i = 0; i < n; i++) {} } unsigned long spi_xmit(unsigned long a) { SpiaRegs.SPITXBUF=a<<8; return a; } void updateGlobalVariables_motor(CTRL_Handle handle, ST_Handle sthandle) { CTRL_Obj *obj = (CTRL_Obj *)handle; ST_Obj *stObj = (ST_Obj *)sthandle; // 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); // 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); // Get the DC buss voltage gMotorVars.VdcBus_kV = _IQmpy(gAdcData.dcBus,_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); // get the Iq reference from the speed controller gMotorVars.IqRef_A = _IQmpy(STVELCTL_getTorqueReference(stObj->velCtlHandle), _IQ(USER_IQ_FULL_SCALE_CURRENT_A)); // gets the Velocity Controller status gMotorVars.SpinTAC.VelCtlStatus = STVELCTL_getStatus(stObj->velCtlHandle); // get the inertia setting gMotorVars.SpinTAC.InertiaEstimate_Aperkrpm = _IQmpy(STVELCTL_getInertia(stObj->velCtlHandle), _IQ(ST_SPEED_PU_PER_KRPM * USER_IQ_FULL_SCALE_CURRENT_A)); // get the friction setting gMotorVars.SpinTAC.FrictionEstimate_Aperkrpm = _IQmpy(STVELCTL_getFriction(stObj->velCtlHandle), _IQ(ST_SPEED_PU_PER_KRPM * USER_IQ_FULL_SCALE_CURRENT_A)); // get the Velocity Controller error gMotorVars.SpinTAC.VelCtlErrorID = STVELCTL_getErrorID(stObj->velCtlHandle); 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 void ST_runVelCtl(ST_Handle handle, CTRL_Handle ctrlHandle) { _iq speedFeedback, iqReference; ST_Obj *stObj = (ST_Obj *)handle; CTRL_Obj *ctrlObj = (CTRL_Obj *)ctrlHandle; // Get the mechanical speed in pu speedFeedback = EST_getFm_pu(ctrlObj->estHandle); // Run the SpinTAC Controller // Note that the library internal ramp generator is used to set the speed reference STVELCTL_setVelocityReference(stObj->velCtlHandle, TRAJ_getIntValue(ctrlObj->trajHandle_spd)); STVELCTL_setAccelerationReference(stObj->velCtlHandle, _IQ(0.0)); // Internal ramp generator does not provide Acceleration Reference STVELCTL_setVelocityFeedback(stObj->velCtlHandle, speedFeedback); STVELCTL_run(stObj->velCtlHandle); // select SpinTAC Velocity Controller iqReference = STVELCTL_getTorqueReference(stObj->velCtlHandle); // Set the Iq reference that came out of SpinTAC Velocity Control CTRL_setIq_ref_pu(ctrlHandle, iqReference); } //@} //defgroup // end of file