diff --git a/README.md b/README.md index 9ce1b22..8160083 100644 --- a/README.md +++ b/README.md @@ -112,9 +112,9 @@ To get started with TAPAS you will need the following (additional) items. + We highly recommend placing TAPAS in __a case__. This will keep your TAPAS board safe. The 3D model for our very own case can be found and downloaded here: -. +. If you don't own a 3D printer, many local 3D printing services are available on-line. -Print with temperature-stable materials like ABS (not PLA). +Print with temperature-stable materials like ABS (not PLA). + __DC power supply__ with a minimum of 12V and >3A continuous current output. Alternatively, you may use any battery with the correct voltage and an appropriate fuse in the supply line @@ -267,11 +267,14 @@ git clone https://github.com/SDI-SoftwareDefinedInverter/TAPAS.git We included a copy of TI motorware in the cloned repository (_`motorware.zip`_). Alternatively you can download motorware from Motorware or here . -As the TAPAS board definition is not part of the stock motorware package we have to make some modifications to it. All the necessary changes are contained in the patch-file _`SDITAPASmotorwarePatch.patch`_. Now copy _`SDITAPASmotorwarePatch.patch`_ to the motorware installation folder (usually _`C:\ti\`_) and start git in bash mode (also in the motorware installation folder). Then execute the following commands: +The zip contains a windows installer, which can also de used on linux via wine. + +As the TAPAS board definition is not part of the stock motorware package we have to make some modifications to it. All the necessary changes are contained in the patch-file _`TAPAS_patch_motorware.patch`_. Now copy _`TAPAS_patch_motorware.patch`_ to the motorware installation folder (usually _`C:\ti\`_) and start git in bash mode (also in the motorware installation folder). Then execute the following commands: ``` -dos2unix SDITAPASmotorwarePatch.patch -patch -p0 -i SDITAPASmotorwarePatch.patch +dos2unix TAPAS_patch_motorware.patch +find . -type f | xargs dos2unix {} \; #only for linux installation +patch -p0 -i TAPAS_patch_motorware.patch ``` This completes the installation of motorware und you can start playing with the motorware-labs @@ -304,7 +307,7 @@ To be able to run our TAPAS demo-webapp you also require the InstaSPIN-UNIVERSAL You have now completed the installation of the TAPAS development environment. We have also created a TAPAS-webapp to test all external I/O hardware. You can download it from: ``` -https://github.com/SDI-SoftwareDefinedInverter/TAPAS/blob/master/TAPASwebapp.zip +https://github.com/SDI-SoftwareDefinedInverter/TAPAS/blob/master/TAPAS_webapp.zip ``` Unzip the file place it in: @@ -344,11 +347,11 @@ board. To prevent this effect, limit the rate of change in motor velocity, use a The following documents can be helpful in developing with TAPAS: + TAPAS Pinout: - + + TAPAS Schematics: - + + This 13document(quick start guide): - + + InstaSPIN-FOC and InstaSPIN-MOTION user guide : + Instaspin projects and labs user's guide, see motorware _`:\ti\motorware\ diff --git a/SDITAPASmotorware_1_01_00_16Patch.patch b/SDITAPASmotorware_1_01_00_16Patch.patch deleted file mode 100644 index 32c8cd9..0000000 --- a/SDITAPASmotorware_1_01_00_16Patch.patch +++ /dev/null @@ -1,94763 +0,0 @@ -diff -crwN motorware/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -*** motorware/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.c 2015-01-20 15:29:02.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.c 2017-06-08 10:40:45.733748300 +0200 -*************** -*** 1008,1013 **** ---- 1008,1042 ---- - return; - } // end of CLK_setWatchDogSrc() function - -+ /* custom functions for enabling DMA- and McBSPA-clock */ -+ void CLK_enableDMAClock(CLK_Handle clkHandle) -+ { -+ CLK_Obj *clk = (CLK_Obj *)clkHandle; -+ -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ // set the bits -+ clk->PCLKCR3 |= CLK_PCLKCR3_DMAENCLK_BITS; -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of CLK_enableDMAClock() function - -+ void CLK_enableMcBSPAClock(CLK_Handle clkHandle) -+ { -+ CLK_Obj *clk = (CLK_Obj *)clkHandle; -+ -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ // set the bits -+ clk->PCLKCR0 |= CLK_PCLKCR0_MCBSPAENCLK_BITS; -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of CLK_enableMcBSPClock() function - - // end of file -diff -crwN motorware/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.h -*** motorware/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.h 2015-01-20 15:29:02.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/clk/src/32b/f28x/f2806x/clk.h 2017-06-08 10:40:45.741248300 +0200 -*************** -*** 105,110 **** ---- 105,115 ---- - //! - #define CLK_PCLKCR0_SCIBENCLK_BITS (1 << 11) - -+ /* added in connection with the McBSPA features */ -+ //! \brief Defines the location of the MCBSPAENCLK bits in the PCLKCR0 register -+ //! -+ #define CLK_PCLKCR0_MCBSPAENCLK_BITS (1 << 12) -+ - //! \brief Defines the location of the ECANAENCLK bits in the PCLKCR0 register - //! - #define CLK_PCLKCR0_ECANAENCLK_BITS (1 << 14) -*************** -*** 174,179 **** ---- 179,189 ---- - //! - #define CLK_PCLKCR3_CPUTIMER2ENCLK_BITS (1 << 10) - -+ /* added in connection with the DMA feature */ -+ //! \brief Defines the location of the DMAENCLK bits in the PCLKCR3 register -+ //! -+ #define CLK_PCLKCR3_DMAENCLK_BITS (1 << 11) -+ - //! \brief Defines the location of the GPIOINENCLK bits in the PCLKCR3 register - //! - #define CLK_PCLKCR3_GPIOINENCLK_BITS (1 << 13) -*************** -*** 701,706 **** ---- 711,734 ---- - //! \param[in] src The watchdog clock source - extern void CLK_setWatchDogSrc(CLK_Handle clkHandle,const CLK_WdClkSrc_e src); - -+ /* additional custom functions for DMA- and McBSP modules to enable and disable clocks */ -+ -+ //! \brief Disables the DMA clock -+ //! \param[in] clkHandle The clock (CLK) object handle -+ void CLK_disableDMAClock(CLK_Handle clkHandle); -+ -+ //! \brief Disables the McBSP clock -+ //! \param[in] clkHandle The clock (CLK) object handle -+ void CLK_disableMcBSPAClock(CLK_Handle clkHandle); -+ -+ //! \brief Enables the DMA clock -+ //! \param[in] clkHandle The clock (CLK) object handle -+ void CLK_enableDMAClock(CLK_Handle clkHandle); -+ -+ //! \brief Enables the McBSPA clock -+ //! \param[in] clkHandle The clock (CLK) object handle -+ void CLK_enableMcBSPAClock(CLK_Handle clkHandle); -+ - - #ifdef __cplusplus - } -diff -crwN motorware/motorware_1_01_00_16/sw/drivers/dma/dma.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/dma/dma.c -*** motorware/motorware_1_01_00_16/sw/drivers/dma/dma.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/dma/dma.c 2017-07-21 10:33:18.674735500 +0200 -*************** -*** 0 **** ---- 1,964 ---- -+ #include "dma.h" -+ -+ DMA_Handle DMA_init(void *pMemory,const size_t numBytes){ -+ -+ DMA_Handle DMAhandle; -+ -+ if(numBytes < sizeof(DMA_Obj)) -+ { -+ return((DMA_Handle)NULL); -+ } -+ -+ // assign the handle -+ DMAhandle = (DMA_Handle)pMemory; -+ -+ return(DMAhandle); -+ } // end of DMA_init() function -+ -+ void DMA_run(DMA_Handle DMAhandle, uint16_t DMAChannel){ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH1.CONTROL |= (1 << DMA_CONTROL_RUN_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH2.CONTROL |= (1 << DMA_CONTROL_RUN_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH3.CONTROL |= (1 << DMA_CONTROL_RUN_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH4.CONTROL |= (1 << DMA_CONTROL_RUN_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH5.CONTROL |= (1 << DMA_CONTROL_RUN_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH6.CONTROL |= (1 << DMA_CONTROL_RUN_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }// end of DMA_run() function -+ -+ void DMA_stop(DMA_Handle DMAhandle, uint16_t DMAChannel){ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH1.CONTROL &= (~(1 << DMA_CONTROL_RUN_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH2.CONTROL &= (~(1 << DMA_CONTROL_RUN_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH3.CONTROL &= (~(1 << DMA_CONTROL_RUN_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH4.CONTROL &= (~(1 << DMA_CONTROL_RUN_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH5.CONTROL &= (~(1 << DMA_CONTROL_RUN_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH6.CONTROL &= (~(1 << DMA_CONTROL_RUN_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }// end of DMA_stop() function -+ -+ void DMA_hardReset(DMA_Handle DMAhandle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->DMACTRL |= (1 << DMA_DMACTRL_HARDRESET_BIT); -+ __asm (" nop"); // one NOP required after HARDRESET -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ }// end of DMA_hardReset() function -+ -+ void DMA_priorityReset(DMA_Handle DMAhandle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->DMACTRL |= (1 << DMA_DMACTRL_PRIORITYRESET_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ }// end of DMA_priorityReset() function -+ -+ void DMA_enableFREE(DMA_Handle DMAhandle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->DEBUGCTRL |= (1u << DMA_DEBUGCTRL_FREE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ }//end of DMA_enableFREE() function -+ -+ void DMA_disableFREE(DMA_Handle DMAhandle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->DEBUGCTRL &= (~(1 << DMA_DEBUGCTRL_FREE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ }//end of DMA_disableFREE() function -+ -+ void DMA_CH1normalMode(DMA_Handle DMAhandle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->PRIORITYCTRL1 &= (~(1 << DMA_PRIORITYCTRL1_CH1PRIORITY_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ }//end of DMA_CH1normalMode() function -+ -+ void DMA_CH1highPriorityMode(DMA_Handle DMAhandle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->PRIORITYCTRL1 |= (1 << DMA_PRIORITYCTRL1_CH1PRIORITY_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ }//end of DMA_CH1highPriorityMode() function -+ -+ void DMA_AddrConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ volatile uint16_t *DMA_Dest,volatile uint16_t *DMA_Source){ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up SOURCE address: -+ DMAhandle->CH1.SRC_BEG_ADDR_SHADOW = (uint32_t)DMA_Source; // Point to beginning of source buffer -+ DMAhandle->CH1.SRC_ADDR_SHADOW = (uint32_t)DMA_Source; -+ -+ // Set up DESTINATION address: -+ DMAhandle->CH1.DST_BEG_ADDR_SHADOW = (uint32_t)DMA_Dest; // Point to beginning of destination buffer -+ DMAhandle->CH1.DST_ADDR_SHADOW = (uint32_t)DMA_Dest; -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up SOURCE address: -+ DMAhandle->CH2.SRC_BEG_ADDR_SHADOW = (uint32_t)DMA_Source; // Point to beginning of source buffer -+ DMAhandle->CH2.SRC_ADDR_SHADOW = (uint32_t)DMA_Source; -+ -+ // Set up DESTINATION address: -+ DMAhandle->CH2.DST_BEG_ADDR_SHADOW = (uint32_t)DMA_Dest; // Point to beginning of destination buffer -+ DMAhandle->CH2.DST_ADDR_SHADOW = (uint32_t)DMA_Dest; -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up SOURCE address: -+ DMAhandle->CH3.SRC_BEG_ADDR_SHADOW = (uint32_t)DMA_Source; // Point to beginning of source buffer -+ DMAhandle->CH3.SRC_ADDR_SHADOW = (uint32_t)DMA_Source; -+ -+ // Set up DESTINATION address: -+ DMAhandle->CH3.DST_BEG_ADDR_SHADOW = (uint32_t)DMA_Dest; // Point to beginning of destination buffer -+ DMAhandle->CH3.DST_ADDR_SHADOW = (uint32_t)DMA_Dest; -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up SOURCE address: -+ DMAhandle->CH4.SRC_BEG_ADDR_SHADOW = (uint32_t)DMA_Source; // Point to beginning of source buffer -+ DMAhandle->CH4.SRC_ADDR_SHADOW = (uint32_t)DMA_Source; -+ -+ // Set up DESTINATION address: -+ DMAhandle->CH4.DST_BEG_ADDR_SHADOW = (uint32_t)DMA_Dest; // Point to beginning of destination buffer -+ DMAhandle->CH4.DST_ADDR_SHADOW = (uint32_t)DMA_Dest; -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up SOURCE address: -+ DMAhandle->CH5.SRC_BEG_ADDR_SHADOW = (uint32_t)DMA_Source; // Point to beginning of source buffer -+ DMAhandle->CH5.SRC_ADDR_SHADOW = (uint32_t)DMA_Source; -+ -+ // Set up DESTINATION address: -+ DMAhandle->CH5.DST_BEG_ADDR_SHADOW = (uint32_t)DMA_Dest; // Point to beginning of destination buffer -+ DMAhandle->CH5.DST_ADDR_SHADOW = (uint32_t)DMA_Dest; -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up SOURCE address: -+ DMAhandle->CH6.SRC_BEG_ADDR_SHADOW = (uint32_t)DMA_Source; // Point to beginning of source buffer -+ DMAhandle->CH6.SRC_ADDR_SHADOW = (uint32_t)DMA_Source; -+ -+ // Set up DESTINATION address: -+ DMAhandle->CH6.DST_BEG_ADDR_SHADOW = (uint32_t)DMA_Dest; // Point to beginning of destination buffer -+ DMAhandle->CH6.DST_ADDR_SHADOW = (uint32_t)DMA_Dest; -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_AddrConfig() function -+ -+ void DMA_BurstConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ uint16_t bsize, int16_t srcbstep, int16_t desbstep){ -+ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up BURST registers: -+ DMAhandle->CH1.BURST_SIZE = bsize; // Number of words(X-1) x-ferred in a burst -+ DMAhandle->CH1.SRC_BURST_STEP = srcbstep; // Increment source addr between each word x-ferred -+ DMAhandle->CH1.DST_BURST_STEP = desbstep; // Increment dest addr between each word x-ferred -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up BURST registers: -+ DMAhandle->CH2.BURST_SIZE = bsize; // Number of words(X-1) x-ferred in a burst -+ DMAhandle->CH2.SRC_BURST_STEP = srcbstep; // Increment source addr between each word x-ferred -+ DMAhandle->CH2.DST_BURST_STEP = desbstep; // Increment dest addr between each word x-ferred -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up BURST registers: -+ DMAhandle->CH3.BURST_SIZE = bsize; // Number of words(X-1) x-ferred in a burst -+ DMAhandle->CH3.SRC_BURST_STEP = srcbstep; // Increment source addr between each word x-ferred -+ DMAhandle->CH3.DST_BURST_STEP = desbstep; // Increment dest addr between each word x-ferred -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up BURST registers: -+ DMAhandle->CH4.BURST_SIZE = bsize; // Number of words(X-1) x-ferred in a burst -+ DMAhandle->CH4.SRC_BURST_STEP = srcbstep; // Increment source addr between each word x-ferred -+ DMAhandle->CH4.DST_BURST_STEP = desbstep; // Increment dest addr between each word x-ferred -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up BURST registers: -+ DMAhandle->CH5.BURST_SIZE = bsize; // Number of words(X-1) x-ferred in a burst -+ DMAhandle->CH5.SRC_BURST_STEP = srcbstep; // Increment source addr between each word x-ferred -+ DMAhandle->CH5.DST_BURST_STEP = desbstep; // Increment dest addr between each word x-ferred -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up BURST registers: -+ DMAhandle->CH6.BURST_SIZE = bsize; // Number of words(X-1) x-ferred in a burst -+ DMAhandle->CH6.SRC_BURST_STEP = srcbstep; // Increment source addr between each word x-ferred -+ DMAhandle->CH6.DST_BURST_STEP = desbstep; // Increment dest addr between each word x-ferred -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_BurstConfig() function -+ -+ void DMA_TransferConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ uint16_t tsize, int16_t srctstep, int16_t deststep){ -+ -+ switch(DMAChannel){ -+ case DMA_CH1 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up TRANSFER registers: -+ DMAhandle->CH1.TRANSFER_SIZE = tsize; // Number of bursts per transfer, DMA interrupt will occur after completed transfer -+ DMAhandle->CH1.SRC_TRANSFER_STEP = srctstep; // TRANSFER_STEP is ignored when WRAP occurs -+ DMAhandle->CH1.DST_TRANSFER_STEP = deststep; // TRANSFER_STEP is ignored when WRAP occurs -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up TRANSFER registers: -+ DMAhandle->CH2.TRANSFER_SIZE = tsize; // Number of bursts per transfer, DMA interrupt will occur after completed transfer -+ DMAhandle->CH2.SRC_TRANSFER_STEP = srctstep; // TRANSFER_STEP is ignored when WRAP occurs -+ DMAhandle->CH2.DST_TRANSFER_STEP = deststep; // TRANSFER_STEP is ignored when WRAP occurs -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up TRANSFER registers: -+ DMAhandle->CH3.TRANSFER_SIZE = tsize; // Number of bursts per transfer, DMA interrupt will occur after completed transfer -+ DMAhandle->CH3.SRC_TRANSFER_STEP = srctstep; // TRANSFER_STEP is ignored when WRAP occurs -+ DMAhandle->CH3.DST_TRANSFER_STEP = deststep; // TRANSFER_STEP is ignored when WRAP occurs -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up TRANSFER registers: -+ DMAhandle->CH4.TRANSFER_SIZE = tsize; // Number of bursts per transfer, DMA interrupt will occur after completed transfer -+ DMAhandle->CH4.SRC_TRANSFER_STEP = srctstep; // TRANSFER_STEP is ignored when WRAP occurs -+ DMAhandle->CH4.DST_TRANSFER_STEP = deststep; // TRANSFER_STEP is ignored when WRAP occurs -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up TRANSFER registers: -+ DMAhandle->CH5.TRANSFER_SIZE = tsize; // Number of bursts per transfer, DMA interrupt will occur after completed transfer -+ DMAhandle->CH5.SRC_TRANSFER_STEP = srctstep; // TRANSFER_STEP is ignored when WRAP occurs -+ DMAhandle->CH5.DST_TRANSFER_STEP = deststep; // TRANSFER_STEP is ignored when WRAP occurs -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up TRANSFER registers: -+ DMAhandle->CH6.TRANSFER_SIZE = tsize; // Number of bursts per transfer, DMA interrupt will occur after completed transfer -+ DMAhandle->CH6.SRC_TRANSFER_STEP = srctstep; // TRANSFER_STEP is ignored when WRAP occurs -+ DMAhandle->CH6.DST_TRANSFER_STEP = deststep; // TRANSFER_STEP is ignored when WRAP occurs -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_TransferConfig() function -+ -+ void DMA_WrapConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ uint16_t srcwsize, int16_t srcwstep, uint16_t deswsize, int16_t deswstep){ -+ -+ switch(DMAChannel){ -+ case DMA_CH1 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up WRAP registers: -+ DMAhandle->CH1.SRC_WRAP_SIZE = srcwsize; // Wrap source address after N bursts -+ DMAhandle->CH1.SRC_WRAP_STEP = srcwstep; // Step for source wrap -+ -+ DMAhandle->CH1.DST_WRAP_SIZE = deswsize; // Wrap destination address after N bursts -+ DMAhandle->CH1.DST_WRAP_STEP = deswstep; // Step for destination wrap -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up WRAP registers: -+ DMAhandle->CH2.SRC_WRAP_SIZE = srcwsize; // Wrap source address after N bursts -+ DMAhandle->CH2.SRC_WRAP_STEP = srcwstep; // Step for source wrap -+ -+ DMAhandle->CH2.DST_WRAP_SIZE = deswsize; // Wrap destination address after N bursts -+ DMAhandle->CH2.DST_WRAP_STEP = deswstep; // Step for destination wrap -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up WRAP registers: -+ DMAhandle->CH3.SRC_WRAP_SIZE = srcwsize; // Wrap source address after N bursts -+ DMAhandle->CH3.SRC_WRAP_STEP = srcwstep; // Step for source wrap -+ -+ DMAhandle->CH3.DST_WRAP_SIZE = deswsize; // Wrap destination address after N bursts -+ DMAhandle->CH3.DST_WRAP_STEP = deswstep; // Step for destination wrap -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up WRAP registers: -+ DMAhandle->CH4.SRC_WRAP_SIZE = srcwsize; // Wrap source address after N bursts -+ DMAhandle->CH4.SRC_WRAP_STEP = srcwstep; // Step for source wrap -+ -+ DMAhandle->CH4.DST_WRAP_SIZE = deswsize; // Wrap destination address after N bursts -+ DMAhandle->CH4.DST_WRAP_STEP = deswstep; // Step for destination wrap -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up WRAP registers: -+ DMAhandle->CH5.SRC_WRAP_SIZE = srcwsize; // Wrap source address after N bursts -+ DMAhandle->CH5.SRC_WRAP_STEP = srcwstep; // Step for source wrap -+ -+ DMAhandle->CH5.DST_WRAP_SIZE = deswsize; // Wrap destination address after N bursts -+ DMAhandle->CH5.DST_WRAP_STEP = deswstep; // Step for destination wrap -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up WRAP registers: -+ DMAhandle->CH6.SRC_WRAP_SIZE = srcwsize; // Wrap source address after N bursts -+ DMAhandle->CH6.SRC_WRAP_STEP = srcwstep; // Step for source wrap -+ -+ DMAhandle->CH6.DST_WRAP_SIZE = deswsize; // Wrap destination address after N bursts -+ DMAhandle->CH6.DST_WRAP_STEP = deswstep; // Step for destination wrap -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_WrapConfig() function -+ -+ void DMA_ModeConfig(DMA_Handle DMAhandle, PIE_Handle PIEhandle, uint16_t DMAChannel, -+ uint16_t persel, uint16_t perinte, uint16_t oneshot, uint16_t cont, -+ uint16_t synce, uint16_t syncsel, uint16_t ovrinte, -+ uint16_t datasize, uint16_t chintmode, uint16_t chinte){ -+ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up MODE Register: -+ -+ // Passed DMA channel as peripheral interrupt source -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(persel << DMA_MODE_PERINTSEL_BITS)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (persel << DMA_MODE_PERINTSEL_BITS); -+ -+ // Peripheral interrupt enable -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(perinte << DMA_MODE_PERINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (perinte << DMA_MODE_PERINTE_BIT); -+ -+ // Oneshot enable -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(oneshot << DMA_MODE_ONESHOT_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (oneshot << DMA_MODE_ONESHOT_BIT); -+ -+ // Continous enable -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(cont << DMA_MODE_CONTINUOUS_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (cont << DMA_MODE_CONTINUOUS_BIT); -+ -+ // Enable/disable the overflow interrupt -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(ovrinte << DMA_MODE_OVRINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (ovrinte << DMA_MODE_OVRINTE_BIT); -+ -+ // 16-bit/32-bit data size transfers -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(datasize << DMA_MODE_DATASIZE_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (datasize << DMA_MODE_DATASIZE_BIT); -+ -+ // Generate interrupt to CPU at beginning/end of transfer -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(chintmode << DMA_MODE_CHINTMODE_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (chintmode << DMA_MODE_CHINTMODE_BIT); -+ -+ // Channel Interrupt to CPU enable -+ //1) clear bit -+ DMAhandle->CH1.MODE &= (~(chinte << DMA_MODE_CHINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH1.MODE |= (chinte << DMA_MODE_CHINTE_BIT); -+ -+ // Clear any spurious flags: -+ // Clear any spurious interrupt flags -+ // set bit -+ DMAhandle->CH1.CONTROL |= (1 << DMA_CONTROL_PERINTCLR_BIT); -+ -+ // Clear any spurious sync error flags -+ // set bit -+ DMAhandle->CH1.CONTROL |= (1 << DMA_CONTROL_ERRCLR_BIT); -+ -+ // Initialize PIE vector for CPU interrupt: -+ PIE_enableInt(PIEhandle, PIE_GroupNumber_7, PIE_InterruptSource_DMA_CH1); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up MODE Register: -+ -+ // Passed DMA channel as peripheral interrupt source -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(persel << DMA_MODE_PERINTSEL_BITS)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (persel << DMA_MODE_PERINTSEL_BITS); -+ -+ // Peripheral interrupt enable -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(perinte << DMA_MODE_PERINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (perinte << DMA_MODE_PERINTE_BIT); -+ -+ // Oneshot enable -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(oneshot << DMA_MODE_ONESHOT_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (oneshot << DMA_MODE_ONESHOT_BIT); -+ -+ // Continous enable -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(cont << DMA_MODE_CONTINUOUS_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (cont << DMA_MODE_CONTINUOUS_BIT); -+ -+ // Enable/disable the overflow interrupt -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(ovrinte << DMA_MODE_OVRINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (ovrinte << DMA_MODE_OVRINTE_BIT); -+ -+ // 16-bit/32-bit data size transfers -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(datasize << DMA_MODE_DATASIZE_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (datasize << DMA_MODE_DATASIZE_BIT); -+ -+ // Generate interrupt to CPU at beginning/end of transfer -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(chintmode << DMA_MODE_CHINTMODE_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (chintmode << DMA_MODE_CHINTMODE_BIT); -+ -+ // Channel Interrupt to CPU enable -+ //1) clear bit -+ DMAhandle->CH2.MODE &= (~(chinte << DMA_MODE_CHINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH2.MODE |= (chinte << DMA_MODE_CHINTE_BIT); -+ -+ // Clear any spurious flags: -+ // Clear any spurious interrupt flags -+ // set bit -+ DMAhandle->CH2.CONTROL |= (1 << DMA_CONTROL_PERINTCLR_BIT); -+ -+ // Clear any spurious sync error flags -+ // set bit -+ DMAhandle->CH2.CONTROL |= (1 << DMA_CONTROL_ERRCLR_BIT); -+ -+ // Initialize PIE vector for CPU interrupt: -+ PIE_enableInt(PIEhandle, PIE_GroupNumber_7, PIE_InterruptSource_DMA_CH2); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up MODE Register: -+ -+ // Passed DMA channel as peripheral interrupt source -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(persel << DMA_MODE_PERINTSEL_BITS)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (persel << DMA_MODE_PERINTSEL_BITS); -+ -+ // Peripheral interrupt enable -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(perinte << DMA_MODE_PERINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (perinte << DMA_MODE_PERINTE_BIT); -+ -+ // Oneshot enable -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(oneshot << DMA_MODE_ONESHOT_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (oneshot << DMA_MODE_ONESHOT_BIT); -+ -+ // Continous enable -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(cont << DMA_MODE_CONTINUOUS_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (cont << DMA_MODE_CONTINUOUS_BIT); -+ -+ // Enable/disable the overflow interrupt -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(ovrinte << DMA_MODE_OVRINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (ovrinte << DMA_MODE_OVRINTE_BIT); -+ -+ // 16-bit/32-bit data size transfers -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(datasize << DMA_MODE_DATASIZE_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (datasize << DMA_MODE_DATASIZE_BIT); -+ -+ // Generate interrupt to CPU at beginning/end of transfer -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(chintmode << DMA_MODE_CHINTMODE_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (chintmode << DMA_MODE_CHINTMODE_BIT); -+ -+ // Channel Interrupt to CPU enable -+ //1) clear bit -+ DMAhandle->CH3.MODE &= (~(chinte << DMA_MODE_CHINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH3.MODE |= (chinte << DMA_MODE_CHINTE_BIT); -+ -+ // Clear any spurious flags: -+ // Clear any spurious interrupt flags -+ // set bit -+ DMAhandle->CH3.CONTROL |= (1 << DMA_CONTROL_PERINTCLR_BIT); -+ -+ // Clear any spurious sync error flags -+ // set bit -+ DMAhandle->CH3.CONTROL |= (1 << DMA_CONTROL_ERRCLR_BIT); -+ -+ // Initialize PIE vector for CPU interrupt: -+ PIE_enableInt(PIEhandle, PIE_GroupNumber_7, PIE_InterruptSource_DMA_CH3); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up MODE Register: -+ -+ // Passed DMA channel as peripheral interrupt source -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(persel << DMA_MODE_PERINTSEL_BITS)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (persel << DMA_MODE_PERINTSEL_BITS); -+ -+ // Peripheral interrupt enable -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(perinte << DMA_MODE_PERINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (perinte << DMA_MODE_PERINTE_BIT); -+ -+ // Oneshot enable -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(oneshot << DMA_MODE_ONESHOT_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (oneshot << DMA_MODE_ONESHOT_BIT); -+ -+ // Continous enable -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(cont << DMA_MODE_CONTINUOUS_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (cont << DMA_MODE_CONTINUOUS_BIT); -+ -+ // Enable/disable the overflow interrupt -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(ovrinte << DMA_MODE_OVRINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (ovrinte << DMA_MODE_OVRINTE_BIT); -+ -+ // 16-bit/32-bit data size transfers -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(datasize << DMA_MODE_DATASIZE_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (datasize << DMA_MODE_DATASIZE_BIT); -+ -+ // Generate interrupt to CPU at beginning/end of transfer -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(chintmode << DMA_MODE_CHINTMODE_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (chintmode << DMA_MODE_CHINTMODE_BIT); -+ -+ // Channel Interrupt to CPU enable -+ //1) clear bit -+ DMAhandle->CH4.MODE &= (~(chinte << DMA_MODE_CHINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH4.MODE |= (chinte << DMA_MODE_CHINTE_BIT); -+ -+ // Clear any spurious flags: -+ // Clear any spurious interrupt flags -+ // set bit -+ DMAhandle->CH4.CONTROL |= (1 << DMA_CONTROL_PERINTCLR_BIT); -+ -+ // Clear any spurious sync error flags -+ // set bit -+ DMAhandle->CH4.CONTROL |= (1 << DMA_CONTROL_ERRCLR_BIT); -+ -+ // Initialize PIE vector for CPU interrupt: -+ PIE_enableInt(PIEhandle, PIE_GroupNumber_7, PIE_InterruptSource_DMA_CH4); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up MODE Register: -+ -+ // Passed DMA channel as peripheral interrupt source -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(persel << DMA_MODE_PERINTSEL_BITS)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (persel << DMA_MODE_PERINTSEL_BITS); -+ -+ // Peripheral interrupt enable -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(perinte << DMA_MODE_PERINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (perinte << DMA_MODE_PERINTE_BIT); -+ -+ // Oneshot enable -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(oneshot << DMA_MODE_ONESHOT_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (oneshot << DMA_MODE_ONESHOT_BIT); -+ -+ // Continous enable -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(cont << DMA_MODE_CONTINUOUS_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (cont << DMA_MODE_CONTINUOUS_BIT); -+ -+ // Enable/disable the overflow interrupt -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(ovrinte << DMA_MODE_OVRINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (ovrinte << DMA_MODE_OVRINTE_BIT); -+ -+ // 16-bit/32-bit data size transfers -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(datasize << DMA_MODE_DATASIZE_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (datasize << DMA_MODE_DATASIZE_BIT); -+ -+ // Generate interrupt to CPU at beginning/end of transfer -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(chintmode << DMA_MODE_CHINTMODE_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (chintmode << DMA_MODE_CHINTMODE_BIT); -+ -+ // Channel Interrupt to CPU enable -+ //1) clear bit -+ DMAhandle->CH5.MODE &= (~(chinte << DMA_MODE_CHINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH5.MODE |= (chinte << DMA_MODE_CHINTE_BIT); -+ -+ // Clear any spurious flags: -+ // Clear any spurious interrupt flags -+ // set bit -+ DMAhandle->CH5.CONTROL |= (1 << DMA_CONTROL_PERINTCLR_BIT); -+ -+ // Clear any spurious sync error flags -+ // set bit -+ DMAhandle->CH5.CONTROL |= (1 << DMA_CONTROL_ERRCLR_BIT); -+ -+ // Initialize PIE vector for CPU interrupt: -+ PIE_enableInt(PIEhandle, PIE_GroupNumber_7, PIE_InterruptSource_DMA_CH5); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ // Set up MODE Register: -+ -+ // Passed DMA channel as peripheral interrupt source -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(persel << DMA_MODE_PERINTSEL_BITS)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (persel << DMA_MODE_PERINTSEL_BITS); -+ -+ // Peripheral interrupt enable -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(perinte << DMA_MODE_PERINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (perinte << DMA_MODE_PERINTE_BIT); -+ -+ // Oneshot enable -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(oneshot << DMA_MODE_ONESHOT_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (oneshot << DMA_MODE_ONESHOT_BIT); -+ -+ // Continous enable -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(cont << DMA_MODE_CONTINUOUS_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (cont << DMA_MODE_CONTINUOUS_BIT); -+ -+ // Enable/disable the overflow interrupt -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(ovrinte << DMA_MODE_OVRINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (ovrinte << DMA_MODE_OVRINTE_BIT); -+ -+ // 16-bit/32-bit data size transfers -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(datasize << DMA_MODE_DATASIZE_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (datasize << DMA_MODE_DATASIZE_BIT); -+ -+ // Generate interrupt to CPU at beginning/end of transfer -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(chintmode << DMA_MODE_CHINTMODE_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (chintmode << DMA_MODE_CHINTMODE_BIT); -+ -+ // Channel Interrupt to CPU enable -+ //1) clear bit -+ DMAhandle->CH6.MODE &= (~(chinte << DMA_MODE_CHINTE_BIT)); -+ //2) set bit -+ DMAhandle->CH6.MODE |= (chinte << DMA_MODE_CHINTE_BIT); -+ -+ // Clear any spurious flags: -+ // Clear any spurious interrupt flags -+ // set bit -+ DMAhandle->CH6.CONTROL |= (1 << DMA_CONTROL_PERINTCLR_BIT); -+ -+ // Clear any spurious sync error flags -+ // set bit -+ DMAhandle->CH6.CONTROL |= (1 << DMA_CONTROL_ERRCLR_BIT); -+ -+ // Initialize PIE vector for CPU interrupt: -+ PIE_enableInt(PIEhandle, PIE_GroupNumber_7, PIE_InterruptSource_DMA_CH6); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_ModeConfig() function -+ -+ void DMA_enableChannelInterrupt(DMA_Handle DMAhandle, uint16_t DMAChannel){ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH1.MODE |= (1u << DMA_MODE_CHINTE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH2.MODE |= (1u << DMA_MODE_CHINTE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH3.MODE |= (1u << DMA_MODE_CHINTE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH4.MODE |= (1u << DMA_MODE_CHINTE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH5.MODE |= (1u << DMA_MODE_CHINTE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH6.MODE |= (1u << DMA_MODE_CHINTE_BIT); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_enableChannelInterrupt() function -+ -+ void DMA_disableChannelInterrupt(DMA_Handle DMAhandle, uint16_t DMAChannel){ -+ switch(DMAChannel){ -+ case DMA_CH1 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH1.MODE &= (~(1 << DMA_MODE_CHINTE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH2.MODE &= (~(1 << DMA_MODE_CHINTE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH3.MODE &= (~(1 << DMA_MODE_CHINTE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH4.MODE &= (~(1 << DMA_MODE_CHINTE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH5.MODE &= (~(1 << DMA_MODE_CHINTE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 : { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH6.MODE &= (~(1 << DMA_MODE_CHINTE_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_disableChannelInterrupt() function -+ -+ void DMA_SoftReset(DMA_Handle DMAhandle, uint16_t DMAChannel){ -+ uint32_t i = 0; -+ -+ switch(DMAChannel){ -+ case DMA_CH1 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH1.CONTROL |= (1 << DMA_CONTROL_SOFTRESET_BIT); -+ for(i = 0; i<100000; i++){} -+ DMAhandle->CH1.CONTROL &= (~(1 << DMA_CONTROL_SOFTRESET_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH2 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH2.CONTROL |= (1 << DMA_CONTROL_SOFTRESET_BIT); -+ for(i = 0; i<100000; i++){} -+ DMAhandle->CH2.CONTROL &= (~(1 << DMA_CONTROL_SOFTRESET_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH3 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH3.CONTROL |= (1 << DMA_CONTROL_SOFTRESET_BIT); -+ for(i = 0; i<100000; i++){} -+ DMAhandle->CH3.CONTROL &= (~(1 << DMA_CONTROL_SOFTRESET_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH4 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH4.CONTROL |= (1 << DMA_CONTROL_SOFTRESET_BIT); -+ for(i = 0; i<100000; i++){} -+ DMAhandle->CH4.CONTROL &= (~(1 << DMA_CONTROL_SOFTRESET_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH5 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH5.CONTROL |= (1 << DMA_CONTROL_SOFTRESET_BIT); -+ for(i = 0; i<100000; i++){} -+ DMAhandle->CH5.CONTROL &= (~(1 << DMA_CONTROL_SOFTRESET_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ case DMA_CH6 :{ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMAhandle->CH6.CONTROL |= (1 << DMA_CONTROL_SOFTRESET_BIT); -+ for(i = 0; i<100000; i++){} -+ DMAhandle->CH6.CONTROL &= (~(1 << DMA_CONTROL_SOFTRESET_BIT)); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ break; -+ } -+ } -+ }//end of DMA_SoftReset() function -+ -+ __interrupt void local_D_INTCH1_ISR(void) // DMA Ch1 -+ { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; // NEED TO EXECUTE ENABLE_PROTECTED_REGISTER_WRITE_MODE INSIDE ISR !!! -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ return; -+ } -+ -+ __interrupt void local_D_INTCH2_ISR(void) // DMA Ch2 -+ { -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; // NEED TO EXECUTE ENABLE_PROTECTED_REGISTER_WRITE_MODE INSIDE ISR !!! -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ return; -+ } -diff -crwN motorware/motorware_1_01_00_16/sw/drivers/dma/dma.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/dma/dma.h -*** motorware/motorware_1_01_00_16/sw/drivers/dma/dma.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/dma/dma.h 2017-07-21 09:59:17.141935500 +0200 -*************** -*** 0 **** ---- 1,264 ---- -+ #ifndef DMA_H_ -+ #define DMA_H_ -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ #include "sw/modules/types/src/types.h" -+ -+ #include "sw/drivers/cpu/src/32b/f28x/f2806x/cpu.h" -+ -+ #include "sw/drivers/pie/src/32b/f28x/f2806x/pie.h" -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ //! \brief Defines the base address of the (mcBSP) registers -+ #define DMA_BASE_ADDR (0x00001000) -+ -+ // MODE -+ //========================== -+ // PERINTSEL bits -+ #define DMA_SEQ1INT 1 -+ #define DMA_SEQ2INT 2 -+ #define DMA_XINT1 3 -+ #define DMA_XINT2 4 -+ #define DMA_XINT3 5 -+ #define DMA_USB0EP1RX 7 -+ #define DMA_USB0EP1TX 8 -+ #define DMA_USB0EP2RX 9 -+ #define DMA_USB0EP2TX 10 -+ #define DMA_TINT0 11 -+ #define DMA_TINT1 12 -+ #define DMA_TINT2 13 -+ #define DMA_MXEVTA 14 -+ #define DMA_MREVTA 15 -+ #define DMA_EPWM2A 18 -+ #define DMA_EPWM2B 19 -+ #define DMA_EPWM3A 20 -+ #define DMA_EPWM3B 21 -+ #define DMA_EPWM4A 22 -+ #define DMA_EPWM4B 23 -+ #define DMA_EPWM5A 24 -+ #define DMA_EPWM5B 25 -+ #define DMA_EPWM6A 26 -+ #define DMA_EPWM6B 27 -+ #define DMA_EPWM7A 28 -+ #define DMA_EPWM7B 29 -+ #define DMA_USB0EP3RX 30 -+ #define DMA_USB0EP3TX 31 -+ // OVERINTE bit -+ #define OVRFLOW_DISABLE 0x0 -+ #define OVEFLOW_ENABLE 0x1 -+ // PERINTE bit -+ #define PERINT_DISABLE 0x0 -+ #define PERINT_ENABLE 0x1 -+ // CHINTMODE bits -+ #define CHINT_BEGIN 0x0 -+ #define CHINT_END 0x1 -+ // ONESHOT bits -+ #define ONESHOT_DISABLE 0x0 -+ #define ONESHOT_ENABLE 0x1 -+ // CONTINOUS bit -+ #define CONT_DISABLE 0x0 -+ #define CONT_ENABLE 0x1 -+ // SYNCE bit -+ #define SYNC_DISABLE 0x0 -+ #define SYNC_ENABLE 0x1 -+ // SYNCSEL bit -+ #define SYNC_SRC 0x0 -+ #define SYNC_DST 0x1 -+ // DATASIZE bit -+ #define SIXTEEN_BIT 0x0 -+ #define THIRTYTWO_BIT 0x1 -+ // CHINTE bit -+ #define CHINT_DISABLE 0x0 -+ #define CHINT_ENABLE 0x1 -+ -+ //--------------------------------------------------------------------------- -+ // DMA Individual Register Bit Definitions: -+ //MODE_BITS -+ // 4:0 Peripheral Interrupt and Sync Select -+ #define DMA_MODE_PERINTSEL_BITS 0 -+ // 6:5 Reserved -+ -+ /// 7 Overflow Interrupt Enable -+ #define DMA_MODE_OVRINTE_BIT 7 -+ // 8 Peripheral Interrupt Enable -+ #define DMA_MODE_PERINTE_BIT 8 -+ // 9 Channel Interrupt Mode -+ #define DMA_MODE_CHINTMODE_BIT 9 -+ // 10 One Shot Mode Bit -+ #define DMA_MODE_ONESHOT_BIT 10 -+ // 11 Continuous Mode Bit -+ #define DMA_MODE_CONTINUOUS_BIT 11 -+ // 13:12 Reserved -+ -+ // 14 Data Size Mode Bit -+ #define DMA_MODE_DATASIZE_BIT 14 -+ // 15 Channel Interrupt Enable Bit -+ #define DMA_MODE_CHINTE_BIT 15 -+ -+ //CONTROL_BITS -+ // 0 Run Bit -+ #define DMA_CONTROL_RUN_BIT 0 -+ // 1 Halt Bit -+ #define DMA_CONTROL_HALT_BIT 1 -+ // 2 Soft Reset Bit -+ #define DMA_CONTROL_SOFTRESET_BIT 2 -+ // 3 Interrupt Force Bit -+ #define DMA_CONTROL_PERINTFRC_BIT 3 -+ // 4 Interrupt Clear Bit -+ #define DMA_CONTROL_PERINTCLR_BIT 4 -+ // 6:5 Reserved -+ -+ // 7 Error Clear Bit -+ #define DMA_CONTROL_ERRCLR_BIT 7 -+ // 8 Interrupt Flag Bit -+ #define DMA_CONTROL_PERINTFLG_BIT 8 -+ // 9 Sync Flag Bit -+ #define DMA_CONTROL_SYNCFLG_BIT 9 -+ // 10 Sync Error Flag Bit -+ #define DMA_CONTROL_SYNCERR_BIT 10 -+ // 11 Transfer Status Bit -+ #define DMA_CONTROL_TRANSFERSTS_BIT 11 -+ // 12 Burst Status Bit -+ #define DMA_CONTROL_BURSTSTS_BIT 12 -+ // 13 Run Status Bit -+ #define DMA_CONTROL_RUNSTS_BIT 13 -+ // 14 Overflow Flag Bit -+ #define DMA_CONTROL_OVRFLG_BIT 14 -+ // 15 Reserved -+ -+ //DMACTRL_BITS -+ // 0 Hard Reset Bit -+ #define DMA_DMACTRL_HARDRESET_BIT 0 -+ // 1 Priority Reset Bit -+ #define DMA_DMACTRL_PRIORITYRESET_BIT 1 -+ // 15:2 Reserved -+ -+ //DEBUGCTRL_BITS -+ // 14:0 Reserved -+ -+ // 15 Debug Mode Bit -+ #define DMA_DEBUGCTRL_FREE_BIT 15 -+ -+ //PRIORITYCTRL1_BITS -+ // 0 Ch1 Priority Bit -+ #define DMA_PRIORITYCTRL1_CH1PRIORITY_BIT 0 -+ // 15:1 Reserved -+ -+ //PRIORITYSTAT_BITS -+ // 2:0 Active Channel Status Bits -+ #define DMA_PRIORITYSTAT_ACTIVESTS_BIT 0 -+ // 3 Reserved -+ -+ // 6:4 Active Channel Status Shadow Bits -+ #define DMA_PRIORITYSTAT_ACTIVESTS_SHADOW_BIT 4 -+ // 15:7 Reserved -+ -+ struct CH_REGS { -+ uint16_t MODE; // Mode Register -+ uint16_t CONTROL; // Control Register -+ uint16_t BURST_SIZE; // Burst Size Register -+ uint16_t BURST_COUNT; // Burst Count Register -+ int16_t SRC_BURST_STEP; // Source Burst Step Register -+ int16_t DST_BURST_STEP; // Destination Burst Step Register -+ uint16_t TRANSFER_SIZE; // Transfer Size Register -+ uint16_t TRANSFER_COUNT; // Transfer Count Register -+ int16_t SRC_TRANSFER_STEP; // Source Transfer Step Register -+ int16_t DST_TRANSFER_STEP; // Destination Transfer Step Register -+ uint16_t SRC_WRAP_SIZE; // Source Wrap Size Register -+ uint16_t SRC_WRAP_COUNT; // Source Wrap Count Register -+ int16_t SRC_WRAP_STEP; // Source Wrap Step Register -+ uint16_t DST_WRAP_SIZE; // Destination Wrap Size Register -+ uint16_t DST_WRAP_COUNT; // Destination Wrap Count Register -+ int16_t DST_WRAP_STEP; // Destination Wrap Step Register -+ uint32_t SRC_BEG_ADDR_SHADOW; // Source Begin Address Shadow Register -+ uint32_t SRC_ADDR_SHADOW; // Source Address Shadow Register -+ uint32_t SRC_BEG_ADDR_ACTIVE; // Source Begin Address Active Register -+ uint32_t SRC_ADDR_ACTIVE; // Source Address Active Register -+ uint32_t DST_BEG_ADDR_SHADOW; // Destination Begin Address Shadow Register -+ uint32_t DST_ADDR_SHADOW; // Destination Address Shadow Register -+ uint32_t DST_BEG_ADDR_ACTIVE; // Destination Begin Address Active Register -+ uint32_t DST_ADDR_ACTIVE; // Destination Address Active Register -+ }; -+ -+ //! \brief Defines the Direct Memory Access (DMA) object -+ typedef struct _DMA_Obj_ { -+ volatile uint16_t DMACTRL; // DMA Control Register -+ volatile uint16_t DEBUGCTRL; // Debug Control Register -+ volatile uint16_t REVISION; // /*Reserved*/ Revision-Bits ... -+ volatile uint16_t rsvd1; // Reserved -+ volatile uint16_t PRIORITYCTRL1; // Priority Control 1 Register -+ volatile uint16_t rsvd2; // Reserved -+ volatile uint16_t PRIORITYSTAT; // Priority Status Register -+ volatile uint16_t rsvd3[25]; // Reserved -+ volatile struct CH_REGS CH1; // DMA Channel 1 Registers -+ volatile struct CH_REGS CH2; // DMA Channel 2 Registers -+ volatile struct CH_REGS CH3; // DMA Channel 3 Registers -+ volatile struct CH_REGS CH4; // DMA Channel 4 Registers -+ volatile struct CH_REGS CH5; // DMA Channel 5 Registers -+ volatile struct CH_REGS CH6; // DMA Channel 6 Registers -+ } DMA_Obj; -+ -+ //! \brief Defines the general purpose I/O (GPIO) handle -+ typedef struct _DMA_Obj_ *DMA_Handle; -+ -+ -+ enum DMA_CHANNEL{ -+ DMA_CH1, DMA_CH2, DMA_CH3, DMA_CH4, DMA_CH5, DMA_CH6 -+ }; -+ -+ extern DMA_Handle DMA_init(void *pMemory,const size_t numBytes); -+ -+ extern void DMA_run(DMA_Handle DMAhandle, uint16_t DMAChannel); -+ -+ extern void DMA_stop(DMA_Handle DMAhandle, uint16_t DMAChannel); -+ -+ extern void DMA_hardReset(DMA_Handle DMAhandle); -+ -+ extern void DMA_priorityReset(DMA_Handle DMAhandle); -+ -+ extern void DMA_enableFREE(DMA_Handle DMAhandle); -+ -+ extern void DMA_disableFREE(DMA_Handle DMAhandle); -+ -+ extern void DMA_CH1normalMode(DMA_Handle DMAhandle); -+ -+ extern void DMA_CH1highPriorityMode(DMA_Handle DMAhandle); -+ -+ -+ extern void DMA_AddrConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ volatile uint16_t *DMA_Dest,volatile uint16_t *DMA_Source); -+ -+ extern void DMA_BurstConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ uint16_t bsize, int16_t srcbstep, int16_t desbstep); -+ -+ extern void DMA_TransferConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ uint16_t tsize, int16_t srctstep, int16_t deststep); -+ -+ extern void DMA_WrapConfig(DMA_Handle DMAhandle, uint16_t DMAChannel, -+ uint16_t srcwsize, int16_t srcwstep, uint16_t deswsize, int16_t deswstep); -+ -+ extern void DMA_ModeConfig(DMA_Handle DMAhandle, PIE_Handle PIEhandle, uint16_t DMAChannel, -+ uint16_t persel, uint16_t perinte, uint16_t oneshot, uint16_t cont, -+ uint16_t synce, uint16_t syncsel, uint16_t ovrinte, -+ uint16_t datasize, uint16_t chintmode, uint16_t chinte); -+ -+ extern void DMA_enableChannelInterrupt(DMA_Handle DMAhandle, uint16_t DMAChannel); -+ -+ extern void DMA_disableChannelInterrupt(DMA_Handle DMAhandle, uint16_t DMAChannel); -+ -+ extern void DMA_SoftReset(DMA_Handle DMAhandle, uint16_t DMAChannel); -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ #endif /* DMA_H_ */ -diff -crwN motorware/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.c -*** motorware/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.c 2017-07-21 10:44:25.247135500 +0200 -*************** -*** 0 **** ---- 1,492 ---- -+ #include "SPImcBSP.h" -+ -+ -+ MCBSP_Handle MCBSP_init(void *pMemory,const size_t numBytes){ -+ -+ MCBSP_Handle MCBSPhandle; -+ -+ if(numBytes < sizeof(MCBSP_Obj)) -+ { -+ return((MCBSP_Handle)NULL); -+ } -+ -+ // assign the handle -+ MCBSPhandle = (MCBSP_Handle)pMemory; -+ -+ return(MCBSPhandle); -+ } // end of MCBSP_init() function -+ -+ void McBSP_stop(MCBSP_Handle handle){ -+ MCBSP_resetReceiver(handle); -+ MCBSP_resetTransmitter(handle); -+ } // end of McBSP_stop() function -+ -+ void McBSP_run(MCBSP_Handle handle){ -+ MCBSP_resetReleaseReceiver(handle); -+ MCBSP_resetReleaseTransmitter(handle); -+ } // end of McBSP_run() function -+ -+ extern void MCBSP_resetTransmitter(MCBSP_Handle handle){ -+ handle->SPCR2 &= (~(1 << MCBSP_SPCR2_XRST_BIT)); -+ } // end of MCBSP_resetTransmitter() function -+ -+ extern void MCBSP_resetReleaseTransmitter(MCBSP_Handle handle){ -+ handle->SPCR2 |= (1 << MCBSP_SPCR2_XRST_BIT); -+ } // end of MCBSP_resetReleaseTransmitter() function -+ -+ void MCBSP_resetReceiver(MCBSP_Handle handle){ -+ handle->SPCR1 &= (~(1 << MCBSP_SPCR1_RRST_BIT)); -+ } // end of MCBSP_resetReceiver() function -+ -+ void MCBSP_resetReleaseReceiver(MCBSP_Handle handle){ -+ handle->SPCR1 |= (1 << MCBSP_SPCR1_RRST_BIT); -+ } // end of MCBSP_resetReleaseReceiver() function -+ -+ void MCBSP_resetSampleRateGenerator(MCBSP_Handle handle){ -+ handle->SPCR2 &= (~(1 << MCBSP_SPCR2_GRST_BIT)); -+ } // end of MCBSP_resetSampleRateGenerator() function -+ -+ void MCBSP_resetReleaseSampleRateGenerator(MCBSP_Handle handle){ -+ handle->SPCR2 |= (1 << MCBSP_SPCR2_GRST_BIT); -+ } // end of MCBSP_resetReleaseSampleRateGenerator() function -+ -+ void MCBSP_resetFrameSynchronizationLogic(MCBSP_Handle handle){ -+ handle->SPCR2 &= (~(1 << MCBSP_SPCR2_FRST_BIT)); -+ } // end of MCBSP_resetFrameSynchronizationLogic() function -+ -+ void MCBSP_resetReleaseFrameSynchronizationLogic(MCBSP_Handle handle){ -+ handle->SPCR2 |= (1 << MCBSP_SPCR2_FRST_BIT); -+ } // end of MCBSP_resetReleaseFrameSynchronizationLogic() function -+ -+ extern void MCBSP_setTransmitClockPolarity(MCBSP_Handle handle, uint16_t polarity){ -+ switch(polarity){ -+ case MCBSP_TransmitClockPolarity_dataSampleRisingEdge :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_CLKXP_BIT)); -+ break; -+ } -+ case MCBSP_TransmitClockPolarity_dataSampleFallingEdge :{ -+ handle->PCR |= (1 << MCBSP_PCR_CLKXP_BIT); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setTransmitClockPolarity() function -+ -+ extern void MCBSP_setReceiveClockPolarity(MCBSP_Handle handle, uint16_t polarity){ -+ switch(polarity){ -+ case MCBSP_ReceiveClockPolarity_dataSampleRisingEdge :{ -+ handle->PCR |= (1 << MCBSP_PCR_CLKRP_BIT); -+ break; -+ } -+ case MCBSP_ReceiveClockPolarity_dataSampleFallingEdge :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_CLKRP_BIT)); -+ break; -+ } -+ default :{ -+ break; -+ } -+ } -+ } // end of MCBSP_setReceiveClockPolarity() function -+ -+ extern void MCBSP_setTransmitClockMode(MCBSP_Handle handle, uint16_t txClkMode){ -+ switch(txClkMode){ -+ case MCBSP_TransmitClockMode_ExternalClkSPISlave :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_CLKXM_BIT)); -+ break; -+ } -+ case MCBSP_TransmitClockMode_InternalClkSPIMaster :{ -+ handle->PCR |= (1 << MCBSP_PCR_CLKXM_BIT); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setTransmitClockMode() function -+ -+ extern void MCBSP_setReceiveClockMode(MCBSP_Handle handle, uint16_t rcvClkMode){ -+ switch(rcvClkMode){ -+ case MCBSP_ReceiveClockMode_ExternalClk :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_CLKRM_BIT)); -+ break; -+ } -+ case MCBSP_ReceiveClockMode_InternalClk :{ -+ handle->PCR |= (1 << MCBSP_PCR_CLKRM_BIT); -+ break; -+ } -+ default :{ -+ break; -+ } -+ } -+ } // end of MCBSP_setReceiveClockMode() function -+ -+ void MCBSP_setClockStopMode(MCBSP_Handle handle, uint16_t clkStopMode){ -+ switch(clkStopMode){ -+ case MCBSP_ClockStopMode_DISABLED:{ -+ //1) clear bit -+ handle->SPCR1 &= (~(0 << MCBSP_SPCR1_CLKSTP_BITS)); -+ //2) set bit -+ handle->SPCR1 |= (0 << MCBSP_SPCR1_CLKSTP_BITS); -+ break; -+ } -+ case MCBSP_ClockStopMode_WithoutClockDelay:{ -+ //1) clear bit -+ handle->SPCR1 &= (~(2 << MCBSP_SPCR1_CLKSTP_BITS)); -+ //2) set bit -+ handle->SPCR1 |= (2 << MCBSP_SPCR1_CLKSTP_BITS); -+ break; -+ } -+ case MCBSP_ClockStopMode_HalfCycleClockDelay:{ -+ //1) clear bit -+ handle->SPCR1 &= (~(3 << MCBSP_SPCR1_CLKSTP_BITS)); -+ //2) set bit -+ handle->SPCR1 |= (3 << MCBSP_SPCR1_CLKSTP_BITS); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setClockStopMode() function -+ -+ void MCBSP_setMode(MCBSP_Handle handle, -+ uint16_t mode, // da stellt man SPI oder "nicht-SPI" ein -+ uint16_t digitalLoopback){ // Loopback-Mode ein/aus -+ switch(digitalLoopback){ -+ case McBSP_disableLoopback :{ -+ handle->SPCR1 &= (~(1 << MCBSP_SPCR1_DLB_BIT)); -+ break; -+ } -+ case McBSP_enableLoopback :{ -+ handle->SPCR1 |= (1u << MCBSP_SPCR1_DLB_BIT); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ -+ switch(mode){ -+ case McBsp_SPISlaveMode0 : { -+ MCBSP_setClockStopMode(handle, MCBSP_ClockStopMode_WithoutClockDelay); -+ -+ MCBSP_setTransmitClockPolarity(handle, MCBSP_TransmitClockPolarity_dataSampleRisingEdge); -+ -+ MCBSP_setReceiveClockPolarity(handle, MCBSP_ReceiveClockPolarity_dataSampleFallingEdge); -+ -+ MCBSP_setTransmitClockMode(handle, MCBSP_TransmitClockMode_ExternalClkSPISlave); -+ -+ MCBSP_setReceiveClockMode(handle, MCBSP_ReceiveClockMode_ExternalClk); -+ break; -+ } -+ case McBsp_SPISlaveMode1 : { -+ MCBSP_setClockStopMode(handle, MCBSP_ClockStopMode_HalfCycleClockDelay); -+ -+ MCBSP_setTransmitClockPolarity(handle, MCBSP_TransmitClockPolarity_dataSampleRisingEdge); -+ -+ MCBSP_setReceiveClockPolarity(handle, MCBSP_ReceiveClockPolarity_dataSampleRisingEdge); -+ -+ MCBSP_setTransmitClockMode(handle, MCBSP_TransmitClockMode_ExternalClkSPISlave); -+ -+ MCBSP_setReceiveClockMode(handle, MCBSP_ReceiveClockMode_ExternalClk); -+ break; -+ } -+ case McBsp_SPISlaveMode2 : { -+ MCBSP_setClockStopMode(handle, MCBSP_ClockStopMode_WithoutClockDelay); -+ -+ MCBSP_setTransmitClockPolarity(handle, MCBSP_TransmitClockPolarity_dataSampleFallingEdge); -+ -+ MCBSP_setReceiveClockPolarity(handle, MCBSP_ReceiveClockPolarity_dataSampleFallingEdge); -+ -+ MCBSP_setTransmitClockMode(handle, MCBSP_TransmitClockMode_ExternalClkSPISlave); -+ -+ MCBSP_setReceiveClockMode(handle, MCBSP_ReceiveClockMode_ExternalClk); -+ break; -+ } -+ case McBsp_SPISlaveMode3 : { -+ MCBSP_setClockStopMode(handle, MCBSP_ClockStopMode_HalfCycleClockDelay); -+ -+ MCBSP_setTransmitClockPolarity(handle, MCBSP_TransmitClockPolarity_dataSampleFallingEdge); -+ -+ MCBSP_setReceiveClockPolarity(handle, MCBSP_ReceiveClockPolarity_dataSampleRisingEdge); -+ -+ MCBSP_setTransmitClockMode(handle, MCBSP_TransmitClockMode_ExternalClkSPISlave); -+ -+ MCBSP_setReceiveClockMode(handle, MCBSP_ReceiveClockMode_ExternalClk); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setMode() function -+ -+ void MCBSP_sampleRateGeneratorInputClockMode(MCBSP_Handle handle, uint16_t sampleRateGenSRC){ -+ switch(sampleRateGenSRC){ -+ case McBSP_SampleRateGen_Source_LSPCLK :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_SCLKME_BIT)); -+ handle->SRGR2 |= (1 << MCBSP_SRGR2_CLKSM_BIT); -+ break; -+ } -+ case McBSP_SampleRateGen_Source_MCLKR_Pin :{ -+ handle->PCR |= (1 << MCBSP_PCR_SCLKME_BIT); -+ handle->SRGR2 &= (~(1 << MCBSP_SRGR2_CLKSM_BIT)); -+ break; -+ } -+ case McBSP_SampleRateGen_Source_MCLKX_Pin :{ -+ handle->PCR |= (1 << MCBSP_PCR_SCLKME_BIT); -+ handle->SRGR2 |= (1 << MCBSP_SRGR2_CLKSM_BIT); -+ break; -+ } -+ default :{ -+ break; -+ } -+ } -+ } // end of MCBSP_sampleRateGeneratorInputClockMode() function -+ -+ void MCBSP_setTransmitFrameSynchronizationMode(MCBSP_Handle handle, uint16_t snycMode){ -+ switch(snycMode){ -+ case MCBSP_TransmitFrameSyncMode_EXTERNAL :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_FSXM_BIT)); -+ break; -+ } -+ case MCBSP_TransmitFrameSyncMode_INTERNAL :{ -+ handle->PCR |= (1 << MCBSP_PCR_FSXM_BIT); -+ break; -+ } -+ default: { -+ break; -+ } -+ } -+ -+ } // end of MCBSP_setTransmitFrameSynchronizationMode() function -+ -+ void MCBSP_setReceiveFrameSynchronizationMode(MCBSP_Handle handle, uint16_t snycMode){ -+ switch(snycMode){ -+ case MCBSP_ReceiveFrameSyncMode_EXTERNAL :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_FSRM_BIT)); -+ break; -+ } -+ case MCBSP_ReceiveFrameSyncMode_INTERNAL :{ -+ handle->PCR |= (1 << MCBSP_PCR_FSRM_BIT); -+ break; -+ } -+ default: { -+ break; -+ } -+ } -+ -+ } // end of MCBSP_setReceiveFrameSynchronizationMode() function -+ -+ void MCBSP_setTransmitFrameSyncPolarity(MCBSP_Handle handle, uint16_t transmitPol){ -+ switch(transmitPol){ -+ case MCBSP_TransmitFrameSync__ACTIVE_HIGH :{ -+ handle->PCR &= (~(1 << MCBSP_PCR_FSXP_BIT)); -+ break; -+ } -+ case MCBSP_TransmitFrameSync__ACTIVE_LOW :{ -+ handle->PCR |= (1 << MCBSP_PCR_FSXP_BIT); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setTransmitFrameSyncPolarity() function -+ -+ void MCBSP_setReceiveFrameSyncPolarity(MCBSP_Handle handle, uint16_t receivePol){ -+ switch(receivePol){ -+ case MCBSP_ReceiveFrameSync__ACTIVE_HIGH:{ -+ handle->PCR &= (~(1 << MCBSP_PCR_FSRP_BIT)); -+ break; -+ } -+ case MCBSP_ReceiveFrameSync__ACTIVE_LOW:{ -+ handle->PCR |= (1 << MCBSP_PCR_FSRP_BIT); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ -+ } // end of MCBSP_setReceiveFrameSyncPolarity() function -+ -+ void MCBSP_setSRGClockDivider(MCBSP_Handle handle, uint16_t divider){ -+ //1) clear bit -+ handle->SRGR1 &= (~( (divider - 1) << MCBSP_SRGR1_CLKGDV_BITS)); -+ //2) set bit -+ handle->SRGR1 |= ( (divider - 1) << MCBSP_SRGR1_CLKGDV_BITS); -+ } // end of MCBSP_setSRGClockDivider() function -+ -+ void MCBSP_setTransmitDataDelay(MCBSP_Handle handle, uint16_t delay){ -+ switch(delay){ -+ case MCBSP_TransmitDataDelay_0Bit :{ -+ //1) clear bit -+ handle->XCR2 &= (~( 0 << MCBSP_XCR2_XDATDLY_BITS)); -+ //2) set bit -+ handle->XCR2 |= ( 0 << MCBSP_XCR2_XDATDLY_BITS); -+ break; -+ } -+ case MCBSP_TransmitDataDelay_1Bit :{ -+ //1) clear bit -+ handle->XCR2 &= (~( 0 << MCBSP_XCR2_XDATDLY_BITS)); -+ //2) set bit -+ handle->XCR2 |= ( 0 << MCBSP_XCR2_XDATDLY_BITS); -+ break; -+ } -+ case MCBSP_TransmitDataDelay_2Bit :{ -+ //1) clear bit -+ handle->XCR2 &= (~( 0 << MCBSP_XCR2_XDATDLY_BITS)); -+ //2) set bit -+ handle->XCR2 |= ( 0 << MCBSP_XCR2_XDATDLY_BITS); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setTransmitDataDelay() function -+ -+ void MCBSP_setReceiveDataDelay(MCBSP_Handle handle, uint16_t delay){ -+ switch(delay){ -+ case MCBSP_ReceiveDataDelay_0Bit :{ -+ //1) clear bit -+ handle->RCR2 &= (~( 0 << MCBSP_RCR2_RDATDLY_BITS)); -+ //2) set bit -+ handle->RCR2 |= ( 0 << MCBSP_RCR2_RDATDLY_BITS); -+ break; -+ } -+ case MCBSP_ReceiveDataDelay_1Bit :{ -+ //1) clear bit -+ handle->RCR2 &= (~( 1 << MCBSP_RCR2_RDATDLY_BITS)); -+ //2) set bit -+ handle->RCR2 |= ( 1 << MCBSP_RCR2_RDATDLY_BITS); -+ break; -+ } -+ case MCBSP_ReceiveDataDelay_2Bit :{ -+ //1) clear bit -+ handle->RCR2 &= (~( 2 << MCBSP_RCR2_RDATDLY_BITS)); -+ //2) set bit -+ handle->RCR2 |= ( 2 << MCBSP_RCR2_RDATDLY_BITS); -+ break; -+ } -+ default:{ -+ break; -+ } -+ } -+ } // end of MCBSP_setReceiveDataDelay() function -+ -+ void MCBSP_setReceiveWordLength1(MCBSP_Handle handle, uint16_t length){ -+ switch(length){ -+ case MCBSP_ReceiveWordLength1_8Bits:{ -+ //1) clear bit -+ handle->RCR1 &= (~( 0 << MCBSP_RCR1_RWDLEN1_BITS)); -+ //2) set bit -+ handle->RCR1 |= ( 0 << MCBSP_RCR1_RWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_ReceiveWordLength1_12Bits:{ -+ //1) clear bit -+ handle->RCR1 &= (~( 1 << MCBSP_RCR1_RWDLEN1_BITS)); -+ //2) set bit -+ handle->RCR1 |= ( 1 << MCBSP_RCR1_RWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_ReceiveWordLength1_16Bits:{ -+ //1) clear bit -+ handle->RCR1 &= (~( 2 << MCBSP_RCR1_RWDLEN1_BITS)); -+ //2) set bit -+ handle->RCR1 |= ( 2 << MCBSP_RCR1_RWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_ReceiveWordLength1_20Bits:{ -+ //1) clear bit -+ handle->RCR1 &= (~( 3 << MCBSP_RCR1_RWDLEN1_BITS)); -+ //2) set bit -+ handle->RCR1 |= ( 3 << MCBSP_RCR1_RWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_ReceiveWordLength1_24Bits:{ -+ //1) clear bit -+ handle->RCR1 &= (~( 4 << MCBSP_RCR1_RWDLEN1_BITS)); -+ //2) set bit -+ handle->RCR1 |= ( 4 << MCBSP_RCR1_RWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_ReceiveWordLength1_32Bits:{ -+ //1) clear bit -+ handle->RCR1 &= (~( 5 << MCBSP_RCR1_RWDLEN1_BITS)); -+ //2) set bit -+ handle->RCR1 |= ( 5 << MCBSP_RCR1_RWDLEN1_BITS); -+ break; -+ } -+ default: { -+ break; -+ } -+ } -+ } // end of MCBSP_setReceiveWordLength1() function -+ -+ void MCBSP_setTransmitWordLength1(MCBSP_Handle handle, uint16_t length){ -+ switch(length){ -+ case MCBSP_TransmitWordLength1_8Bits :{ -+ //1) clear bit -+ handle->XCR1 &= (~( 0 << MCBSP_XCR1_XWDLEN1_BITS)); -+ //2) set bit -+ handle->XCR1 |= ( 0 << MCBSP_XCR1_XWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_TransmitWordLength1_12Bits :{ -+ //1) clear bit -+ handle->XCR1 &= (~( 1 << MCBSP_XCR1_XWDLEN1_BITS)); -+ //2) set bit -+ handle->XCR1 |= ( 1 << MCBSP_XCR1_XWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_TransmitWordLength1_16Bits :{ -+ //1) clear bit -+ handle->XCR1 &= (~( 2 << MCBSP_XCR1_XWDLEN1_BITS)); -+ //2) set bit -+ handle->XCR1 |= ( 2 << MCBSP_XCR1_XWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_TransmitWordLength1_20Bits :{ -+ //1) clear bit -+ handle->XCR1 &= (~( 3 << MCBSP_XCR1_XWDLEN1_BITS)); -+ //2) set bit -+ handle->XCR1 |= ( 3 << MCBSP_XCR1_XWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_TransmitWordLength1_24Bits :{ -+ //1) clear bit -+ handle->XCR1 &= (~( 4 << MCBSP_XCR1_XWDLEN1_BITS)); -+ //2) set bit -+ handle->XCR1 |= ( 4 << MCBSP_XCR1_XWDLEN1_BITS); -+ break; -+ } -+ case MCBSP_TransmitWordLength1_32Bits :{ -+ //1) clear bit -+ handle->XCR1 &= (~( 5 << MCBSP_XCR1_XWDLEN1_BITS)); -+ //2) set bit -+ handle->XCR1 |= ( 5 << MCBSP_XCR1_XWDLEN1_BITS); -+ break; -+ } -+ default: { -+ break; -+ } -+ } -+ } // end of MCBSP_setTransmitWordLength1() function -+ -+ uint16_t MCBSP_getClockDiv(MCBSP_Handle handle){ -+ return ((handle->SRGR1 & 0x00FF) + 1); -+ } // end of MCBSP_getClockDiv() function -+ -+ void MCBSP_InitDelayLoop(MCBSP_Handle handle, long systemFrequencyMHz){ -+ long CPU_SPD = systemFrequencyMHz * 1000000; -+ long MCBSP_SRG_FREQ = CPU_SPD / MCBSP_getClockDiv(handle); -+ long MCBSP_INIT_DELAY = 2 * (CPU_SPD / MCBSP_SRG_FREQ); // # of CPU cycles in 2 SRG cycles-init delay -+ -+ long i; -+ for (i = 0; i < MCBSP_INIT_DELAY; i++) {} //delay in McBsp init. must be at least 2 SRG cycles -+ } // end of MCBSP_InitDelayLoop() function -diff -crwN motorware/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.h -*** motorware/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/drivers/mcbsp/SPImcBSP.h 2017-07-21 10:53:15.054335500 +0200 -*************** -*** 0 **** ---- 1,917 ---- -+ #ifndef SPIMCBSP_H_ -+ #define SPIMCBSP_H_ -+ -+ // ************************************************************************** -+ // the includes -+ -+ #include "sw/modules/types/src/types.h" -+ -+ #include "sw/drivers/cpu/src/32b/f28x/f2806x/cpu.h" -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ //! \brief Defines the base address of the (mcBSP) registers -+ //! -+ #define MCBSPA_BASE_ADDR (0x00005000) -+ #define MCBSPB_BASE_ADDR (0x00005040) -+ -+ //--------------------------------------------------------------------------- -+ -+ /**** Data Registers, Receive, Transmit ****/ -+ // DRR2_BITS (McBSP Data Receive Register 2) -+ // 15:0 High part of receive data (for 20-, 24- or 32-bit data) -+ #define MCBSP_DDR2_BITS 0 -+ -+ // DRR1_BITS (McBSP Data Receive Register 1) -+ // 15:0 Receive data (for 8-, 12-, or 16-bit data) or low part of receive data (for 20-, 24- or 32-bit data) -+ #define MCBSP_DDR1_BITS 0 -+ -+ // DXR2_BITS (McBSP Data Transmit Register 2) -+ // 15:0 High part of transmit data (for 20-, 24- or 32-bit data) -+ #define MCBSP_DXR2_BITS 0 -+ -+ // DXR1_BITS (McBSP Data Transmit Register 1) -+ // 15:0 Transmit data (for 8-, 12-, or 16-bit data) or low part of receive data (for 20-, 24- or 32-bit data) -+ #define MCBSP_DXR1_BITS 0 -+ -+ /**** McBSP Control Registers ****/ -+ // SPCR2_BITS (McBSP Serial Port Control Register 2) -+ // 0 Transmitter reset Bit -+ #define MCBSP_SPCR2_XRST_BIT 0 -+ // 1 Transmitter ready bit -+ #define MCBSP_SPCR2_XRDY_BIT 1 -+ // 2 Transmitter empty bit -+ #define MCBSP_SPCR2_XEMPTY_BIT 2 -+ // 3 Transmit frame-synchronization error bit -+ #define MCBSP_SPCR2_XSYNCERR_BITS 3 -+ // 5:4 Transmit interrupt mode bits -+ #define MCBSP_SPCR2_XINTM_BIT 4 -+ // 6 Sample rate generator reset bit -+ #define MCBSP_SPCR2_GRST_BIT 6 -+ // 7 Frame-synchronization logic reset bit -+ #define MCBSP_SPCR2_FRST_BIT 7 -+ // 8 Soft stop bit -+ #define MCBSP_SPCR2_SOFT_BIT 8 -+ // 9 Free run bit -+ #define MCBSP_SPCR2_FREE_BIT 9 -+ -+ // SPCR1_BITS (McBSP Serial Port Control Register 1) -+ // 0 Receiver reset bit -+ #define MCBSP_SPCR1_RRST_BIT 0 -+ // 1 Receiver ready bit -+ #define MCBSP_SPCR1_RRDY_BIT 1 -+ // 2 Receiver full bit. -+ #define MCBSP_SPCR1_RFULL_BIT 2 -+ // 3 Receive frame-sync error bit -+ #define MCBSP_SPCR1_RSYNCERR_BIT 3 -+ // 5:4 Receive interrupt mode bits -+ #define MCBSP_SPCR1_RINTM_BITS 4 -+ // 7 DX delay enabler mode bit -+ #define MCBSP_SPCR1_DXENA_BIT 7 -+ // 12:11 Clock stop mode bits -+ #define MCBSP_SPCR1_CLKSTP_BITS 11 -+ // 14:13 Receive sign-extension and justification mode bits -+ #define MCBSP_SPCR1_RJUST_BITS 13 -+ // 15 Digital loopback mode bit -+ #define MCBSP_SPCR1_DLB_BIT 15 -+ -+ // RCR2_BITS (McBSP Receive Control Register 2) -+ // 1:0 Receive data delay bits -+ #define MCBSP_RCR2_RDATDLY_BITS 0 -+ // 2 Receive frame-synchronization ignore bit -+ #define MCBSP_RCR2_RFIG_BIT 2 -+ // 4:3 Receive companding mode bits -+ #define MCBSP_RCR2_RCOMPAND_BITS 3 -+ // 7:5 Receive word length 2 -+ #define MCBSP_RCR2_RWDLEN2_BITS 5 -+ // 14:8 Receive frame length 2 -+ #define MCBSP_RCR2_RFRLEN2_BITS 8 -+ // 15 Receive phase number bit -+ #define MCBSP_RCR2_RPHASE_BIT 15 -+ -+ // RCR1_BITS (McBSP Receive Control Register 1) -+ // 7:5 Receive word length 1 -+ #define MCBSP_RCR1_RWDLEN1_BITS 5 -+ // 14:8 Receive frame length 1 (1 to 128 words) -+ #define MCBSP_RCR1_RFRLEN1_BITS 8 -+ -+ // XCR2_BITS (McBSP Transmit Control Register 2) -+ // 1:0 Transmit data delay bits -+ #define MCBSP_XCR2_XDATDLY_BITS 0 -+ // 2 Transmit frame-synchronization ignore bit -+ #define MCBSP_XCR2_XFIG 2 -+ // 4:3 Transmit companding mode bits -+ #define MCBSP_XCR2_XCOMPAND 3 -+ // 7:5 Transmit word length 2 -+ #define MCBSP_XCR2_XWDLEN2 5 -+ // 14:8 Transmit frame length 2 (1 to 128 words) -+ #define MCBSP_XCR2_XFRLEN2 8 -+ // 15 Transmit phase number bit -+ #define MCBSP_XCR2_XPHASE 15 -+ -+ // XCR1_BITS (McBSP Transmit Control Register 1) -+ // 7:5 Transmit word length 1 -+ #define MCBSP_XCR1_XWDLEN1_BITS 5 -+ // 14:8 Transmit frame length 1 (1 to 128 words) -+ #define MCBSP_XCR1_XFRLEN1_BITS 8 -+ -+ // SRGR2_BITS (McBSP Sample Rate Generator Register 2) -+ // 11:0 Frame-synchronization period bits for FSG -+ #define MCBSP_SRGR2_FPER_BITS 0 -+ // 12 Sample rate generator transmit frame-synchronization mode bit -+ #define MCBSP_SRGR2_FSGM_BIT 12 -+ // 13 Sample rate generator input clock mode bit -+ #define MCBSP_SRGR2_CLKSM_BIT 13 -+ // 15 Clock synchronization mode bit for CLKG -+ #define MCBSP_SRGR2_GSYNC_BIT 15 -+ -+ // SRGR1_BITS (McBSP Sample Rate Generator Register 1) -+ // 7:0 Divide-down value for CLKG -+ #define MCBSP_SRGR1_CLKGDV_BITS 0 -+ // 15:8 Frame-synchronization pulse width bits for FSG -+ #define MCBSP_SRGR1_FWID_BITS 8 -+ -+ /**** Multichannel Control Registers ****/ -+ // MCR2_BITS (McBSP Multichannel Register 2) -+ // 1:0 Transmit multichannel selection mode bits -+ #define MCBSP_MCR2_XMCM_BITS 0 -+ // 4:2 Transmit current block indicator -+ #define MCBSP_MCR2_XCBLK_BITS 2 -+ // 6:5 Transmit partition A block bits -+ #define MCBSP_MCR2_XPABLK_BITS 5 -+ // 8:7 Transmit partition B block bits -+ #define MCBSP_MCR2_XPBBLK_BITS 7 -+ // 9 Transmit multichannel partition mode bit -+ #define MCBSP_MCR2_XMCME_BIT 9 -+ -+ // MCR1_BITS (McBSP Multichannel Register 1) -+ // 0 Receive multichannel selection mode bit -+ #define MCBSP_MCR1_RMCM_BIT 0 -+ // 4:2 Receive current block indicator -+ #define MCBSP_MCR1_RCBLK_BITS 2 -+ // 6:5 Receive partition A block bits -+ #define MCBSP_MCR1_RPABLK_BITS 5 -+ // 8:7 Receive partition B block bits -+ #define MCBSP_MCR1_RPBBLK_BITS 7 -+ // 9 Receive multichannel partition mode bit -+ #define MCBSP_MCR1_RMCME_BIT 9 -+ -+ // the RCERA und RCERB - Bits were moved downwards, because -+ // RCERA to RCERH are internally of the same structure; -+ // the same is true for the XCERA - XCERH - Bits -+ -+ // PCR_BITS (McBSP Pin Control Register) -+ // 0 Receive clock polarity bit -+ #define MCBSP_PCR_CLKRP_BIT 0 -+ // 1 Transmit clock polarity bit -+ #define MCBSP_PCR_CLKXP_BIT 1 -+ // 2 Receive frame-synchronization polarity bit -+ #define MCBSP_PCR_FSRP_BIT 2 -+ // 3 Transmit frame-synchronization polarity bit -+ #define MCBSP_PCR_FSXP_BIT 3 -+ // 7 Sample rate generator input clock mode bit -+ #define MCBSP_PCR_SCLKME_BIT 7 -+ // 8 Receive clock mode bit -+ #define MCBSP_PCR_CLKRM_BIT 8 -+ // 9 Transmit clock mode bit -+ #define MCBSP_PCR_CLKXM_BIT 9 -+ // 10 Receive frame-synchronization mode bit -+ #define MCBSP_PCR_FSRM_BIT 10 -+ // 11 Transmit frame-synchronization mode bit -+ #define MCBSP_PCR_FSXM_BIT 11 -+ -+ // RCERA_BITS (McBSP Receive Channel Enable Register Partition A) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERA_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERA_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERA_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERA_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERA_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERA_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERA_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERA_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERA_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERA_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERA_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERA_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERA_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERA_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERA_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERA_RCE15_BIT 15 -+ -+ -+ // RCERB_BITS (McBSP Receive Channel Enable Register Partition B) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERB_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERB_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERB_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERB_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERB_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERB_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERB_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERB_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERB_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERB_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERB_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERB_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERB_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERB_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERB_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERB_RCE15_BIT 15 -+ -+ // RCERC_BITS (McBSP Receive Channel Enable Register Partition C) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERC_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERC_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERC_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERC_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERC_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERC_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERC_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERC_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERC_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERC_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERC_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERC_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERC_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERC_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERC_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERC_RCE15_BIT 15 -+ -+ // RCERD_BITS (McBSP Receive Channel Enable Register Partition D) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERD_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERD_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERD_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERD_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERD_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERD_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERD_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERD_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERD_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERD_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERD_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERD_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERD_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERD_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERD_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERD_RCE15_BIT 15 -+ -+ // RCERE_BITS (McBSP Receive Channel Enable Register Partition E) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERE_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERE_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERE_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERE_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERE_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERE_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERE_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERE_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERE_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERE_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERE_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERE_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERE_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERE_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERE_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERE_RCE15_BIT 15 -+ -+ // RCERF_BITS (McBSP Receive Channel Enable Register Partition F) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERF_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERF_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERF_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERF_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERF_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERF_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERF_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERF_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERF_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERF_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERF_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERF_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERF_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERF_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERF_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERF_RCE15_BIT 15 -+ -+ // RCERG_BITS (McBSP Receive Channel Enable Register Partition G) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERG_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERG_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERG_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERG_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERG_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERG_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERG_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERG_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERG_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERG_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERG_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERG_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERG_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERG_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERG_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERG_RCE15_BIT 15 -+ -+ // RCERH_BITS (McBSP Receive Channel Enable Register Partition H) -+ // 0 Receive channel enable bit -+ #define MCBSP_RCERH_RCE0_BIT 0 -+ // 1 Receive channel enable bit -+ #define MCBSP_RCERH_RCE1_BIT 1 -+ // 2 Receive channel enable bit -+ #define MCBSP_RCERH_RCE2_BIT 2 -+ // 3 Receive channel enable bit -+ #define MCBSP_RCERH_RCE3_BIT 3 -+ // 4 Receive channel enable bit -+ #define MCBSP_RCERH_RCE4_BIT 4 -+ // 5 Receive channel enable bit -+ #define MCBSP_RCERH_RCE5_BIT 5 -+ // 6 Receive channel enable bit -+ #define MCBSP_RCERH_RCE6_BIT 6 -+ // 7 Receive channel enable bit -+ #define MCBSP_RCERH_RCE7_BIT 7 -+ // 8 Receive channel enable bit -+ #define MCBSP_RCERH_RCE8_BIT 8 -+ // 9 Receive channel enable bit -+ #define MCBSP_RCERH_RCE9_BIT 9 -+ // 10 Receive channel enable bit -+ #define MCBSP_RCERH_RCE10_BIT 10 -+ // 11 Receive channel enable bit -+ #define MCBSP_RCERH_RCE11_BIT 11 -+ // 12 Receive channel enable bit -+ #define MCBSP_RCERH_RCE12_BIT 12 -+ // 13 Receive channel enable bit -+ #define MCBSP_RCERH_RCE13_BIT 13 -+ // 14 Receive channel enable bit -+ #define MCBSP_RCERH_RCE14_BIT 14 -+ // 15 Receive channel enable bit -+ #define MCBSP_RCERH_RCE15_BIT 15 -+ -+ // XCERA_BITS (McBSP Transmit Channel Enable Register Partition A) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERA_XCE15_BIT 15 -+ -+ // XCERB_BITS (McBSP Transmit Channel Enable Register Partition B) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERB_XCE15_BIT 15 -+ -+ // XCERC_BITS (McBSP Transmit Channel Enable Register Partition C) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERC_XCE15_BIT 15 -+ -+ // XCERD_BITS (McBSP Transmit Channel Enable Register Partition D) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERD_XCE15_BIT 15 -+ -+ // XCERE_BITS (McBSP Transmit Channel Enable Register Partition E) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERE_XCE15_BIT 15 -+ -+ // XCERF_BITS (McBSP Transmit Channel Enable Register Partition F) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERF_XCE15_BIT 15 -+ -+ // XCERG_BITS (McBSP Transmit Channel Enable Register Partition G) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERG_XCE15_BIT 15 -+ -+ // XCERH_BITS (McBSP Transmit Channel Enable Register Partition H) -+ // 0 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE0_BIT 0 -+ // 1 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE1_BIT 1 -+ // 2 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE2_BIT 2 -+ // 3 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE3_BIT 3 -+ // 4 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE4_BIT 4 -+ // 5 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE5_BIT 5 -+ // 6 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE6_BIT 6 -+ // 7 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE7_BIT 7 -+ // 8 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE8_BIT 8 -+ // 9 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE9_BIT 9 -+ // 10 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE10_BIT 10 -+ // 11 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE11_BIT 11 -+ // 12 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE12_BIT 12 -+ // 13 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE13_BIT 13 -+ // 14 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE14_BIT 14 -+ // 15 Transmit channel enable bit -+ #define MCBSP_XCERH_XCE15_BIT 15 -+ -+ // MFFINT_BITS (McBSP Interrupt Enable Register) -+ // 0 Enable for transmit Interrupt -+ #define MCBSP_MFFINT_XINT__ENA_BIT 0 -+ // 2 Enable for Receive Interrupt -+ #define MCBSP_MFFINTRINT__ENA_BIT 2 -+ -+ //! \brief Defines the Multichannel Buffered Serial Port (McBSP) object -+ typedef struct _MCBSP_Obj_ { -+ volatile uint16_t DRR2; // Data receive register bits 31-16 -+ volatile uint16_t DRR1; // Data receive register bits 15-0 -+ volatile uint16_t DXR2; // Data transmit register bits 31-16 -+ volatile uint16_t DXR1; // Data transmit register bits 15-0 -+ volatile uint16_t SPCR2; // Control register 2 -+ volatile uint16_t SPCR1; // Control register 1 -+ volatile uint16_t RCR2; // Receive Control register 2 -+ volatile uint16_t RCR1; // Receive Control register 1 -+ volatile uint16_t XCR2; // Transmit Control register 2 -+ volatile uint16_t XCR1; // Transmit Control register 1 -+ volatile uint16_t SRGR2; // Sample rate generator register 2 -+ volatile uint16_t SRGR1; // Sample rate generator register 1 -+ volatile uint16_t MCR2; // Multi-channel register 2 -+ volatile uint16_t MCR1; // Multi-channel register 1 -+ volatile uint16_t RCERA; // Receive channel enable partition A -+ volatile uint16_t RCERB; // Receive channel enable partition B -+ volatile uint16_t XCERA; // Transmit channel enable partition A -+ volatile uint16_t XCERB; // Transmit channel enable partition B -+ volatile uint16_t PCR; // Pin Control register -+ volatile uint16_t RCERC; // Receive channel enable partition C -+ volatile uint16_t RCERD; // Receive channel enable partition D -+ volatile uint16_t XCERC; // Transmit channel enable partition C -+ volatile uint16_t XCERD; // Transmit channel enable partition D -+ volatile uint16_t RCERE; // Receive channel enable partition E -+ volatile uint16_t RCERF; // Receive channel enable partition F -+ volatile uint16_t XCERE; // Transmit channel enable partition E -+ volatile uint16_t XCERF; // Transmit channel enable partition F -+ volatile uint16_t RCERG; // Receive channel enable partition G -+ volatile uint16_t RCERH; // Receive channel enable partition H -+ volatile uint16_t XCERG; // Transmit channel enable partition G -+ volatile uint16_t XCERH; // Transmit channel enable partition H -+ volatile uint16_t rsvd1[4]; // Reserved -+ volatile uint16_t MFFINT; // Interrupt enable -+ } MCBSP_Obj; -+ -+ //! \brief Defines the Multichannel Buffered Serial Port (McBSP) handle -+ typedef struct _MCBSP_Obj_ *MCBSP_Handle; -+ -+ extern MCBSP_Handle MCBSP_init(void *pMemory,const size_t numBytes); -+ -+ extern void McBSP_stop(MCBSP_Handle handle); -+ -+ extern void McBSP_run(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetTransmitter(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetReleaseTransmitter(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetReceiver(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetReleaseReceiver(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetSampleRateGenerator(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetFrameSynchronizationLogic(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetReleaseFrameSynchronizationLogic(MCBSP_Handle handle); -+ -+ extern void MCBSP_resetReleaseSampleRateGenerator(MCBSP_Handle handle); -+ -+ enum McBSP_Mode{ -+ McBsp_SPIMasterMode0, McBsp_SPIMasterMode1, McBsp_SPIMasterMode2, McBsp_SPIMasterMode3, -+ McBsp_SPISlaveMode0, McBsp_SPISlaveMode1, McBsp_SPISlaveMode2, McBsp_SPISlaveMode3 -+ }; -+ -+ enum McBSP_Loopback{ -+ McBSP_disableLoopback, McBSP_enableLoopback -+ }; -+ -+ extern void MCBSP_setMode(MCBSP_Handle handle, -+ uint16_t mode, -+ uint16_t digitalLoopback); -+ -+ enum McBSP_SampleRateGenSource{ -+ McBSP_SampleRateGen_Source_LSPCLK, McBSP_SampleRateGen_Source_MCLKR_Pin, McBSP_SampleRateGen_Source_MCLKX_Pin -+ }; -+ -+ extern void MCBSP_sampleRateGeneratorInputClockMode(MCBSP_Handle handle, uint16_t sampleRateGenSRC); -+ -+ enum MCBSP_TransmitFrameSyncMode{ -+ MCBSP_TransmitFrameSyncMode_EXTERNAL, // Sync is supplied by external source via the FSX Pin -+ MCBSP_TransmitFrameSyncMode_INTERNAL // Sync is supplied internal by by the Sample Rate Generator -+ }; -+ extern void MCBSP_setTransmitFrameSynchronizationMode(MCBSP_Handle handle, uint16_t snycMode); -+ -+ enum MCBSP_ReceiveFrameSyncMode{ -+ MCBSP_ReceiveFrameSyncMode_EXTERNAL, // Sync is supplied by external source via the FSR Pin -+ MCBSP_ReceiveFrameSyncMode_INTERNAL // Sync is supplied internal by by the Sample Rate Generator -+ }; -+ -+ extern void MCBSP_setReceiveFrameSynchronizationMode(MCBSP_Handle handle, uint16_t snycMode); -+ -+ enum MCBSP_TransmitFrameSyncPol{ -+ MCBSP_TransmitFrameSync__ACTIVE_HIGH, MCBSP_TransmitFrameSync__ACTIVE_LOW -+ }; -+ -+ extern void MCBSP_setTransmitFrameSyncPolarity(MCBSP_Handle handle, uint16_t transmitPol); -+ -+ enum MCBSP_ReceiveFrameSyncPol{ -+ MCBSP_ReceiveFrameSync__ACTIVE_HIGH, MCBSP_ReceiveFrameSync__ACTIVE_LOW -+ }; -+ -+ extern void MCBSP_setReceiveFrameSyncPolarity(MCBSP_Handle handle, uint16_t transmitPol); -+ -+ extern void MCBSP_setSRGClockDivider(MCBSP_Handle handle, uint16_t divider); -+ -+ enum MCBSP_TransmitDataDelay{ -+ MCBSP_TransmitDataDelay_0Bit, MCBSP_TransmitDataDelay_1Bit, MCBSP_TransmitDataDelay_2Bit -+ }; -+ -+ extern void MCBSP_setTransmitDataDelay(MCBSP_Handle handle, uint16_t delay); -+ -+ enum MCBSP_ReceiveDataDelay{ -+ MCBSP_ReceiveDataDelay_0Bit, MCBSP_ReceiveDataDelay_1Bit, MCBSP_ReceiveDataDelay_2Bit -+ }; -+ -+ extern void MCBSP_setReceiveDataDelay(MCBSP_Handle handle, uint16_t delay); -+ -+ enum MCBSP_ReceiveWordLength1{ -+ MCBSP_ReceiveWordLength1_8Bits, MCBSP_ReceiveWordLength1_12Bits, MCBSP_ReceiveWordLength1_16Bits, -+ MCBSP_ReceiveWordLength1_20Bits, MCBSP_ReceiveWordLength1_24Bits, MCBSP_ReceiveWordLength1_32Bits -+ }; -+ -+ extern void MCBSP_setReceiveWordLength1(MCBSP_Handle handle, uint16_t length); -+ -+ enum MCBSP_TransmitWordLength1{ -+ MCBSP_TransmitWordLength1_8Bits, MCBSP_TransmitWordLength1_12Bits, MCBSP_TransmitWordLength1_16Bits, -+ MCBSP_TransmitWordLength1_20Bits, MCBSP_TransmitWordLength1_24Bits, MCBSP_TransmitWordLength1_32Bits -+ }; -+ -+ extern void MCBSP_setTransmitWordLength1(MCBSP_Handle handle, uint16_t length); -+ -+ extern void MCBSP_InitDelayLoop(MCBSP_Handle handle, long systemFrequencyMHz); -+ -+ enum MCBSP_TransmitClockPolarity{ -+ MCBSP_TransmitClockPolarity_dataSampleRisingEdge, -+ MCBSP_TransmitClockPolarity_dataSampleFallingEdge -+ }; -+ -+ extern void MCBSP_setTransmitClockPolarity(MCBSP_Handle handle, uint16_t polarity); -+ -+ enum MCBSP_TransmitClockMode{ -+ MCBSP_TransmitClockMode_ExternalClkSPISlave, -+ MCBSP_TransmitClockMode_InternalClkSPIMaster -+ }; -+ -+ extern void MCBSP_setTransmitClockMode(MCBSP_Handle handle, uint16_t txClkMode); -+ -+ enum MCBSP_ReceiveClockPolarity{ -+ MCBSP_ReceiveClockPolarity_dataSampleRisingEdge, -+ MCBSP_ReceiveClockPolarity_dataSampleFallingEdge -+ }; -+ -+ extern void MCBSP_setReceiveClockPolarity(MCBSP_Handle handle, uint16_t polarity); -+ -+ // this depends on the device being in DLB-Mode! -+ // these definitions are valid for non-DLB-Mode -+ enum MCBSP_ReceiveClockMode{ -+ MCBSP_ReceiveClockMode_ExternalClk, -+ MCBSP_ReceiveClockMode_InternalClk -+ }; -+ -+ extern void MCBSP_setReceiveClockMode(MCBSP_Handle handle, uint16_t rcvClkMode); -+ -+ enum MCBSP_ClockStopMode{ -+ MCBSP_ClockStopMode_DISABLED, -+ MCBSP_ClockStopMode_WithoutClockDelay, -+ MCBSP_ClockStopMode_HalfCycleClockDelay -+ }; -+ -+ extern void MCBSP_setClockStopMode(MCBSP_Handle handle, uint16_t clkStopMode); -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ #endif /* SPIMCBSP_H_ */ -diff -crwN motorware/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069F_ram_lnk.cmd motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069F_ram_lnk.cmd -*** motorware/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069F_ram_lnk.cmd 2015-09-08 13:10:18.000000000 +0200 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069F_ram_lnk.cmd 2017-06-21 16:36:38.622344300 +0200 -*************** -*** 78,84 **** - - BEGIN : origin = 0x000000, length = 0x000002 /* BEGIN is used for the "boot to SARAM" bootloader mode */ - RAMM0 : origin = 0x000050, length = 0x0003B0 -! RAML0_L8 : origin = 0x008000, length = 0x00B800 /* on-chip RAM block RAML0-L8. From 0x13800 to 0x14000 is reserved for InstaSPIN */ - - RESET : origin = 0x3FFFC0, length = 0x000002 - FPUTABLES : origin = 0x3FD590, length = 0x0006A0 /* FPU Tables in Boot ROM */ ---- 78,87 ---- - - BEGIN : origin = 0x000000, length = 0x000002 /* BEGIN is used for the "boot to SARAM" bootloader mode */ - RAMM0 : origin = 0x000050, length = 0x0003B0 -! // (RAML0_L8) is shrinked here, because I need a dedicated ram space for the DMA-Controller -! // "RAML0_L7" and "RAML8" at "PAGE 1" is spaced, that the region for InstaSPIN rests as is -! ///* alt */RAML0_L8 : origin = 0x008000, length = 0x00B800 /* on-chip RAM block RAML0-L8. From 0x13800 to 0x14000 is reserved for InstaSPIN */ -! RAML0_L7 : origin = 0x008000, length = 0x0097FF /* on-chip RAM block RAML0-L7. From 0x13800 to 0x14000 is reserved for InstaSPIN ? */ - - RESET : origin = 0x3FFFC0, length = 0x000002 - FPUTABLES : origin = 0x3FD590, length = 0x0006A0 /* FPU Tables in Boot ROM */ -*************** -*** 93,98 **** ---- 96,102 ---- - - BOOT_RSVD : origin = 0x000002, length = 0x00004E /* Part of M0, BOOT rom will use this for stack */ - RAMM1 : origin = 0x000400, length = 0x000400 /* on-chip RAM block M1 */ -+ RAML8 : origin = 0x011800, length = 0x001FFF /* on-chip RAM block L8 (used by DMA) */ - USB_RAM : origin = 0x040000, length = 0x000800 /* USB RAM */ - } - -*************** -*** 109,133 **** - RUN_START(_RamfuncsRunStart), - LOAD_SIZE(_RamfuncsLoadSize), - PAGE = 0 -! .text : > RAML0_L8, PAGE = 0 - .cinit : > RAMM0, PAGE = 0 - .pinit : > RAMM0, PAGE = 0 - .switch : > RAMM0, PAGE = 0 - .reset : > RESET, PAGE = 0, TYPE = DSECT /* not used, */ - - .stack : > RAMM1, PAGE = 1 -! .ebss : > RAML0_L8, PAGE = 0 -! .econst : > RAML0_L8, PAGE = 0 -! .esysmem : > RAML0_L8, PAGE = 0 -! -! IQmath : > RAML0_L8, PAGE = 0 - IQmathTables : > IQTABLES, PAGE = 0, TYPE = NOLOAD - - /* Allocate FPU math areas: */ - FPUmathTables : > FPUTABLES, PAGE = 0, TYPE = NOLOAD - - /* DMARAML4_6 : > RAML4_6, PAGE = 1 /* */ -! - - /* Uncomment the section below if calling the IQNexp() or IQexp() - functions from the IQMath.lib library in order to utilize the ---- 113,141 ---- - RUN_START(_RamfuncsRunStart), - LOAD_SIZE(_RamfuncsLoadSize), - PAGE = 0 -! // old: .text : > RAML0_L8, PAGE = 0 -! .text : > RAML0_L7, PAGE = 0 - .cinit : > RAMM0, PAGE = 0 - .pinit : > RAMM0, PAGE = 0 - .switch : > RAMM0, PAGE = 0 - .reset : > RESET, PAGE = 0, TYPE = DSECT /* not used, */ - - .stack : > RAMM1, PAGE = 1 -! // old: .ebss : > RAML0_L8, PAGE = 0 -! .ebss : > RAML0_L7, PAGE = 0 -! // old: .econst : > RAML0_L8, PAGE = 0 -! .econst : > RAML0_L7, PAGE = 0 -! // old: .esysmem : > RAML0_L8, PAGE = 0 -! .esysmem : > RAML0_L7, PAGE = 0 -! // old: IQmath : > RAML0_L8, PAGE = 0 -! IQmath : > RAML0_L7, PAGE = 0 - IQmathTables : > IQTABLES, PAGE = 0, TYPE = NOLOAD - - /* Allocate FPU math areas: */ - FPUmathTables : > FPUTABLES, PAGE = 0, TYPE = NOLOAD - - /* DMARAML4_6 : > RAML4_6, PAGE = 1 /* */ -! DMARAML8 : > RAML8, PAGE = 1 - - /* Uncomment the section below if calling the IQNexp() or IQexp() - functions from the IQMath.lib library in order to utilize the -*************** -*** 160,167 **** - } - */ - -! Cla1Prog : > RAML0_L8, PAGE = 0 -! unsecure_data : > RAML0_L8, PAGE = 0 - } - - /* ---- 168,177 ---- - } - */ - -! // old: Cla1Prog : > RAML0_L8, PAGE = 0 -! Cla1Prog : > RAML0_L7, PAGE = 0 -! // old: unsecure_data : > RAML0_L8, PAGE = 0 -! unsecure_data : > RAML0_L7, PAGE = 0 - } - - /* -diff -crwN motorware/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069M_ram_lnk.cmd motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069M_ram_lnk.cmd -*** motorware/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069M_ram_lnk.cmd 2015-09-08 13:10:18.000000000 +0200 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/ide/ccs/cmd/f2806x/f28069M_ram_lnk.cmd 2017-06-27 18:43:11.758812100 +0200 -*************** -*** 78,84 **** - - BEGIN : origin = 0x000000, length = 0x000002 /* BEGIN is used for the "boot to SARAM" bootloader mode */ - RAMM0 : origin = 0x000050, length = 0x0003B0 -! RAML0_L8 : origin = 0x008000, length = 0x00B800 /* on-chip RAM block RAML0-L8. From 0x13800 to 0x14000 is reserved for InstaSPIN */ - - RESET : origin = 0x3FFFC0, length = 0x000002 - FPUTABLES : origin = 0x3FD590, length = 0x0006A0 /* FPU Tables in Boot ROM */ ---- 78,87 ---- - - BEGIN : origin = 0x000000, length = 0x000002 /* BEGIN is used for the "boot to SARAM" bootloader mode */ - RAMM0 : origin = 0x000050, length = 0x0003B0 -! // (RAML0_L8) is shrinked here, because I need a dedicated ram space for the DMA-Controller -! // "RAML0_L7" and "RAML8" at "PAGE 1" is spaced, that the region for InstaSPIN rests as is -! ///* alt */RAML0_L8 : origin = 0x008000, length = 0x00B800 /* on-chip RAM block RAML0-L8. From 0x13800 to 0x14000 is reserved for InstaSPIN */ -! RAML0_L7 : origin = 0x008000, length = 0x00B6FF /* on-chip RAM block RAML0-L7. From 0x13800 to 0x14000 is reserved for InstaSPIN ? */ - - RESET : origin = 0x3FFFC0, length = 0x000002 - FPUTABLES : origin = 0x3FD590, length = 0x0006A0 /* FPU Tables in Boot ROM */ -*************** -*** 93,98 **** ---- 96,102 ---- - - BOOT_RSVD : origin = 0x000002, length = 0x00004E /* Part of M0, BOOT rom will use this for stack */ - RAMM1 : origin = 0x000400, length = 0x000400 /* on-chip RAM block M1 */ -+ RAML8 : origin = 0x013700, length = 0x0000FF /* on-chip RAM block L8 (used by DMA) */ - USB_RAM : origin = 0x040000, length = 0x000800 /* USB RAM */ - } - -*************** -*** 109,133 **** - RUN_START(_RamfuncsRunStart), - LOAD_SIZE(_RamfuncsLoadSize), - PAGE = 0 -! .text : > RAML0_L8, PAGE = 0 - .cinit : > RAMM0, PAGE = 0 - .pinit : > RAMM0, PAGE = 0 - .switch : > RAMM0, PAGE = 0 - .reset : > RESET, PAGE = 0, TYPE = DSECT /* not used, */ - - .stack : > RAMM1, PAGE = 1 -! .ebss : > RAML0_L8, PAGE = 0 -! .econst : > RAML0_L8, PAGE = 0 -! .esysmem : > RAML0_L8, PAGE = 0 -! -! IQmath : > RAML0_L8, PAGE = 0 - IQmathTables : > IQTABLES, PAGE = 0, TYPE = NOLOAD - - /* Allocate FPU math areas: */ - FPUmathTables : > FPUTABLES, PAGE = 0, TYPE = NOLOAD - - /* DMARAML4_6 : > RAML4_6, PAGE = 1 /* */ -! - - /* Uncomment the section below if calling the IQNexp() or IQexp() - functions from the IQMath.lib library in order to utilize the ---- 113,141 ---- - RUN_START(_RamfuncsRunStart), - LOAD_SIZE(_RamfuncsLoadSize), - PAGE = 0 -! // old: .text : > RAML0_L8, PAGE = 0 -! .text : > RAML0_L7, PAGE = 0 - .cinit : > RAMM0, PAGE = 0 - .pinit : > RAMM0, PAGE = 0 - .switch : > RAMM0, PAGE = 0 - .reset : > RESET, PAGE = 0, TYPE = DSECT /* not used, */ - - .stack : > RAMM1, PAGE = 1 -! // old: .ebss : > RAML0_L8, PAGE = 0 -! .ebss : > RAML0_L7, PAGE = 0 -! // old: .econst : > RAML0_L8, PAGE = 0 -! .econst : > RAML0_L7, PAGE = 0 -! // old: .esysmem : > RAML0_L8, PAGE = 0 -! .esysmem : > RAML0_L7, PAGE = 0 -! // old: IQmath : > RAML0_L8, PAGE = 0 -! IQmath : > RAML0_L7, PAGE = 0 - IQmathTables : > IQTABLES, PAGE = 0, TYPE = NOLOAD - - /* Allocate FPU math areas: */ - FPUmathTables : > FPUTABLES, PAGE = 0, TYPE = NOLOAD - - /* DMARAML4_6 : > RAML4_6, PAGE = 1 /* */ -! DMARAML8 : > RAML8, PAGE = 1 - - /* Uncomment the section below if calling the IQNexp() or IQexp() - functions from the IQMath.lib library in order to utilize the -*************** -*** 160,167 **** - } - */ - -! Cla1Prog : > RAML0_L8, PAGE = 0 -! unsecure_data : > RAML0_L8, PAGE = 0 - } - - /* ---- 168,177 ---- - } - */ - -! // old: Cla1Prog : > RAML0_L8, PAGE = 0 -! Cla1Prog : > RAML0_L7, PAGE = 0 -! // old: unsecure_data : > RAML0_L8, PAGE = 0 -! unsecure_data : > RAML0_L7, PAGE = 0 - } - - /* -diff -crwN motorware/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams.h -*** motorware/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams.h 2015-01-20 15:28:10.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams.h 2017-06-08 10:41:26.376948300 +0200 -*************** -*** 260,265 **** ---- 260,267 ---- - float_t maxNegativeIdCurrent_a; //!< Defines the maximum negative current that the Id PID is allowed to go to, A - - USER_ErrorCode_e errorCode; -+ // Test : add a further Parameter here for the FIKAT -+ float_t analogIn_voltage_sf; //!< Defines the voltage scale factor for the six external analog Inputs - } USER_Params; - - -diff -crwN motorware/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams_2motors.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams_2motors.h -*** motorware/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams_2motors.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/fast/src/32b/userParams_2motors.h 2017-03-22 17:28:20.000000000 +0100 -*************** -*** 0 **** ---- 1,284 ---- -+ #ifndef _USERPARAMS_2MOTORS_H_ -+ #define _USERPARAMS_2MOTORS_H_ -+ /* --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/boards/drv8301kit_revD/f28x/f2806xF/src/userParams_2motors.h -+ //! \brief Defines the structures for the USER_Params object -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // modules -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/motor/src/32b/motor.h" -+ -+ #include "sw/modules/est/src/est_states.h" -+ #include "sw/modules/est/src/est_Flux_states.h" -+ #include "sw/modules/est/src/est_Ls_states.h" -+ #include "sw/modules/est/src/est_Rs_states.h" -+ -+ #include "sw/modules/ctrl/src/ctrl_states.h" -+ -+ -+ //! -+ //! -+ //! \defgroup USERPARAMS USERPARAMS -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ -+ // ************************************************************************** -+ // the defines -+ -+ #define USER_SYSTEM_FREQ_MHz_COM (90.0) // 90.0MHz -+ -+ //! \brief Defines the Pulse Width Modulation (PWM) frequency, kHz -+ //! \brief PWM frequency can be set directly here up to 30 KHz safely (60 KHz MAX in some cases) -+ //! \brief For higher PWM frequencies (60 KHz+ typical for low inductance, high current ripple motors) it is recommended to use the ePWM hardware -+ //! \brief and adjustable ADC SOC to decimate the ADC conversion done interrupt to the control system, or to use the software Que example. -+ //! \brief Otherwise you risk missing interrupts and disrupting the timing of the control state machine -+ //#define USER_PWM_FREQ_kHz_COM (5.0) // 5.0kHz for run in Flash -+ #define USER_PWM_FREQ_kHz_COM (10.0) // 10.0kHz for run in Flash -+ -+ // ************************************************************************** -+ // the typedefs -+ -+ //! \brief Enumeration for the user error codes -+ //! -+ typedef enum -+ { -+ USER_ErrorCode_NoError=0, //!< no error error code -+ USER_ErrorCode_iqFullScaleCurrent_A_High=1, //!< iqFullScaleCurrent_A too high error code -+ USER_ErrorCode_iqFullScaleCurrent_A_Low=2, //!< iqFullScaleCurrent_A too low error code -+ USER_ErrorCode_iqFullScaleVoltage_V_High=3, //!< iqFullScaleVoltage_V too high error code -+ USER_ErrorCode_iqFullScaleVoltage_V_Low=4, //!< iqFullScaleVoltage_V too low error code -+ USER_ErrorCode_iqFullScaleFreq_Hz_High=5, //!< iqFullScaleFreq_Hz too high error code -+ USER_ErrorCode_iqFullScaleFreq_Hz_Low=6, //!< iqFullScaleFreq_Hz too low error code -+ USER_ErrorCode_numPwmTicksPerIsrTick_High=7, //!< numPwmTicksPerIsrTick too high error code -+ USER_ErrorCode_numPwmTicksPerIsrTick_Low=8, //!< numPwmTicksPerIsrTick too low error code -+ USER_ErrorCode_numIsrTicksPerCtrlTick_High=9, //!< numIsrTicksPerCtrlTick too high error code -+ USER_ErrorCode_numIsrTicksPerCtrlTick_Low=10, //!< numIsrTicksPerCtrlTick too low error code -+ USER_ErrorCode_numCtrlTicksPerCurrentTick_High=11, //!< numCtrlTicksPerCurrentTick too high error code -+ USER_ErrorCode_numCtrlTicksPerCurrentTick_Low=12, //!< numCtrlTicksPerCurrentTick too low error code -+ USER_ErrorCode_numCtrlTicksPerEstTick_High=13, //!< numCtrlTicksPerEstTick too high error code -+ USER_ErrorCode_numCtrlTicksPerEstTick_Low=14, //!< numCtrlTicksPerEstTick too low error code -+ USER_ErrorCode_numCtrlTicksPerSpeedTick_High=15, //!< numCtrlTicksPerSpeedTick too high error code -+ USER_ErrorCode_numCtrlTicksPerSpeedTick_Low=16, //!< numCtrlTicksPerSpeedTick too low error code -+ USER_ErrorCode_numCtrlTicksPerTrajTick_High=17, //!< numCtrlTicksPerTrajTick too high error code -+ USER_ErrorCode_numCtrlTicksPerTrajTick_Low=18, //!< numCtrlTicksPerTrajTick too low error code -+ USER_ErrorCode_numCurrentSensors_High=19, //!< numCurrentSensors too high error code -+ USER_ErrorCode_numCurrentSensors_Low=20, //!< numCurrentSensors too low error code -+ USER_ErrorCode_numVoltageSensors_High=21, //!< numVoltageSensors too high error code -+ USER_ErrorCode_numVoltageSensors_Low=22, //!< numVoltageSensors too low error code -+ USER_ErrorCode_offsetPole_rps_High=23, //!< offsetPole_rps too high error code -+ USER_ErrorCode_offsetPole_rps_Low=24, //!< offsetPole_rps too low error code -+ USER_ErrorCode_fluxPole_rps_High=25, //!< fluxPole_rps too high error code -+ USER_ErrorCode_fluxPole_rps_Low=26, //!< fluxPole_rps too low error code -+ USER_ErrorCode_zeroSpeedLimit_High=27, //!< zeroSpeedLimit too high error code -+ USER_ErrorCode_zeroSpeedLimit_Low=28, //!< zeroSpeedLimit too low error code -+ USER_ErrorCode_forceAngleFreq_Hz_High=29, //!< forceAngleFreq_Hz too high error code -+ USER_ErrorCode_forceAngleFreq_Hz_Low=30, //!< forceAngleFreq_Hz too low error code -+ USER_ErrorCode_maxAccel_Hzps_High=31, //!< maxAccel_Hzps too high error code -+ USER_ErrorCode_maxAccel_Hzps_Low=32, //!< maxAccel_Hzps too low error code -+ USER_ErrorCode_maxAccel_est_Hzps_High=33, //!< maxAccel_est_Hzps too high error code -+ USER_ErrorCode_maxAccel_est_Hzps_Low=34, //!< maxAccel_est_Hzps too low error code -+ USER_ErrorCode_directionPole_rps_High=35, //!< directionPole_rps too high error code -+ USER_ErrorCode_directionPole_rps_Low=36, //!< directionPole_rps too low error code -+ USER_ErrorCode_speedPole_rps_High=37, //!< speedPole_rps too high error code -+ USER_ErrorCode_speedPole_rps_Low=38, //!< speedPole_rps too low error code -+ USER_ErrorCode_dcBusPole_rps_High=39, //!< dcBusPole_rps too high error code -+ USER_ErrorCode_dcBusPole_rps_Low=40, //!< dcBusPole_rps too low error code -+ USER_ErrorCode_fluxFraction_High=41, //!< fluxFraction too high error code -+ USER_ErrorCode_fluxFraction_Low=42, //!< fluxFraction too low error code -+ USER_ErrorCode_indEst_speedMaxFraction_High=43, //!< indEst_speedMaxFraction too high error code -+ USER_ErrorCode_indEst_speedMaxFraction_Low=44, //!< indEst_speedMaxFraction too low error code -+ USER_ErrorCode_powerWarpGain_High=45, //!< powerWarpGain too high error code -+ USER_ErrorCode_powerWarpGain_Low=46, //!< powerWarpGain too low error code -+ USER_ErrorCode_systemFreq_MHz_High=47, //!< systemFreq_MHz too high error code -+ USER_ErrorCode_systemFreq_MHz_Low=48, //!< systemFreq_MHz too low error code -+ USER_ErrorCode_pwmFreq_kHz_High=49, //!< pwmFreq_kHz too high error code -+ USER_ErrorCode_pwmFreq_kHz_Low=50, //!< pwmFreq_kHz too low error code -+ USER_ErrorCode_voltage_sf_High=51, //!< voltage_sf too high error code -+ USER_ErrorCode_voltage_sf_Low=52, //!< voltage_sf too low error code -+ USER_ErrorCode_current_sf_High=53, //!< current_sf too high error code -+ USER_ErrorCode_current_sf_Low=54, //!< current_sf too low error code -+ USER_ErrorCode_voltageFilterPole_Hz_High=55, //!< voltageFilterPole_Hz too high error code -+ USER_ErrorCode_voltageFilterPole_Hz_Low=56, //!< voltageFilterPole_Hz too low error code -+ USER_ErrorCode_maxVsMag_pu_High=57, //!< maxVsMag_pu too high error code -+ USER_ErrorCode_maxVsMag_pu_Low=58, //!< maxVsMag_pu too low error code -+ USER_ErrorCode_estKappa_High=59, //!< estKappa too high error code -+ USER_ErrorCode_estKappa_Low=60, //!< estKappa too low error code -+ USER_ErrorCode_motor_type_Unknown=61, //!< motor type unknown error code -+ USER_ErrorCode_motor_numPolePairs_High=62, //!< motor_numPolePairs too high error code -+ USER_ErrorCode_motor_numPolePairs_Low=63, //!< motor_numPolePairs too low error code -+ USER_ErrorCode_motor_ratedFlux_High=64, //!< motor_ratedFlux too high error code -+ USER_ErrorCode_motor_ratedFlux_Low=65, //!< motor_ratedFlux too low error code -+ USER_ErrorCode_motor_Rr_High=66, //!< motor_Rr too high error code -+ USER_ErrorCode_motor_Rr_Low=67, //!< motor_Rr too low error code -+ USER_ErrorCode_motor_Rs_High=68, //!< motor_Rs too high error code -+ USER_ErrorCode_motor_Rs_Low=69, //!< motor_Rs too low error code -+ USER_ErrorCode_motor_Ls_d_High=70, //!< motor_Ls_d too high error code -+ USER_ErrorCode_motor_Ls_d_Low=71, //!< motor_Ls_d too low error code -+ USER_ErrorCode_motor_Ls_q_High=72, //!< motor_Ls_q too high error code -+ USER_ErrorCode_motor_Ls_q_Low=73, //!< motor_Ls_q too low error code -+ USER_ErrorCode_maxCurrent_High=74, //!< maxCurrent too high error code -+ USER_ErrorCode_maxCurrent_Low=75, //!< maxCurrent too low error code -+ USER_ErrorCode_maxCurrent_resEst_High=76, //!< maxCurrent_resEst too high error code -+ USER_ErrorCode_maxCurrent_resEst_Low=77, //!< maxCurrent_resEst too low error code -+ USER_ErrorCode_maxCurrent_indEst_High=78, //!< maxCurrent_indEst too high error code -+ USER_ErrorCode_maxCurrent_indEst_Low=79, //!< maxCurrent_indEst too low error code -+ USER_ErrorCode_maxCurrentSlope_High=80, //!< maxCurrentSlope too high error code -+ USER_ErrorCode_maxCurrentSlope_Low=81, //!< maxCurrentSlope too low error code -+ USER_ErrorCode_maxCurrentSlope_powerWarp_High=82, //!< maxCurrentSlope_powerWarp too high error code -+ USER_ErrorCode_maxCurrentSlope_powerWarp_Low=83, //!< maxCurrentSlope_powerWarp too low error code -+ USER_ErrorCode_IdRated_High=84, //!< IdRated too high error code -+ USER_ErrorCode_IdRated_Low=85, //!< IdRated too low error code -+ USER_ErrorCode_IdRatedFraction_indEst_High=86, //!< IdRatedFraction_indEst too high error code -+ USER_ErrorCode_IdRatedFraction_indEst_Low=87, //!< IdRatedFraction_indEst too low error code -+ USER_ErrorCode_IdRatedFraction_ratedFlux_High=88, //!< IdRatedFraction_ratedFlux too high error code -+ USER_ErrorCode_IdRatedFraction_ratedFlux_Low=89, //!< IdRatedFraction_ratedFlux too low error code -+ USER_ErrorCode_IdRated_delta_High=90, //!< IdRated_delta too high error code -+ USER_ErrorCode_IdRated_delta_Low=91, //!< IdRated_delta too low error code -+ USER_ErrorCode_fluxEstFreq_Hz_High=92, //!< fluxEstFreq_Hz too high error code -+ USER_ErrorCode_fluxEstFreq_Hz_Low=93, //!< fluxEstFreq_Hz too low error code -+ USER_ErrorCode_ctrlFreq_Hz_High=94, //!< ctrlFreq_Hz too high error code -+ USER_ErrorCode_ctrlFreq_Hz_Low=95, //!< ctrlFreq_Hz too low error code -+ USER_ErrorCode_estFreq_Hz_High=96, //!< estFreq_Hz too high error code -+ USER_ErrorCode_estFreq_Hz_Low=97, //!< estFreq_Hz too low error code -+ USER_ErrorCode_RoverL_estFreq_Hz_High=98, //!< RoverL_estFreq_Hz too high error code -+ USER_ErrorCode_RoverL_estFreq_Hz_Low=99, //!< RoverL_estFreq_Hz too low error code -+ USER_ErrorCode_trajFreq_Hz_High=100, //!< trajFreq_Hz too high error code -+ USER_ErrorCode_trajFreq_Hz_Low=101, //!< trajFreq_Hz too low error code -+ USER_ErrorCode_ctrlPeriod_sec_High=102, //!< ctrlPeriod_sec too high error code -+ USER_ErrorCode_ctrlPeriod_sec_Low=103, //!< ctrlPeriod_sec too low error code -+ USER_ErrorCode_maxNegativeIdCurrent_a_High=104, //!< maxNegativeIdCurrent_a too high error code -+ USER_ErrorCode_maxNegativeIdCurrent_a_Low=105, //!< maxNegativeIdCurrent_a too low error code -+ USER_numErrorCodes=106 //!< the number of user error codes -+ } USER_ErrorCode_e; -+ -+ -+ //! \brief Defines a structure for the user parameters -+ //! -+ typedef struct _USER_Params_ -+ { -+ float_t iqFullScaleCurrent_A; //!< Defines the full scale current for the IQ variables, A -+ float_t iqFullScaleVoltage_V; //!< Defines the full scale voltage for the IQ variable, V -+ float_t iqFullScaleFreq_Hz; //!< Defines the full scale frequency for IQ variable, Hz -+ -+ uint_least16_t numIsrTicksPerCtrlTick; //!< Defines the number of Interrupt Service Routine (ISR) clock ticks per controller clock tick -+ uint_least16_t numCtrlTicksPerCurrentTick; //!< Defines the number of controller clock ticks per current controller clock tick -+ uint_least16_t numCtrlTicksPerEstTick; //!< Defines the number of controller clock ticks per estimator clock tick -+ uint_least16_t numCtrlTicksPerSpeedTick; //!< Defines the number of controller clock ticks per speed controller clock tick -+ uint_least16_t numCtrlTicksPerTrajTick; //!< Defines the number of controller clock ticks per trajectory clock tick -+ uint_least8_t numCurrentSensors; //!< Defines the number of current sensors -+ uint_least8_t numVoltageSensors; //!< Defines the number of voltage sensors -+ -+ float_t offsetPole_rps; //!< Defines the pole location for the voltage and current offset estimation, rad/s -+ float_t fluxPole_rps; //!< Defines the pole location for the flux estimation, rad/s -+ float_t zeroSpeedLimit; //!< Defines the low speed limit for the flux integrator, pu -+ float_t forceAngleFreq_Hz; //!< Defines the force angle frequency, Hz -+ float_t maxAccel_Hzps; //!< Defines the maximum acceleration for the speed profiles, Hz/s -+ float_t maxAccel_est_Hzps; //!< Defines the maximum acceleration for the estimation speed profiles, Hz/s -+ float_t directionPole_rps; //!< Defines the pole location for the direction filter, rad/s -+ float_t speedPole_rps; //!< Defines the pole location for the speed control filter, rad/s -+ float_t dcBusPole_rps; //!< Defines the pole location for the DC bus filter, rad/s -+ float_t fluxFraction; //!< Defines the flux fraction for Id rated current estimation -+ float_t indEst_speedMaxFraction; //!< Defines the fraction of SpeedMax to use during inductance estimation -+ float_t powerWarpGain; //!< Defines the PowerWarp gain for computing Id reference -+ -+ uint_least16_t systemFreq_MHz; //!< Defines the system clock frequency, MHz -+ -+ float_t pwmPeriod_usec; //!< Defines the Pulse Width Modulation (PWM) period, usec -+ float_t voltage_sf; //!< Defines the voltage scale factor for the system -+ float_t current_sf; //!< Defines the current scale factor for the system -+ float_t voltageFilterPole_rps; //!< Defines the analog voltage filter pole location, rad/s -+ float_t maxVsMag_pu; //!< Defines the maximum voltage magnitude, pu -+ float_t estKappa; //!< Defines the convergence factor for the estimator -+ -+ MOTOR_Type_e motor_type; //!< Defines the motor type -+ uint_least16_t motor_numPolePairs; //!< Defines the number of pole pairs for the motor -+ -+ float_t motor_ratedFlux; //!< Defines the rated flux of the motor, V/Hz -+ float_t motor_Rr; //!< Defines the rotor resistance, ohm -+ float_t motor_Rs; //!< Defines the stator resistance, ohm -+ float_t motor_Ls_d; //!< Defines the direct stator inductance, H -+ float_t motor_Ls_q; //!< Defines the quadrature stator inductance, H -+ float_t maxCurrent; //!< Defines the maximum current value, A -+ float_t maxCurrent_resEst; //!< Defines the maximum current value for resistance estimation, A -+ float_t maxCurrent_indEst; //!< Defines the maximum current value for inductance estimation, A -+ float_t maxCurrentSlope; //!< Defines the maximum current slope for Id current trajectory -+ float_t maxCurrentSlope_powerWarp; //!< Defines the maximum current slope for Id current trajectory during PowerWarp -+ float_t IdRated; //!< Defines the Id rated current value, A -+ float_t IdRatedFraction_indEst; //!< Defines the fraction of Id rated current to use during inductance estimation -+ float_t IdRatedFraction_ratedFlux; //!< Defines the fraction of Id rated current to use during rated flux estimation -+ float_t IdRated_delta; //!< Defines the Id rated delta current value, A -+ float_t fluxEstFreq_Hz; //!< Defines the flux estimation frequency, Hz -+ -+ uint_least32_t ctrlWaitTime[CTRL_numStates]; //!< Defines the wait times for each controller state, estimator ticks -+ uint_least32_t estWaitTime[EST_numStates]; //!< Defines the wait times for each estimator state, estimator ticks -+ uint_least32_t FluxWaitTime[EST_Flux_numStates]; //!< Defines the wait times for each Ls estimator, estimator ticks -+ uint_least32_t LsWaitTime[EST_Ls_numStates]; //!< Defines the wait times for each Ls estimator, estimator ticks -+ uint_least32_t RsWaitTime[EST_Rs_numStates]; //!< Defines the wait times for each Rs estimator, estimator ticks -+ uint_least32_t ctrlFreq_Hz; //!< Defines the controller frequency, Hz -+ uint_least32_t estFreq_Hz; //!< Defines the estimator frequency, Hz -+ uint_least32_t RoverL_estFreq_Hz; //!< Defines the R/L estimation frequency, Hz -+ uint_least32_t trajFreq_Hz; //!< Defines the trajectory frequency, Hz -+ -+ float_t ctrlPeriod_sec; //!< Defines the controller execution period, sec -+ -+ float_t maxNegativeIdCurrent_a; //!< Defines the maximum negative current that the Id PID is allowed to go to, A -+ -+ USER_ErrorCode_e errorCode; -+ -+ uint_least16_t numPwmTicksPerIsrTick; //!< Defines the number of PWM clock ticks per -+ //!< Interrupt Service Routine (ISR) clock ticks -+ } USER_Params; -+ -+ // ************************************************************************** -+ // the functions -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _USERPARAMS_H_ definition -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c 2017-07-06 09:48:23.450007200 +0200 -*************** -*** 0 **** ---- 1,1820 ---- -+ /* --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/boards/drv8301kit_revD/f28x/f2806xF/src/hal.c -+ //! \brief Contains the various functions related to the HAL object (everything outside the CTRL system) -+ //! -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // drivers -+ -+ // modules -+ #include "sw/modules/spiCTRL/src/32b/spiCTRL.h" -+ -+ // platforms -+ #include "hal.h" -+ #include "user.h" -+ #include "hal_obj.h" -+ -+ #ifdef FLASH -+ #pragma CODE_SECTION(HAL_setupFlash,"ramfuncs"); -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ HAL_Obj hal; -+ -+ float dcBusCurrentOffset = 0.0; -+ -+ bool dcBusCurrentOffsetCalibrationDone = false; -+ -+ // ************************************************************************** -+ // the functions -+ -+ void HAL_cal(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable the ADC clock -+ CLK_enableAdcClock(obj->clkHandle); -+ -+ -+ // Run the Device_cal() function -+ // This function copies the ADC and oscillator calibration values from TI reserved -+ // OTP into the appropriate trim registers -+ // This boot ROM automatically calls this function to calibrate the interal -+ // oscillators and ADC with device specific calibration data. -+ // If the boot ROM is bypassed by Code Composer Studio during the development process, -+ // then the calibration must be initialized by the application -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ (*Device_cal)(); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ // run offsets calibration in user's memory -+ HAL_AdcOffsetSelfCal(handle); -+ -+ // run oscillator compensation -+ HAL_OscTempComp(handle); -+ -+ // disable the ADC clock -+ CLK_disableAdcClock(obj->clkHandle); -+ -+ return; -+ } // end of HAL_cal() function -+ -+ -+ void HAL_OscTempComp(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t Temperature; -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ // enable non-overlap mode -+ ADC_enableNoOverlapMode(obj->adcHandle); -+ -+ // connect channel A5 internally to the temperature sensor -+ ADC_setTempSensorSrc(obj->adcHandle, ADC_TempSensorSrc_Int); -+ -+ // set SOC0 channel select to ADCINA5 -+ ADC_setSocChanNumber(obj->adcHandle, ADC_SocNumber_0, ADC_SocChanNumber_A5); -+ -+ // set SOC0 acquisition period to 26 ADCCLK -+ ADC_setSocSampleDelay(obj->adcHandle, ADC_SocNumber_0, ADC_SocSampleDelay_64_cycles); -+ -+ // connect ADCINT1 to EOC0 -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_1, ADC_IntSrc_EOC0); -+ -+ // clear ADCINT1 flag -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ // enable ADCINT1 -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_1); -+ -+ // force start of conversion on SOC0 -+ ADC_setSocFrc(obj->adcHandle, ADC_SocFrc_0); -+ -+ // wait for end of conversion -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_1) == 0){} -+ -+ // clear ADCINT1 flag -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ Temperature = ADC_readResult(obj->adcHandle, ADC_ResultNumber_0); -+ -+ HAL_osc1Comp(handle, Temperature); -+ -+ HAL_osc2Comp(handle, Temperature); -+ -+ return; -+ } // end of HAL_OscTempComp() function -+ -+ -+ void HAL_osc1Comp(HAL_Handle handle, const int16_t sensorSample) -+ { -+ int16_t compOscFineTrim; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ compOscFineTrim = ((sensorSample - getRefTempOffset())*(int32_t)getOsc1FineTrimSlope() -+ + OSC_POSTRIM_OFF + FP_ROUND )/FP_SCALE + getOsc1FineTrimOffset() - OSC_POSTRIM; -+ -+ if(compOscFineTrim > 31) -+ { -+ compOscFineTrim = 31; -+ } -+ else if(compOscFineTrim < -31) -+ { -+ compOscFineTrim = -31; -+ } -+ -+ OSC_setTrim(obj->oscHandle, OSC_Number_1, HAL_getOscTrimValue(getOsc1CoarseTrim(), compOscFineTrim)); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_osc1Comp() function -+ -+ -+ void HAL_osc2Comp(HAL_Handle handle, const int16_t sensorSample) -+ { -+ int16_t compOscFineTrim; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ compOscFineTrim = ((sensorSample - getRefTempOffset())*(int32_t)getOsc2FineTrimSlope() -+ + OSC_POSTRIM_OFF + FP_ROUND )/FP_SCALE + getOsc2FineTrimOffset() - OSC_POSTRIM; -+ -+ if(compOscFineTrim > 31) -+ { -+ compOscFineTrim = 31; -+ } -+ else if(compOscFineTrim < -31) -+ { -+ compOscFineTrim = -31; -+ } -+ -+ OSC_setTrim(obj->oscHandle, OSC_Number_2, HAL_getOscTrimValue(getOsc2CoarseTrim(), compOscFineTrim)); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_osc2Comp() function -+ -+ -+ uint16_t HAL_getOscTrimValue(int16_t coarse, int16_t fine) -+ { -+ uint16_t regValue = 0; -+ -+ if(fine < 0) -+ { -+ regValue = ((-fine) | 0x20) << 9; -+ } -+ else -+ { -+ regValue = fine << 9; -+ } -+ -+ if(coarse < 0) -+ { -+ regValue |= ((-coarse) | 0x80); -+ } -+ else -+ { -+ regValue |= coarse; -+ } -+ -+ return regValue; -+ } // end of HAL_getOscTrimValue() function -+ -+ -+ void HAL_AdcOffsetSelfCal(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t AdcConvMean; -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ //Select VREFLO internal connection on B5 -+ ADC_enableVoltRefLoConv(obj->adcHandle); -+ -+ //Select channel B5 for all SOC -+ HAL_AdcCalChanSelect(handle, ADC_SocChanNumber_B5); -+ -+ //Apply artificial offset (+80) to account for a negative offset that may reside in the ADC core -+ ADC_setOffTrim(obj->adcHandle, 80); -+ -+ //Capture ADC conversion on VREFLO -+ AdcConvMean = HAL_AdcCalConversion(handle); -+ -+ //Set offtrim register with new value (i.e remove artical offset (+80) and create a two's compliment of the offset error) -+ ADC_setOffTrim(obj->adcHandle, 80 - AdcConvMean); -+ -+ //Select external ADCIN5 input pin on B5 -+ ADC_disableVoltRefLoConv(obj->adcHandle); -+ -+ return; -+ } // end of HAL_AdcOffsetSelfCal() function -+ -+ -+ void HAL_AdcCalChanSelect(HAL_Handle handle, const ADC_SocChanNumber_e chanNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_0,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_1,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_2,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_3,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_4,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_5,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_6,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_7,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_8,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_9,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_10,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_11,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_12,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_13,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_14,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_15,chanNumber); -+ -+ return; -+ } // end of HAL_AdcCalChanSelect() function -+ -+ -+ uint16_t HAL_AdcCalConversion(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t index, SampleSize, Mean; -+ uint32_t Sum; -+ ADC_SocSampleDelay_e ACQPS_Value; -+ -+ index = 0; //initialize index to 0 -+ SampleSize = 256; //set sample size to 256 (**NOTE: Sample size must be multiples of 2^x where is an integer >= 4) -+ Sum = 0; //set sum to 0 -+ Mean = 999; //initialize mean to known value -+ -+ //Set the ADC sample window to the desired value (Sample window = ACQPS + 1) -+ ACQPS_Value = ADC_SocSampleDelay_7_cycles; -+ -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_0,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_1,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_2,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_3,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_4,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_5,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_6,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_7,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_8,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_9,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_10,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_11,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_12,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_13,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_14,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_15,ACQPS_Value); -+ -+ // Enabled ADCINT1 and ADCINT2 -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_1); -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_2); -+ -+ // Disable continuous sampling for ADCINT1 and ADCINT2 -+ ADC_setIntMode(obj->adcHandle, ADC_IntNumber_1, ADC_IntMode_EOC); -+ ADC_setIntMode(obj->adcHandle, ADC_IntNumber_2, ADC_IntMode_EOC); -+ -+ //ADCINTs trigger at end of conversion -+ ADC_setIntPulseGenMode(obj->adcHandle, ADC_IntPulseGenMode_Prior); -+ -+ // Setup ADCINT1 and ADCINT2 trigger source -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_1, ADC_IntSrc_EOC6); -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_2, ADC_IntSrc_EOC14); -+ -+ // Setup each SOC's ADCINT trigger source -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_0, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_1, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_2, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_3, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_4, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_5, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_6, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_7, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_8, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_9, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_10, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_11, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_12, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_13, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_14, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_15, ADC_Int1TriggersSOC); -+ -+ // Delay before converting ADC channels -+ usDelay(ADC_DELAY_usec); -+ -+ ADC_setSocFrcWord(obj->adcHandle, 0x00FF); -+ -+ while( index < SampleSize ) -+ { -+ //Wait for ADCINT1 to trigger, then add ADCRESULT0-7 registers to sum -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_1) == 0){} -+ -+ //Must clear ADCINT1 flag since INT1CONT = 0 -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_0); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_1); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_2); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_3); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_4); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_5); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_6); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_7); -+ -+ //Wait for ADCINT2 to trigger, then add ADCRESULT8-15 registers to sum -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_2) == 0){} -+ -+ //Must clear ADCINT2 flag since INT2CONT = 0 -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_2); -+ -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_8); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_9); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_10); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_11); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_12); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_13); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_14); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_15); -+ -+ index+=16; -+ -+ } // end data collection -+ -+ //Disable ADCINT1 and ADCINT2 to STOP the ping-pong sampling -+ ADC_disableInt(obj->adcHandle, ADC_IntNumber_1); -+ ADC_disableInt(obj->adcHandle, ADC_IntNumber_2); -+ -+ //Calculate average ADC sample value -+ Mean = Sum / SampleSize; -+ -+ // Clear start of conversion trigger -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_0, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_1, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_2, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_3, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_4, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_5, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_6, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_7, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_8, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_9, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_10, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_11, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_12, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_13, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_14, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_15, ADC_NoIntTriggersSOC); -+ -+ //return the average -+ return(Mean); -+ } // end of HAL_AdcCalConversion() function -+ -+ -+ void HAL_disableWdog(HAL_Handle halHandle) -+ { -+ HAL_Obj *hal = (HAL_Obj *)halHandle; -+ -+ -+ WDOG_disable(hal->wdogHandle); -+ -+ -+ return; -+ } // end of HAL_disableWdog() function -+ -+ -+ void HAL_disableGlobalInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_disableGlobalInts(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_disableGlobalInts() function -+ -+ -+ void HAL_enableAdcInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable the PIE interrupts associated with the ADC interrupts -+ PIE_enableAdcInt(obj->pieHandle,ADC_IntNumber_1); -+ -+ -+ // enable the ADC interrupts -+ ADC_enableInt(obj->adcHandle,ADC_IntNumber_1); -+ -+ -+ // enable the cpu interrupt for ADC interrupts -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_10); -+ -+ return; -+ } // end of HAL_enableAdcInts() function -+ -+ -+ void HAL_enableDebugInt(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_enableDebugInt(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_enableDebugInt() function -+ -+ -+ void HAL_enableGlobalInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_enableGlobalInts(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_enableGlobalInts() function -+ -+ -+ void HAL_enablePwmInt(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ PIE_enablePwmInt(obj->pieHandle,PWM_Number_4); -+ -+ // enable the interrupt -+ PWM_enableInt(obj->pwmHandle[0]); -+ -+ -+ // enable the cpu interrupt for EPWMx_INT -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_3); -+ -+ return; -+ } // end of HAL_enablePwmInt() function -+ -+ -+ void HAL_enableTimer0Int(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_enableTimer0Int(obj->pieHandle); -+ -+ -+ // enable the interrupt -+ TIMER_enableInt(obj->timerHandle[0]); -+ -+ -+ // enable the cpu interrupt for TINT0 -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_1); -+ -+ return; -+ } // end of HAL_enablePwmInt() function -+ -+ -+ void HAL_setupFaults(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint_least8_t cnt; -+ -+ -+ // Configure Trip Mechanism for the Motor control software -+ // -Cycle by cycle trip on CPU halt -+ // -One shot fault trip zone -+ // These trips need to be repeated for EPWM1 ,2 & 3 -+ for(cnt=0;cnt<3;cnt++) -+ { -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ6_NOT); -+ -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ3_NOT); -+ -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ2_NOT); -+ -+ // What do we want the OST/CBC events to do? -+ // TZA events can force EPWMxA -+ // TZB events can force EPWMxB -+ -+ PWM_setTripZoneState_TZA(obj->pwmHandle[cnt],PWM_TripZoneState_EPWM_Low); -+ PWM_setTripZoneState_TZB(obj->pwmHandle[cnt],PWM_TripZoneState_EPWM_Low); -+ } -+ -+ return; -+ } // end of HAL_setupFaults() function -+ -+ -+ HAL_Handle HAL_init(void *pMemory,const size_t numBytes) -+ { -+ uint_least8_t cnt; -+ HAL_Handle handle; -+ HAL_Obj *obj; -+ -+ -+ if(numBytes < sizeof(HAL_Obj)) -+ return((HAL_Handle)NULL); -+ -+ -+ // assign the handle -+ handle = (HAL_Handle)pMemory; -+ -+ -+ // assign the object -+ obj = (HAL_Obj *)handle; -+ -+ -+ // initialize the watchdog driver -+ obj->wdogHandle = WDOG_init((void *)WDOG_BASE_ADDR,sizeof(WDOG_Obj)); -+ -+ -+ // disable watchdog -+ HAL_disableWdog(handle); -+ -+ -+ // initialize the ADC -+ obj->adcHandle = ADC_init((void *)ADC_BASE_ADDR,sizeof(ADC_Obj)); -+ -+ -+ // initialize the clock handle -+ obj->clkHandle = CLK_init((void *)CLK_BASE_ADDR,sizeof(CLK_Obj)); -+ -+ -+ // initialize the CPU handle -+ obj->cpuHandle = CPU_init(&cpu,sizeof(cpu)); -+ -+ -+ // initialize the FLASH handle -+ obj->flashHandle = FLASH_init((void *)FLASH_BASE_ADDR,sizeof(FLASH_Obj)); -+ -+ -+ // initialize the GPIO handle -+ obj->gpioHandle = GPIO_init((void *)GPIO_BASE_ADDR,sizeof(GPIO_Obj)); -+ -+ -+ // initialize the current offset estimator handles -+ for(cnt=0;cntoffsetHandle_I[cnt] = OFFSET_init(&obj->offset_I[cnt],sizeof(obj->offset_I[cnt])); -+ } -+ -+ -+ // initialize the voltage offset estimator handles -+ for(cnt=0;cntoffsetHandle_V[cnt] = OFFSET_init(&obj->offset_V[cnt],sizeof(obj->offset_V[cnt])); -+ } -+ -+ -+ // initialize the oscillator handle -+ obj->oscHandle = OSC_init((void *)OSC_BASE_ADDR,sizeof(OSC_Obj)); -+ -+ -+ // initialize the PIE handle -+ obj->pieHandle = PIE_init((void *)PIE_BASE_ADDR,sizeof(PIE_Obj)); -+ -+ -+ // initialize the PLL handle -+ obj->pllHandle = PLL_init((void *)PLL_BASE_ADDR,sizeof(PLL_Obj)); -+ -+ -+ // initialize the SPI handles -+ obj->spiAHandle = SPI_init((void *)SPIA_BASE_ADDR,sizeof(SPI_Obj)); -+ obj->spiBHandle = SPI_init((void *)SPIB_BASE_ADDR,sizeof(SPI_Obj)); -+ -+ -+ // initialize PWM handles -+ obj->pwmHandle[0] = PWM_init((void *)PWM_ePWM4_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[1] = PWM_init((void *)PWM_ePWM5_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[2] = PWM_init((void *)PWM_ePWM6_BASE_ADDR,sizeof(PWM_Obj)); -+ -+ -+ // initialize PWM DAC handles -+ obj->pwmDacHandle[0] = PWMDAC_init((void *)PWM_ePWM7_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmDacHandle[1] = PWMDAC_init((void *)PWM_ePWM8_BASE_ADDR,sizeof(PWM_Obj)); -+ -+ -+ // initialize power handle -+ obj->pwrHandle = PWR_init((void *)PWR_BASE_ADDR,sizeof(PWR_Obj)); -+ -+ -+ // initialize timer handles -+ obj->timerHandle[0] = TIMER_init((void *)TIMER0_BASE_ADDR,sizeof(TIMER_Obj)); -+ obj->timerHandle[1] = TIMER_init((void *)TIMER1_BASE_ADDR,sizeof(TIMER_Obj)); -+ obj->timerHandle[2] = TIMER_init((void *)TIMER2_BASE_ADDR,sizeof(TIMER_Obj)); -+ -+ -+ #ifdef QEP -+ // initialize QEP driver -+ obj->qepHandle[0] = QEP_init((void*)QEP1_BASE_ADDR,sizeof(QEP_Obj)); -+ obj->qepHandle[1] = QEP_init((void*)QEP2_BASE_ADDR,sizeof(QEP_Obj)); -+ #endif -+ -+ // Custom Module initialization -+ // do McBSPA init -+ obj->mcBSPAhandle = MCBSP_init((void*)MCBSPA_BASE_ADDR, sizeof(MCBSP_Obj)); -+ -+ -+ // do DMA init -+ obj->DMAhandle = DMA_init((void*)DMA_BASE_ADDR, sizeof(DMA_Obj)); -+ -+ -+ return(handle); -+ } // end of HAL_init() function -+ -+ -+ void HAL_setParams(HAL_Handle handle,const USER_Params *pUserParams) -+ { -+ uint_least8_t cnt; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ _iq beta_lp_pu = _IQ(pUserParams->offsetPole_rps/(float_t)pUserParams->ctrlFreq_Hz); -+ -+ -+ HAL_setNumCurrentSensors(handle,pUserParams->numCurrentSensors); -+ HAL_setNumVoltageSensors(handle,pUserParams->numVoltageSensors); -+ -+ -+ for(cnt=0;cntcpuHandle); -+ -+ -+ // disable cpu interrupts -+ CPU_disableInts(obj->cpuHandle); -+ -+ -+ // clear cpu interrupt flags -+ CPU_clearIntFlags(obj->cpuHandle); -+ -+ -+ // setup the clocks -+ HAL_setupClks(handle); -+ -+ -+ // Setup the PLL -+ HAL_setupPll(handle,PLL_ClkFreq_90_MHz); -+ -+ -+ // setup the PIE -+ HAL_setupPie(handle); -+ -+ -+ // run the device calibration -+ HAL_cal(handle); -+ -+ -+ // setup the peripheral clocks -+ HAL_setupPeripheralClks(handle); -+ -+ -+ // setup the GPIOs -+ HAL_setupGpios(handle); -+ -+ -+ // setup the flash -+ HAL_setupFlash(handle); -+ -+ -+ // setup the ADCs -+ HAL_setupAdcs(handle); -+ -+ -+ // setup the PWMs -+ HAL_setupPwms(handle, -+ (float_t)pUserParams->systemFreq_MHz, -+ pUserParams->pwmPeriod_usec, -+ USER_NUM_PWM_TICKS_PER_ISR_TICK); -+ -+ #ifdef QEP -+ // setup the QEP -+ HAL_setupQEP(handle,HAL_Qep_QEP1); -+ HAL_setupQEP(handle,HAL_Qep_QEP2); -+ #endif -+ -+ // setup the spiA -+ HAL_setupSpiA(handle); -+ -+ -+ // setup the spiB -+ HAL_setupSpiB(handle); -+ -+ -+ // setup the PWM DACs -+ HAL_setupPwmDacs(handle); -+ -+ -+ // setup the timers -+ HAL_setupTimers(handle, -+ (float_t)pUserParams->systemFreq_MHz); -+ -+ -+ /* added to start SPI-DMA functionality */ -+ -+ // setup the DMA-Controller -+ HAL_setupDMA(handle); -+ -+ // setup the McBSP-Interface -+ HAL_setupMcBSPA(handle); -+ -+ -+ // set the default current bias -+ { -+ uint_least8_t cnt; -+ _iq bias = _IQ12mpy(ADC_dataBias,_IQ(pUserParams->current_sf)); -+ -+ for(cnt=0;cntcurrent_sf); -+ -+ HAL_setCurrentScaleFactor(handle,current_sf); -+ } -+ -+ -+ // set the default voltage bias -+ { -+ uint_least8_t cnt; -+ _iq bias = _IQ(0.0); -+ -+ for(cnt=0;cntvoltage_sf); -+ -+ HAL_setVoltageScaleFactor(handle,voltage_sf); -+ } -+ -+ // FIKAT-specific: -+ // set voltage scale factor for the 6 external analog inputs -+ { -+ _iq analogVoltageSF = _IQ(pUserParams->analogIn_voltage_sf); -+ HAL_setAnalogInputVoltageScaleFactor(handle, analogVoltageSF); -+ } -+ return; -+ } // end of HAL_setParams() function -+ -+ -+ void HAL_setupAdcs(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ -+ // set the ADC interrupt pulse generation to prior -+ ADC_setIntPulseGenMode(obj->adcHandle,ADC_IntPulseGenMode_Prior); -+ -+ -+ // set the temperature sensor source to external -+ ADC_setTempSensorSrc(obj->adcHandle,ADC_TempSensorSrc_Ext); -+ -+ -+ // configure the interrupt sources -+ ADC_disableInt(obj->adcHandle,ADC_IntNumber_1); -+ ADC_setIntMode(obj->adcHandle,ADC_IntNumber_1,ADC_IntMode_ClearFlag); -+ ADC_setIntSrc(obj->adcHandle,ADC_IntNumber_1,ADC_IntSrc_EOC7); -+ -+ //configure the SOCs for FIKAT -+ // EXT IA-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_0,ADC_SocChanNumber_A0); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_0,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_0,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IA-FB -+ // Duplicate conversion due to ADC Initial Conversion bug (SPRZ342) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_1,ADC_SocChanNumber_A0); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_1,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_1,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IB-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_2,ADC_SocChanNumber_A1); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_2,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_2,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IC-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_3,ADC_SocChanNumber_A2); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_3,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_3,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb1 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_4,ADC_SocChanNumber_A4); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_4,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_4,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb2 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_5,ADC_SocChanNumber_A5); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_5,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_5,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb3 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_6,ADC_SocChanNumber_A6); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_6,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_6,ADC_SocSampleDelay_9_cycles); -+ -+ // VDCBUS -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_7,ADC_SocChanNumber_A7); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_7,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_7,ADC_SocSampleDelay_9_cycles); -+ -+ // hier ein extra des FIKAT-Boards: Gesamtstrommessung an ADC-Kanal ADCINA3 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_8,ADC_SocChanNumber_A3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_8,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_8,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Analogeingang ADC24_0 (ADCINB0) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_9,ADC_SocChanNumber_B0); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_9,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_9,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Analogeingang ADC24_1 (ADCINB1) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_10,ADC_SocChanNumber_B1); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_10,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_10,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Analogeingang ADC24_2 (ADCINB2) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_11,ADC_SocChanNumber_B2); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_11,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_11,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Analogeingang ADC24_3 (ADCINB3) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_12,ADC_SocChanNumber_B3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_12,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_12,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Analogeingang ADC24_4 (ADCINB4) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_13,ADC_SocChanNumber_B4); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_13,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_13,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Analogeingang ADC24_5 (ADCINB5) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_14,ADC_SocChanNumber_B5); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_14,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_14,ADC_SocSampleDelay_9_cycles); -+ -+ // FIKAT-Extra : Temperatursensor LM61 an ADCINB6 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_15,ADC_SocChanNumber_B6); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_15,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_15,ADC_SocSampleDelay_9_cycles); -+ -+ return; -+ } // end of HAL_setupAdcs() function -+ -+ -+ void HAL_setupClks(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable internal oscillator 1 -+ CLK_enableOsc1(obj->clkHandle); -+ -+ // set the oscillator source -+ CLK_setOscSrc(obj->clkHandle,CLK_OscSrc_Internal); -+ -+ // disable the external clock in -+ CLK_disableClkIn(obj->clkHandle); -+ -+ // disable the crystal oscillator -+ CLK_disableCrystalOsc(obj->clkHandle); -+ -+ // disable oscillator 2 -+ CLK_disableOsc2(obj->clkHandle); -+ -+ // set the low speed clock prescaler -+ CLK_setLowSpdPreScaler(obj->clkHandle,CLK_LowSpdPreScaler_SysClkOut_by_1); -+ -+ // set the clock out prescaler -+ CLK_setClkOutPreScaler(obj->clkHandle,CLK_ClkOutPreScaler_SysClkOut_by_1); -+ -+ return; -+ } // end of HAL_setupClks() function -+ -+ -+ void HAL_setupFlash(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ FLASH_enablePipelineMode(obj->flashHandle); -+ -+ FLASH_setNumPagedReadWaitStates(obj->flashHandle,FLASH_NumPagedWaitStates_3); -+ -+ FLASH_setNumRandomReadWaitStates(obj->flashHandle,FLASH_NumRandomWaitStates_3); -+ -+ FLASH_setOtpWaitStates(obj->flashHandle,FLASH_NumOtpWaitStates_5); -+ -+ FLASH_setStandbyWaitCount(obj->flashHandle,FLASH_STANDBY_WAIT_COUNT_DEFAULT); -+ -+ FLASH_setActiveWaitCount(obj->flashHandle,FLASH_ACTIVE_WAIT_COUNT_DEFAULT); -+ -+ return; -+ } // HAL_setupFlash() function -+ -+ -+ void HAL_setupGpios(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // Fikat Digital Input 0 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_0,GPIO_0_Mode_GeneralPurpose); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_0,GPIO_Direction_Input); -+ -+ // Fikat Digital Input 1 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_1,GPIO_1_Mode_GeneralPurpose); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_1,GPIO_Direction_Input); -+ -+ // Fikat Digital Input 2 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_2,GPIO_2_Mode_GeneralPurpose); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_2,GPIO_Direction_Input); -+ -+ // Fikat Digital Input 3 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_3,GPIO_3_Mode_GeneralPurpose); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_3,GPIO_Direction_Input); -+ -+ // Fikat Digital Output 0 -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_4, GPIO_4_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_4); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_4,GPIO_Direction_Output); -+ -+ // Fikat Digital Output 1 -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_5, GPIO_5_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_5); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_5,GPIO_Direction_Output); -+ -+ // PWM4A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_6,GPIO_6_Mode_EPWM4A); -+ -+ // PWM4B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_7,GPIO_7_Mode_EPWM4B); -+ -+ // PWM5A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_8,GPIO_8_Mode_EPWM5A); -+ -+ // PWM5B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_9,GPIO_9_Mode_EPWM5B); -+ -+ // PWM6A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_10,GPIO_10_Mode_EPWM6A); -+ -+ // PWM6B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_11,GPIO_11_Mode_EPWM6B); -+ -+ // Fikat Digital Output 6 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_12,GPIO_12_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_12); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_12,GPIO_Direction_Output); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_13,GPIO_13_Mode_GeneralPurpose); -+ -+ // SPIB CLK -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_14,GPIO_14_Mode_SPICLKB); -+ -+ // UARTB RX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_15,GPIO_15_Mode_SCIRXDB); -+ -+ // Set Qualification Period for GPIO16-23, 22*2*(1/90MHz) = 0.48us -+ GPIO_setQualificationPeriod(obj->gpioHandle,GPIO_Number_16,22); -+ -+ // SPIA SIMO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_16,GPIO_16_Mode_SPISIMOA); -+ -+ // SPIA SOMI -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_17,GPIO_17_Mode_SPISOMIA); -+ -+ // SPIA CLK -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_18,GPIO_18_Mode_SPICLKA); -+ -+ // SPIA CS -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_19,GPIO_19_Mode_SPISTEA_NOT); -+ -+ #ifdef QEP -+ // EQEP1A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_20,GPIO_20_Mode_EQEP1A); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_20,GPIO_Qual_Sample_3); -+ -+ // EQEP1B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_21,GPIO_21_Mode_EQEP1B); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_21,GPIO_Qual_Sample_3); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_22,GPIO_22_Mode_GeneralPurpose); -+ -+ // EQEP1I -+ // GPIO_setMode(obj->gpioHandle,GPIO_Number_23,GPIO_23_Mode_EQEP1I); -+ // GPIO_setQualification(obj->gpioHandle,GPIO_Number_23,GPIO_Qual_Sample_3); -+ #else -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_20,GPIO_20_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_21,GPIO_21_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_22,GPIO_22_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_23,GPIO_23_Mode_GeneralPurpose); -+ #endif -+ -+ // SPIB SIMO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_24,GPIO_24_Mode_SPISIMOB); -+ -+ // SPIB SOMI -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_25,GPIO_25_Mode_SPISOMIB); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_26,GPIO_26_Mode_GeneralPurpose); -+ -+ // SPIB CS -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_27,GPIO_27_Mode_SPISTEB_NOT); -+ -+ // OCTWn -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_28,GPIO_28_Mode_TZ2_NOT); -+ -+ // FAULTn -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_29,GPIO_29_Mode_TZ3_NOT); -+ -+ // CAN RX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_30,GPIO_30_Mode_CANRXA); -+ -+ // CAN TX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_31,GPIO_31_Mode_CANTXA); -+ -+ // I2C Data -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_32,GPIO_32_Mode_SDAA); -+ -+ // I2C Clock -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_33,GPIO_33_Mode_SCLA); -+ -+ // LED D9 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_34,GPIO_34_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_34); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_34,GPIO_Direction_Output); -+ -+ // JTAG -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_35,GPIO_35_Mode_JTAG_TDI); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_36,GPIO_36_Mode_JTAG_TMS); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_37,GPIO_37_Mode_JTAG_TDO); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_38,GPIO_38_Mode_JTAG_TCK); -+ -+ // LED D10 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_39,GPIO_39_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_39); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_39,GPIO_Direction_Output); -+ -+ // Fikat - Digital Output (2) -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_40, GPIO_40_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_40); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_40,GPIO_Direction_Output); -+ -+ // Fikat - Digital Output (3) -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_41, GPIO_41_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_41); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_41,GPIO_Direction_Output); -+ -+ // Fikat - Digital Output (4) -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_42, GPIO_42_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_42); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_42,GPIO_Direction_Output); -+ -+ // Fikat - Digital Output (5) -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_43, GPIO_43_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_43); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_43,GPIO_Direction_Output); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_44,GPIO_44_Mode_GeneralPurpose); -+ -+ // Set Qualification Period for GPIO50-55, 22*2*(1/90MHz) = 0.48us -+ GPIO_setQualificationPeriod(obj->gpioHandle,GPIO_Number_50,22); -+ -+ // GPIO 50 = MDXA (FIKAT) -+ // GPIO_setMode(obj->gpioHandle,GPIO_Number_50,GPIO_50_Mode_GeneralPurpose); -+ -+ // GPIO 51 = MDRA (FIKAT) -+ // GPIO_setMode(obj->gpioHandle,GPIO_Number_51,GPIO_51_Mode_GeneralPurpose); -+ -+ // GPIO 52 = MCLKXA (FIKAT) -+ // GPIO_setMode(obj->gpioHandle,GPIO_Number_52,GPIO_52_Mode_GeneralPurpose); -+ -+ // GPIO 53 = MFSXA (FIKAT) -+ //GPIO_setMode(obj->gpioHandle,GPIO_Number_53,GPIO_53_Mode_GeneralPurpose); -+ -+ // Set Qualification Period for GPIO56-58, 22*2*(1/90MHz) = 0.48us -+ GPIO_setQualificationPeriod(obj->gpioHandle,GPIO_Number_56,22); -+ -+ #ifdef QEP -+ // EQEP2A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_54,GPIO_54_Mode_EQEP2A); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_54,GPIO_Qual_Sample_3); -+ -+ // EQEP2B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_55,GPIO_55_Mode_EQEP2B); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_55,GPIO_Qual_Sample_3); -+ -+ // EQEP2I -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_56,GPIO_56_Mode_EQEP2I); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_56,GPIO_Qual_Sample_3); -+ #else -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_54,GPIO_54_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_55,GPIO_55_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_56,GPIO_56_Mode_GeneralPurpose); -+ #endif -+ -+ // No Connection -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_57,GPIO_57_Mode_GeneralPurpose); -+ -+ // UARTB TX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_58,GPIO_58_Mode_SCITXDB); -+ -+ /* Eigenbau : Hier das McBSP-Interface GPIO-maessig definieren */ -+ //EALLOW; /* EALLOW und EDIS ist in allen GPIO_xyz-Funktionen enthalten */ -+ -+ /* Configure McBSP-A pins using GPIO regs*/ -+ // This specifies which of the possible GPIO pins will be McBSP functional pins. -+ /* GPIO_setMode() schreibt auf die GPAMUX2-Register */ -+ //GpioCtrlRegs.GPAMUX2.bit.GPIO20 = 2; // GPIO50 is MDXA pin -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_50, GPIO_50_Mode_MDXA); -+ //GpioCtrlRegs.GPAMUX2.bit.GPIO21 = 2; // GPIO51 is MDRA pin -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_51, GPIO_51_Mode_MDRA); -+ //GpioCtrlRegs.GPAMUX2.bit.GPIO23 = 2; // GPIO53 is MFSXA pin -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_53, GPIO_53_Mode_MFSXA); -+ //GpioCtrlRegs.GPBMUX2.bit.GPIO52 = 2; // GPIO52 is MCLKXA pin -+ GPIO_setMode(obj->gpioHandle, GPIO_Number_52, GPIO_52_Mode_MCLKXA); -+ -+ /* Set qualification for selected input pins to asynch only */ -+ // This will select asynch (no qualification) for the selected pins. -+ // Comment out other unwanted lines. -+ /* Ist GPIO20 (SIMO) Standardmaessig Output ? */ -+ //GpioCtrlRegs.GPAQSEL2.bit.GPIO21 = 3; // Asynch input GPIO51 (MDRA) -+ GPIO_setQualification(obj->gpioHandle, GPIO_Number_51, GPIO_Qual_ASync); -+ //GpioCtrlRegs.GPAQSEL2.bit.GPIO23 = 3; // Asynch input GPIO53 (MFSXA) -+ GPIO_setQualification(obj->gpioHandle, GPIO_Number_53, GPIO_Qual_ASync); -+ //GpioCtrlRegs.GPBQSEL2.bit.GPIO52 = 3; // Asynch input GPIO52 (MCLKXA) -+ GPIO_setQualification(obj->gpioHandle, GPIO_Number_52, GPIO_Qual_ASync); -+ //EDIS; -+ -+ return; -+ } // end of HAL_setupGpios() function -+ -+ -+ void HAL_setupPie(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_disable(obj->pieHandle); -+ -+ PIE_disableAllInts(obj->pieHandle); -+ -+ PIE_clearAllInts(obj->pieHandle); -+ -+ PIE_clearAllFlags(obj->pieHandle); -+ -+ PIE_setDefaultIntVectorTable(obj->pieHandle); -+ -+ PIE_enable(obj->pieHandle); -+ -+ return; -+ } // end of HAL_setupPie() function -+ -+ -+ void HAL_setupPeripheralClks(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CLK_enableAdcClock(obj->clkHandle); -+ -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_1); -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_2); -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_3); -+ -+ CLK_disableEcap1Clock(obj->clkHandle); -+ -+ CLK_enableEcanaClock(obj->clkHandle); -+ -+ #ifdef QEP -+ CLK_enableEqep1Clock(obj->clkHandle); -+ CLK_enableEqep2Clock(obj->clkHandle); -+ #endif -+ -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_1); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_2); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_3); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_4); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_5); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_6); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_7); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_8); -+ -+ CLK_disableHrPwmClock(obj->clkHandle); -+ -+ CLK_enableI2cClock(obj->clkHandle); -+ -+ CLK_disableLinAClock(obj->clkHandle); -+ -+ CLK_disableClaClock(obj->clkHandle); -+ -+ CLK_disableSciaClock(obj->clkHandle); -+ CLK_enableScibClock(obj->clkHandle); -+ -+ CLK_enableSpiaClock(obj->clkHandle); -+ CLK_enableSpibClock(obj->clkHandle); -+ -+ CLK_enableTbClockSync(obj->clkHandle); -+ -+ /* enable clocks for DMA and McBSPA */ -+ CLK_enableDMAClock(obj->clkHandle); -+ CLK_enableMcBSPAClock(obj->clkHandle); -+ -+ -+ return; -+ } // end of HAL_setupPeripheralClks() function -+ -+ -+ void HAL_setupPll(HAL_Handle handle,const PLL_ClkFreq_e clkFreq) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // make sure PLL is not running in limp mode -+ if(PLL_getClkStatus(obj->pllHandle) != PLL_ClkStatus_Normal) -+ { -+ // reset the clock detect -+ PLL_resetClkDetect(obj->pllHandle); -+ -+ // ??????? -+ asm(" ESTOP0"); -+ } -+ -+ -+ // Divide Select must be ClkIn/4 before the clock rate can be changed -+ if(PLL_getDivideSelect(obj->pllHandle) != PLL_DivideSelect_ClkIn_by_4) -+ { -+ PLL_setDivideSelect(obj->pllHandle,PLL_DivideSelect_ClkIn_by_4); -+ } -+ -+ -+ if(PLL_getClkFreq(obj->pllHandle) != clkFreq) -+ { -+ // disable the clock detect -+ PLL_disableClkDetect(obj->pllHandle); -+ -+ // set the clock rate -+ PLL_setClkFreq(obj->pllHandle,clkFreq); -+ } -+ -+ -+ // wait until locked -+ while(PLL_getLockStatus(obj->pllHandle) != PLL_LockStatus_Done) {} -+ -+ -+ // enable the clock detect -+ PLL_enableClkDetect(obj->pllHandle); -+ -+ -+ // set divide select to ClkIn/2 to get desired clock rate -+ // NOTE: clock must be locked before setting this register -+ PLL_setDivideSelect(obj->pllHandle,PLL_DivideSelect_ClkIn_by_2); -+ -+ return; -+ } // end of HAL_setupPll() function -+ -+ -+ void HAL_setupPwms(HAL_Handle handle, -+ const float_t systemFreq_MHz, -+ const float_t pwmPeriod_usec, -+ const uint_least16_t numPwmTicksPerIsrTick) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t halfPeriod_cycles = (uint16_t)(systemFreq_MHz*pwmPeriod_usec) >> 1; -+ uint_least8_t cnt; -+ -+ -+ // turns off the outputs of the EPWM peripherals which will put the power switches -+ // into a high impedance state. -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ for(cnt=0;cnt<3;cnt++) -+ { -+ // setup the Time-Base Control Register (TBCTL) -+ PWM_setCounterMode(obj->pwmHandle[cnt],PWM_CounterMode_UpDown); -+ PWM_disableCounterLoad(obj->pwmHandle[cnt]); -+ PWM_setPeriodLoad(obj->pwmHandle[cnt],PWM_PeriodLoad_Immediate); -+ PWM_setSyncMode(obj->pwmHandle[cnt],PWM_SyncMode_EPWMxSYNC); -+ PWM_setHighSpeedClkDiv(obj->pwmHandle[cnt],PWM_HspClkDiv_by_1); -+ PWM_setClkDiv(obj->pwmHandle[cnt],PWM_ClkDiv_by_1); -+ PWM_setPhaseDir(obj->pwmHandle[cnt],PWM_PhaseDir_CountUp); -+ PWM_setRunMode(obj->pwmHandle[cnt],PWM_RunMode_FreeRun); -+ -+ // setup the Timer-Based Phase Register (TBPHS) -+ PWM_setPhase(obj->pwmHandle[cnt],0); -+ -+ // setup the Time-Base Counter Register (TBCTR) -+ PWM_setCount(obj->pwmHandle[cnt],0); -+ -+ // setup the Time-Base Period Register (TBPRD) -+ // set to zero initially -+ PWM_setPeriod(obj->pwmHandle[cnt],0); -+ -+ // setup the Counter-Compare Control Register (CMPCTL) -+ PWM_setLoadMode_CmpA(obj->pwmHandle[cnt],PWM_LoadMode_Zero); -+ PWM_setLoadMode_CmpB(obj->pwmHandle[cnt],PWM_LoadMode_Zero); -+ PWM_setShadowMode_CmpA(obj->pwmHandle[cnt],PWM_ShadowMode_Shadow); -+ PWM_setShadowMode_CmpB(obj->pwmHandle[cnt],PWM_ShadowMode_Immediate); -+ -+ // setup the Action-Qualifier Output A Register (AQCTLA) -+ PWM_setActionQual_CntUp_CmpA_PwmA(obj->pwmHandle[cnt],PWM_ActionQual_Set); -+ PWM_setActionQual_CntDown_CmpA_PwmA(obj->pwmHandle[cnt],PWM_ActionQual_Clear); -+ -+ // setup the Dead-Band Generator Control Register (DBCTL) -+ PWM_setDeadBandOutputMode(obj->pwmHandle[cnt],PWM_DeadBandOutputMode_EPWMxA_Rising_EPWMxB_Falling); -+ PWM_setDeadBandPolarity(obj->pwmHandle[cnt],PWM_DeadBandPolarity_EPWMxB_Inverted); -+ -+ // setup the Dead-Band Rising Edge Delay Register (DBRED) -+ PWM_setDeadBandRisingEdgeDelay(obj->pwmHandle[cnt],HAL_PWM_DBRED_CNT); -+ -+ // setup the Dead-Band Falling Edge Delay Register (DBFED) -+ PWM_setDeadBandFallingEdgeDelay(obj->pwmHandle[cnt],HAL_PWM_DBFED_CNT); -+ // setup the PWM-Chopper Control Register (PCCTL) -+ PWM_disableChopping(obj->pwmHandle[cnt]); -+ -+ // setup the Trip Zone Select Register (TZSEL) -+ PWM_disableTripZones(obj->pwmHandle[cnt]); -+ } -+ -+ -+ // setup the Event Trigger Selection Register (ETSEL) -+ PWM_disableInt(obj->pwmHandle[PWM_Number_1]); -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualZero); -+ PWM_enableSocAPulse(obj->pwmHandle[PWM_Number_1]); -+ -+ -+ // setup the Event Trigger Prescale Register (ETPS) -+ if(numPwmTicksPerIsrTick == 3) -+ { -+ PWM_setIntPeriod(obj->pwmHandle[PWM_Number_1],PWM_IntPeriod_ThirdEvent); -+ PWM_setSocAPeriod(obj->pwmHandle[PWM_Number_1],PWM_SocPeriod_ThirdEvent); -+ } -+ else if(numPwmTicksPerIsrTick == 2) -+ { -+ PWM_setIntPeriod(obj->pwmHandle[PWM_Number_1],PWM_IntPeriod_SecondEvent); -+ PWM_setSocAPeriod(obj->pwmHandle[PWM_Number_1],PWM_SocPeriod_SecondEvent); -+ } -+ else -+ { -+ PWM_setIntPeriod(obj->pwmHandle[PWM_Number_1],PWM_IntPeriod_FirstEvent); -+ PWM_setSocAPeriod(obj->pwmHandle[PWM_Number_1],PWM_SocPeriod_FirstEvent); -+ } -+ -+ -+ // setup the Event Trigger Clear Register (ETCLR) -+ PWM_clearIntFlag(obj->pwmHandle[PWM_Number_1]); -+ PWM_clearSocAFlag(obj->pwmHandle[PWM_Number_1]); -+ -+ // first step to synchronize the pwms -+ CLK_disableTbClockSync(obj->clkHandle); -+ -+ // since the PWM is configured as an up/down counter, the period register is set to one-half -+ // of the desired PWM period -+ PWM_setPeriod(obj->pwmHandle[PWM_Number_1],halfPeriod_cycles); -+ PWM_setPeriod(obj->pwmHandle[PWM_Number_2],halfPeriod_cycles); -+ PWM_setPeriod(obj->pwmHandle[PWM_Number_3],halfPeriod_cycles); -+ -+ // last step to synchronize the pwms -+ CLK_enableTbClockSync(obj->clkHandle); -+ -+ return; -+ } // end of HAL_setupPwms() function -+ -+ #ifdef QEP -+ void HAL_setupQEP(HAL_Handle handle,HAL_QepSelect_e qep) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // hold the counter in reset -+ QEP_reset_counter(obj->qepHandle[qep]); -+ -+ // set the QPOSINIT register -+ QEP_set_posn_init_count(obj->qepHandle[qep], 0); -+ -+ // disable all interrupts -+ QEP_disable_all_interrupts(obj->qepHandle[qep]); -+ -+ // clear the interrupt flags -+ QEP_clear_all_interrupt_flags(obj->qepHandle[qep]); -+ -+ // clear the position counter -+ QEP_clear_posn_counter(obj->qepHandle[qep]); -+ -+ // setup the max position -+ QEP_set_max_posn_count(obj->qepHandle[qep], (4*USER_MOTOR_ENCODER_LINES)-1); -+ -+ // setup the QDECCTL register -+ QEP_set_QEP_source(obj->qepHandle[qep], QEP_Qsrc_Quad_Count_Mode); -+ QEP_disable_sync_out(obj->qepHandle[qep]); -+ QEP_set_swap_quad_inputs(obj->qepHandle[qep], QEP_Swap_Not_Swapped); -+ QEP_disable_gate_index(obj->qepHandle[qep]); -+ QEP_set_ext_clock_rate(obj->qepHandle[qep], QEP_Xcr_2x_Res); -+ QEP_set_A_polarity(obj->qepHandle[qep], QEP_Qap_No_Effect); -+ QEP_set_B_polarity(obj->qepHandle[qep], QEP_Qbp_No_Effect); -+ QEP_set_index_polarity(obj->qepHandle[qep], QEP_Qip_No_Effect); -+ -+ // setup the QEPCTL register -+ QEP_set_emu_control(obj->qepHandle[qep], QEPCTL_Freesoft_Unaffected_Halt); -+ QEP_set_posn_count_reset_mode(obj->qepHandle[qep], QEPCTL_Pcrm_Max_Reset); -+ QEP_set_strobe_event_init(obj->qepHandle[qep], QEPCTL_Sei_Nothing); -+ QEP_set_index_event_init(obj->qepHandle[qep], QEPCTL_Iei_Nothing); -+ QEP_set_index_event_latch(obj->qepHandle[qep], QEPCTL_Iel_Rising_Edge); -+ QEP_set_soft_init(obj->qepHandle[qep], QEPCTL_Swi_Nothing); -+ QEP_disable_unit_timer(obj->qepHandle[qep]); -+ QEP_disable_watchdog(obj->qepHandle[qep]); -+ -+ // setup the QPOSCTL register -+ QEP_disable_posn_compare(obj->qepHandle[qep]); -+ -+ // setup the QCAPCTL register -+ QEP_disable_capture(obj->qepHandle[qep]); -+ -+ // renable the position counter -+ QEP_enable_counter(obj->qepHandle[qep]); -+ -+ -+ return; -+ } -+ #endif -+ -+ void HAL_setupSpiA(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ SPI_reset(obj->spiAHandle); -+ SPI_setMode(obj->spiAHandle,SPI_Mode_Master); -+ SPI_setClkPolarity(obj->spiAHandle,SPI_ClkPolarity_OutputRisingEdge_InputFallingEdge); -+ SPI_enableTx(obj->spiAHandle); -+ SPI_enableTxFifoEnh(obj->spiAHandle); -+ SPI_enableTxFifo(obj->spiAHandle); -+ SPI_setTxDelay(obj->spiAHandle,0x0018); -+ SPI_setBaudRate(obj->spiAHandle,(SPI_BaudRate_e)(0x000d)); -+ SPI_setCharLength(obj->spiAHandle,SPI_CharLength_16_Bits); -+ SPI_setSuspend(obj->spiAHandle,SPI_TxSuspend_free); -+ SPI_enable(obj->spiAHandle); -+ -+ return; -+ } // end of HAL_setupSpiA() function -+ -+ -+ void HAL_setupSpiB(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ SPI_reset(obj->spiBHandle); -+ SPI_setMode(obj->spiBHandle,SPI_Mode_Master); -+ SPI_setClkPolarity(obj->spiBHandle,SPI_ClkPolarity_OutputRisingEdge_InputFallingEdge); -+ SPI_enableTx(obj->spiBHandle); -+ SPI_enableTxFifoEnh(obj->spiBHandle); -+ SPI_enableTxFifo(obj->spiBHandle); -+ SPI_setTxDelay(obj->spiBHandle,0x0018); -+ SPI_setBaudRate(obj->spiBHandle,(SPI_BaudRate_e)(0x000d)); -+ SPI_setCharLength(obj->spiBHandle,SPI_CharLength_16_Bits); -+ SPI_setSuspend(obj->spiBHandle,SPI_TxSuspend_free); -+ SPI_enable(obj->spiBHandle); -+ -+ return; -+ } // end of HAL_setupSpiB() function -+ -+ -+ void HAL_setupPwmDacs(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t halfPeriod_cycles = 512; // 3000->10kHz, 1500->20kHz, 1000-> 30kHz, 500->60kHz -+ uint_least8_t cnt; -+ -+ -+ for(cnt=0;cnt<2;cnt++) -+ { -+ // initialize the Time-Base Control Register (TBCTL) -+ PWMDAC_setCounterMode(obj->pwmDacHandle[cnt],PWM_CounterMode_UpDown); -+ PWMDAC_disableCounterLoad(obj->pwmDacHandle[cnt]); -+ PWMDAC_setPeriodLoad(obj->pwmDacHandle[cnt],PWM_PeriodLoad_Immediate); -+ PWMDAC_setSyncMode(obj->pwmDacHandle[cnt],PWM_SyncMode_EPWMxSYNC); -+ PWMDAC_setHighSpeedClkDiv(obj->pwmDacHandle[cnt],PWM_HspClkDiv_by_1); -+ PWMDAC_setClkDiv(obj->pwmDacHandle[cnt],PWM_ClkDiv_by_1); -+ PWMDAC_setPhaseDir(obj->pwmDacHandle[cnt],PWM_PhaseDir_CountUp); -+ PWMDAC_setRunMode(obj->pwmDacHandle[cnt],PWM_RunMode_FreeRun); -+ -+ // initialize the Timer-Based Phase Register (TBPHS) -+ PWMDAC_setPhase(obj->pwmDacHandle[cnt],0); -+ -+ // setup the Time-Base Counter Register (TBCTR) -+ PWMDAC_setCount(obj->pwmDacHandle[cnt],0); -+ -+ // Initialize the Time-Base Period Register (TBPRD) -+ // set to zero initially -+ PWMDAC_setPeriod(obj->pwmDacHandle[cnt],0); -+ -+ // initialize the Counter-Compare Control Register (CMPCTL) -+ PWMDAC_setLoadMode_CmpA(obj->pwmDacHandle[cnt],PWM_LoadMode_Zero); -+ PWMDAC_setLoadMode_CmpB(obj->pwmDacHandle[cnt],PWM_LoadMode_Zero); -+ PWMDAC_setShadowMode_CmpA(obj->pwmDacHandle[cnt],PWM_ShadowMode_Shadow); -+ PWMDAC_setShadowMode_CmpB(obj->pwmDacHandle[cnt],PWM_ShadowMode_Shadow); -+ -+ // Initialize the Action-Qualifier Output A Register (AQCTLA) -+ PWMDAC_setActionQual_CntUp_CmpA_PwmA(obj->pwmDacHandle[cnt],PWM_ActionQual_Clear); -+ PWMDAC_setActionQual_CntDown_CmpA_PwmA(obj->pwmDacHandle[cnt],PWM_ActionQual_Set); -+ PWMDAC_setActionQual_CntUp_CmpB_PwmB(obj->pwmDacHandle[cnt],PWM_ActionQual_Clear); -+ PWMDAC_setActionQual_CntDown_CmpB_PwmB(obj->pwmDacHandle[cnt],PWM_ActionQual_Set); -+ -+ // Initialize the Dead-Band Control Register (DBCTL) -+ PWMDAC_disableDeadBand(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the PWM-Chopper Control Register (PCCTL) -+ PWMDAC_disableChopping(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the Trip-Zone Control Register (TZSEL) -+ PWMDAC_disableTripZones(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the Trip-Zone Control Register (TZCTL) -+ PWMDAC_setTripZoneState_TZA(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_TZB(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCAEVT1(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCAEVT2(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCBEVT1(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ } -+ -+ // since the PWM is configured as an up/down counter, the period register is set to one-half -+ // of the desired PWM period -+ PWMDAC_setPeriod(obj->pwmDacHandle[PWMDAC_Number_1],halfPeriod_cycles); -+ PWMDAC_setPeriod(obj->pwmDacHandle[PWMDAC_Number_2],halfPeriod_cycles); -+ -+ return; -+ } // end of HAL_setupPwmDacs() function -+ -+ -+ void HAL_setupTimers(HAL_Handle handle,const float_t systemFreq_MHz) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint32_t timerPeriod_cnts = (uint32_t)(systemFreq_MHz * (float_t)1000000.0) - 1; -+ -+ // use timer 0 for frequency diagnostics -+ TIMER_setDecimationFactor(obj->timerHandle[0],0); -+ TIMER_setEmulationMode(obj->timerHandle[0],TIMER_EmulationMode_RunFree); -+ TIMER_setPeriod(obj->timerHandle[0],timerPeriod_cnts); -+ TIMER_setPreScaler(obj->timerHandle[0],0); -+ -+ // use timer 1 for CPU usage diagnostics -+ TIMER_setDecimationFactor(obj->timerHandle[1],0); -+ TIMER_setEmulationMode(obj->timerHandle[1],TIMER_EmulationMode_RunFree); -+ TIMER_setPeriod(obj->timerHandle[1],timerPeriod_cnts); -+ TIMER_setPreScaler(obj->timerHandle[1],0); -+ -+ return; -+ } // end of HAL_setupTimers() function -+ -+ // here come the setup-functions for the custom used peripherals for FIKAT -+ /* a) McBSPA - Transceiver ... */ -+ void HAL_setupMcBSPA(HAL_Handle handle){ // ja, okay -+ MCBSP_resetTransmitter(handle->mcBSPAhandle); -+ MCBSP_resetReceiver(handle->mcBSPAhandle); -+ MCBSP_resetSampleRateGenerator(handle->mcBSPAhandle); -+ // wieder in Mode2 wechseln! -+ MCBSP_setMode(handle->mcBSPAhandle, McBsp_SPISlaveMode2, McBSP_disableLoopback); -+ -+ MCBSP_sampleRateGeneratorInputClockMode(handle->mcBSPAhandle, McBSP_SampleRateGen_Source_LSPCLK); -+ -+ MCBSP_setSRGClockDivider(handle->mcBSPAhandle, 2); -+ -+ MCBSP_setTransmitFrameSynchronizationMode(handle->mcBSPAhandle, MCBSP_TransmitFrameSyncMode_EXTERNAL); -+ MCBSP_setTransmitFrameSyncPolarity(handle->mcBSPAhandle, MCBSP_ReceiveFrameSync__ACTIVE_LOW); -+ -+ MCBSP_setReceiveDataDelay(handle->mcBSPAhandle, MCBSP_ReceiveDataDelay_0Bit); -+ MCBSP_setTransmitDataDelay(handle->mcBSPAhandle, MCBSP_TransmitDataDelay_0Bit); -+ -+ MCBSP_resetReleaseSampleRateGenerator(handle->mcBSPAhandle); -+ -+ MCBSP_setReceiveWordLength1(handle->mcBSPAhandle, MCBSP_ReceiveWordLength1_16Bits); -+ MCBSP_setTransmitWordLength1(handle->mcBSPAhandle, MCBSP_TransmitWordLength1_16Bits); -+ MCBSP_InitDelayLoop(handle->mcBSPAhandle, USER_SYSTEM_FREQ_MHz); -+ -+ MCBSP_resetReleaseTransmitter(handle->mcBSPAhandle); -+ MCBSP_resetReleaseReceiver(handle->mcBSPAhandle); -+ MCBSP_resetReleaseFrameSynchronizationLogic(handle->mcBSPAhandle); -+ -+ return; -+ } // end of HAL_setupMcBSPA() function -+ -+ /* DMA - Controller */ -+ void HAL_setupDMA(HAL_Handle handle){ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ DMA_hardReset(handle->DMAhandle); -+ -+ /* DMA-Channel 1 konfigurieren; McBSP-Tx-Kanal */ -+ DMA_disableChannelInterrupt(handle->DMAhandle, DMA_CH1); -+ -+ DMA_BurstConfig(handle->DMAhandle, DMA_CH1, 0, 0, 0); -+ -+ //*** DMA_TransferConfig(handle->DMAhandle, DMA_CH1, 15, 1, 0); -+ DMA_TransferConfig(handle->DMAhandle, DMA_CH1, BUFFER_SIZE-1, 1, 0); -+ -+ DMA_WrapConfig(handle->DMAhandle, DMA_CH1, 0xFFFF, 0, 0xFFFF, 0); -+ -+ DMA_ModeConfig(handle->DMAhandle, handle->pieHandle, DMA_CH1, -+ DMA_MXEVTA, 1, ONESHOT_DISABLE, CONT_ENABLE, SYNC_DISABLE, SYNC_SRC, -+ OVRFLOW_DISABLE, SIXTEEN_BIT, CHINT_END, CHINT_DISABLE); -+ -+ /* DMA-Channel 2 konfigurieren; McBSP-Rx-Kanal */ -+ DMA_disableChannelInterrupt(handle->DMAhandle, DMA_CH2); -+ -+ DMA_BurstConfig(handle->DMAhandle, DMA_CH2, 0, 0, 0); -+ -+ //*** DMA_TransferConfig(handle->DMAhandle, DMA_CH2, 15, 0, 1); -+ DMA_TransferConfig(handle->DMAhandle, DMA_CH2, BUFFER_SIZE-1, 0, 1); -+ -+ DMA_WrapConfig(handle->DMAhandle, DMA_CH2, 0xFFFF, 0, 0xFFFF, 0); -+ // hier war DMA_MREVTA -+ DMA_ModeConfig(handle->DMAhandle, handle->pieHandle, DMA_CH2, -+ DMA_MXEVTA, 1, ONESHOT_DISABLE, CONT_ENABLE, SYNC_DISABLE, SYNC_SRC, -+ OVRFLOW_DISABLE, SIXTEEN_BIT, CHINT_END, CHINT_DISABLE); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ /* setup DMA-Memory Adresses for the arrays */ -+ DMA_AddrConfig(handle->DMAhandle, DMA_CH1, &handle->mcBSPAhandle->DXR1, tx_buffer); -+ DMA_AddrConfig(handle->DMAhandle, DMA_CH2, rx_buffer, &handle->mcBSPAhandle->DRR1); -+ -+ DMA_run(handle->DMAhandle, DMA_CH1); -+ DMA_run(handle->DMAhandle, DMA_CH2); -+ -+ return; -+ } // end of HAL_setupDMA() function -+ -+ void HAL_calculateOffsetDCBusCurrent(HAL_Handle handle, HAL_AdcData_t * gAdcData){ -+ HAL_disablePwm(handle); -+ int i = 0; -+ float acc = 0.0; -+ for(i = 0; i < 10; i++){ -+ acc = acc + _IQtoF(_IQmpy(gAdcData->I_dcBus,_IQ(USER_IQ_FULL_SCALE_CURRENT_A))); -+ } -+ dcBusCurrentOffset = acc / 10.0; -+ dcBusCurrentOffsetCalibrationDone = true; -+ } // end of HAL_getOffsetDCBusCurrent() function -+ -+ float HAL_getDCbusCurrentOffset(){ -+ if(dcBusCurrentOffsetCalibrationDone){ -+ return dcBusCurrentOffset; -+ }else{ -+ return -9999.0; -+ } -+ } // end of HAL_getDCbusOffset() function -+ -+ bool HAL_getDCbusCurrentOffsetCalibrationDone(){ -+ return dcBusCurrentOffsetCalibrationDone; -+ } // end of HAL_getDCbusCurrentOffsetCalibrationDone() function -+ -+ // end of file -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.h 2017-07-20 11:05:43.503923600 +0200 -*************** -*** 0 **** ---- 1,1483 ---- -+ #ifndef _HAL_H_ -+ #define _HAL_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806x/src/hal.h -+ //! \brief Contains public interface to various functions related -+ //! to the HAL object -+ //! -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ -+ // modules -+ -+ -+ // platforms -+ #include "hal_obj.h" -+ #include "sw/modules/svgen/src/32b/svgen_current.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL HAL -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ -+ // ************************************************************************** -+ // the defines -+ -+ #define Device_cal (void (*)(void))0x3D7C80 -+ -+ //! \brief Defines used in oscillator calibration functions -+ //! \brief Defines the scale factor for Q15 fixed point numbers (2^15) -+ #define FP_SCALE 32768 -+ -+ //! \brief Defines the quantity added to Q15 numbers before converting to integer to round the number -+ #define FP_ROUND FP_SCALE/2 -+ -+ //! \brief Defines the amount to add to Q16.15 fixed point number to shift from a fine trim range of -+ //! \brief (-31 to 31) to (1 to 63). This guarantees that the trim is positive and can -+ //! \brief therefore be efficiently rounded -+ #define OSC_POSTRIM 32 -+ #define OSC_POSTRIM_OFF FP_SCALE*OSC_POSTRIM -+ -+ //! \brief The following functions return reference values stored in OTP. -+ -+ //! \brief Defines the slope used to compensate oscillator 1 (fine trim steps / ADC code). Stored in fixed point Q15 format -+ #define getOsc1FineTrimSlope() (*(int16_t (*)(void))0x3D7E90)() -+ -+ //! \brief Defines the oscillator 1 fine trim at high temp -+ #define getOsc1FineTrimOffset() (*(int16_t (*)(void))0x3D7E93)() -+ -+ //! \brief Defines the oscillator 1 coarse trim -+ #define getOsc1CoarseTrim() (*(int16_t (*)(void))0x3D7E96)() -+ -+ //! \brief Defines the slope used to compensate oscillator 2 (fine trim steps / ADC code). Stored -+ //! \brief in fixed point Q15 format. -+ #define getOsc2FineTrimSlope() (*(int16_t (*)(void))0x3D7E99)() -+ -+ //! \brief Defines the oscillator 2 fine trim at high temp -+ #define getOsc2FineTrimOffset() (*(int16_t (*)(void))0x3D7E9C)() -+ -+ //! \brief Defines the oscillator 2 coarse trim -+ #define getOsc2CoarseTrim() (*(int16_t (*)(void))0x3D7E9F)() -+ -+ //! \brief Defines the ADC reading of temperature sensor at reference temperature for compensation -+ #define getRefTempOffset() (*(int16_t (*)(void))0x3D7EA2)() -+ -+ //! \brief Defines the PWM deadband falling edge delay count (system clocks) -+ //! -+ #define HAL_PWM_DBFED_CNT 1 -+ -+ -+ //! \brief Defines the PWM deadband rising edge delay count (system clocks) -+ //! -+ #define HAL_PWM_DBRED_CNT 1 -+ -+ -+ //! \brief Defines the function to turn LEDs off -+ //! -+ #define HAL_turnLedOff HAL_setGpioLow -+ -+ -+ //! \brief Defines the function to turn LEDs on -+ //! -+ #define HAL_turnLedOn HAL_setGpioHigh -+ -+ -+ //! \brief Defines the function to turn LEDs on -+ //! -+ #define HAL_toggleLed HAL_toggleGpio -+ -+ -+ // ************************************************************************** -+ // the typedefs -+ -+ -+ //! \brief Enumeration for the QEP setup -+ //! -+ typedef enum -+ { -+ HAL_Qep_QEP1=0, //!< Select QEP1 -+ HAL_Qep_QEP2=1 //!< Select QEP2 -+ } HAL_QepSelect_e; -+ -+ -+ //! \brief Enumeration for the LED numbers -+ //! -+ typedef enum -+ { -+ HAL_Gpio_LED2=GPIO_Number_34, //!< GPIO pin number for LaunchPad LED D9 -+ HAL_Gpio_LED3=GPIO_Number_39 //!< GPIO pin number for LaunchPad LED D10 -+ } HAL_LedNumber_e; -+ -+ -+ //! \brief Enumeration for the digital Inputs of the FIKAT-Board -+ //! -+ typedef enum -+ { -+ HAL_FIKAT_DIC24_0=GPIO_Number_0, //!< Digital Input 0 (DIC24_0) of the FIKAT Board -+ HAL_FIKAT_DIC24_1=GPIO_Number_1, //!< Digital Input 1 (DIC24_1) of the FIKAT Board -+ HAL_FIKAT_DIC24_2=GPIO_Number_2, //!< Digital Input 2 (DIC24_2) of the FIKAT Board -+ HAL_FIKAT_DIC24_3=GPIO_Number_3 //!< Digital Input 3 (DIC24_3) of the FIKAT Board -+ } HAL_FikatDINumber_e; -+ -+ -+ //! \brief Enumeration for the digital Outputs of the FIKAT-Board -+ //! -+ typedef enum -+ { -+ HAL_FIKAT_DO24_0=GPIO_Number_4, //!< Digital Output 0 (DO24_0) of the FIKAT Board -+ HAL_FIKAT_DO24_1=GPIO_Number_5, //!< Digital Output 1 (DO24_1) of the FIKAT Board -+ HAL_FIKAT_DO24_2=GPIO_Number_40, //!< Digital Output 2 (DO24_2) of the FIKAT Board -+ HAL_FIKAT_DO24_3=GPIO_Number_41, //!< Digital Output 3 (DO24_3) of the FIKAT Board -+ HAL_FIKAT_DO24_4=GPIO_Number_42, //!< Digital Output 4 (DO24_4) of the FIKAT Board -+ HAL_FIKAT_DO24_5=GPIO_Number_43, //!< Digital Output 5 (DO24_5) of the FIKAT Board -+ HAL_FIKAT_DO24_6=GPIO_Number_12 //!< Digital Output 6 (DO24_6) of the FIKAT Board -+ }HAL_FikatDONumber_e; -+ -+ //! \brief Enumeration for the sensor types -+ //! -+ typedef enum -+ { -+ HAL_SensorType_Current=0, //!< Enumeration for current sensor -+ HAL_SensorType_Voltage //!< Enumeration for voltage sensor -+ } HAL_SensorType_e; -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ extern interrupt void mainISR(void); -+ -+ extern interrupt void cpuTimer2ISR(void); -+ -+ // ************************************************************************** -+ // the function prototypes -+ -+ -+ //! \brief Acknowledges an interrupt from the ADC so that another ADC interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] intNumber The interrupt number -+ static inline void HAL_acqAdcInt(HAL_Handle handle,const ADC_IntNumber_e intNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the ADC interrupt flag -+ ADC_clearIntFlag(obj->adcHandle,intNumber); -+ -+ -+ // Acknowledge interrupt from PIE group 10 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_10); -+ -+ return; -+ } // end of HAL_acqAdcInt() function -+ -+ -+ //! \brief Acknowledges an interrupt from the PWM so that another PWM interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ static inline void HAL_acqPwmInt(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the PWM interrupt flag -+ PWM_clearIntFlag(obj->pwmHandle[pwmNumber]); -+ -+ -+ // clear the SOCA flag -+ PWM_clearSocAFlag(obj->pwmHandle[pwmNumber]); -+ -+ -+ // Acknowledge interrupt from PIE group 3 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_3); -+ -+ return; -+ } // end of HAL_acqPwmInt() function -+ -+ -+ //! \brief Acknowledges an interrupt from Timer 0 so that another Timer 0 interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_acqTimer0Int(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the Timer 0 interrupt flag -+ TIMER_clearFlag(obj->timerHandle[0]); -+ -+ -+ // Acknowledge interrupt from PIE group 1 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_1); -+ -+ return; -+ } // end of HAL_acqTimer0Int() function -+ -+ -+ //! \brief Executes calibration routines -+ //! \details Values for offset and gain are programmed into OTP memory at -+ //! the TI factory. This calls and internal function that programs -+ //! these offsets and gains into the ADC registers. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_cal(HAL_Handle handle); -+ -+ -+ //! \brief Disables global interrupts -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_disableGlobalInts(HAL_Handle handle); -+ -+ -+ //! \brief Disables the watch dog -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_disableWdog(HAL_Handle handle); -+ -+ -+ //! \brief Disables the PWM device -+ //! \details Turns off the outputs of the EPWM peripherals which will put -+ //! the power switches into a high impedance state. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_disablePwm(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ return; -+ } // end of HAL_disablePwm() function -+ -+ -+ //! \brief Enables the ADC interrupts -+ //! \details Enables the ADC interrupt in the PIE, and CPU. Enables the -+ //! interrupt to be sent from the ADC peripheral. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableAdcInts(HAL_Handle handle); -+ -+ -+ //! \brief Enables the debug interrupt -+ //! \details The debug interrupt is used for the real-time debugger. It is -+ //! not needed if the real-time debugger is not used. Clears -+ //! bit 1 of ST1. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableDebugInt(HAL_Handle handle); -+ -+ -+ //! \brief Enables global interrupts -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableGlobalInts(HAL_Handle handle); -+ -+ -+ //! \brief Enables the PWM devices -+ //! \details Turns on the outputs of the EPWM peripheral which will allow -+ //! the power switches to be controlled. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_enablePwm(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ return; -+ } // end of HAL_enablePwm() function -+ -+ -+ //! \brief Enables the PWM interrupt -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enablePwmInt(HAL_Handle handle); -+ -+ -+ //! \brief Enables the Timer 0 interrupt -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableTimer0Int(HAL_Handle handle); -+ -+ -+ //! \brief Gets the ADC delay value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] socNumber The ADC SOC number -+ //! \return The ADC delay value -+ static inline ADC_SocSampleDelay_e HAL_getAdcSocSampleDelay(HAL_Handle handle, -+ const ADC_SocNumber_e socNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(ADC_getSocSampleDelay(obj->adcHandle,socNumber)); -+ } // end of HAL_getAdcSocSampleDelay() function -+ -+ -+ //! \brief Gets the ADC bias value -+ //! \details The ADC bias contains the feedback circuit's offset and bias. -+ //! Bias is the mathematical offset used when a bi-polar signal -+ //! is read into a uni-polar ADC. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \return The ADC bias value -+ static inline _iq HAL_getBias(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ uint_least8_t sensorNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ _iq bias = _IQ(0.0); -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ bias = obj->adcBias.I.value[sensorNumber]; -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ bias = obj->adcBias.V.value[sensorNumber]; -+ } -+ -+ return(bias); -+ } // end of HAL_getBias() function -+ -+ -+ //! \brief Gets the current scale factor -+ //! \details The current scale factor is defined as -+ //! USER_ADC_FULL_SCALE_CURRENT_A/USER_IQ_FULL_SCALE_CURRENT_A. -+ //! This scale factor is not used when converting between PU amps -+ //! and real amps. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The current scale factor -+ static inline _iq HAL_getCurrentScaleFactor(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(obj->current_sf); -+ } // end of HAL_getCurrentScaleFactor() function -+ -+ -+ //! \brief Gets the number of current sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The number of current sensors -+ static inline uint_least8_t HAL_getNumCurrentSensors(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ return(obj->numCurrentSensors); -+ } // end of HAL_getNumCurrentSensors() function -+ -+ -+ //! \brief Gets the number of voltage sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The number of voltage sensors -+ static inline uint_least8_t HAL_getNumVoltageSensors(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ return(obj->numVoltageSensors); -+ } // end of HAL_getNumVoltageSensors() function -+ -+ -+ //! \brief Gets the value used to set the low pass filter pole for offset estimation -+ //! \details An IIR single pole low pass filter is used to find the feedback circuit's -+ //! offsets. This function returns the value of that pole. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \return The value used to set the low pass filter pole, pu -+ static inline _iq HAL_getOffsetBeta_lp_pu(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq beta_lp_pu = _IQ(0.0); -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ beta_lp_pu = OFFSET_getBeta(obj->offsetHandle_I[sensorNumber]); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ beta_lp_pu = OFFSET_getBeta(obj->offsetHandle_V[sensorNumber]); -+ } -+ -+ return(beta_lp_pu); -+ } // end of HAL_getOffsetBeta_lp_pu() function -+ -+ -+ //! \brief Gets the offset value -+ //! \details The offsets that are calculated during the feedback circuits calibrations -+ //! are returned from the IIR filter object. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \return The offset value -+ static inline _iq HAL_getOffsetValue(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq offset = _IQ(0.0); -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ offset = OFFSET_getOffset(obj->offsetHandle_I[sensorNumber]); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ offset = OFFSET_getOffset(obj->offsetHandle_V[sensorNumber]); -+ } -+ -+ return(offset); -+ } // end of HAL_getOffsetValue() function -+ -+ -+ //! \brief Gets the voltage scale factor -+ //! \details The voltage scale factor is defined as -+ //! USER_ADC_FULL_SCALE_VOLTAGE_V/USER_IQ_FULL_SCALE_VOLTAGE_V. -+ //! This scale factor is not used when converting between PU volts -+ //! and real volts. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The voltage scale factor -+ static inline _iq HAL_getVoltageScaleFactor(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(obj->voltage_sf); -+ } // end of HAL_getVoltageScaleFactor() function -+ -+ //! \brief Gets the voltage scale factor -+ //! \details The voltage scale factor is defined as -+ //! USER_ADC_FULL_SCALE_VOLTAGE_V/USER_IQ_FULL_SCALE_VOLTAGE_V. -+ //! This scale factor is not used when converting between PU volts -+ //! and real volts. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The voltage scale factor -+ static inline _iq HAL_getAnalogInputVoltageScaleFactor(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(obj->analogInVoltage_sf); -+ } // end of HAL_getAnalogInputVoltageScaleFactor() function -+ -+ //! \brief Configures the fault protection logic -+ //! \details Sets up the trip zone inputs so that when a comparator -+ //! signal from outside the micro-controller trips a fault, -+ //! the EPWM peripheral blocks will force the -+ //! power switches into a high impedance state. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupFaults(HAL_Handle handle); -+ -+ -+ //! \brief Initializes the hardware abstraction layer (HAL) object -+ //! \details Initializes all handles to the microcontroller peripherals. -+ //! Returns a handle to the HAL object. -+ //! \param[in] pMemory A pointer to the memory for the hardware abstraction layer object -+ //! \param[in] numBytes The number of bytes allocated for the hardware abstraction layer object, bytes -+ //! \return The hardware abstraction layer (HAL) object handle -+ extern HAL_Handle HAL_init(void *pMemory,const size_t numBytes); -+ -+ -+ //! \brief Initializes the interrupt vector table -+ //! \details Points ADCINT1 to mainISR -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_initIntVectorTable(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ PIE_Obj *pie = (PIE_Obj *)obj->pieHandle; -+ -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ pie->ADCINT1 = &mainISR; -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_initIntVectorTable() function -+ -+ -+ //! \brief Reads the ADC data -+ //! \details Reads in the ADC result registers, adjusts for offsets, and -+ //! scales the values according to the settings in user.h. The -+ //! structure gAdcData holds three phase voltages, three line -+ //! currents, and one DC bus voltage. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pAdcData A pointer to the ADC data buffer -+ static inline void HAL_readAdcData(HAL_Handle handle,HAL_AdcData_t *pAdcData) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq value; -+ _iq current_sf = HAL_getCurrentScaleFactor(handle); -+ _iq voltage_sf = HAL_getVoltageScaleFactor(handle); -+ -+ // custom defined scaling factors for FIKAT -+ _iq voltage_sf_analogIn_FIKAT = HAL_getAnalogInputVoltageScaleFactor(handle); -+ -+ // convert current A -+ // sample the first sample twice due to errata sprz342f, ignore the first sample -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_1); -+ value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[0]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->I.value[0] = value; -+ -+ // convert current B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_2); -+ value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[1]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->I.value[1] = value; -+ -+ // convert current C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_3); -+ value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[2]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->I.value[2] = value; -+ -+ // convert voltage A -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_4); -+ value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[0]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->V.value[0] = value; -+ -+ // convert voltage B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_5); -+ value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[1]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->V.value[1] = value; -+ -+ // convert voltage C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_6); -+ value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[2]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->V.value[2] = value; -+ -+ // read the dcBus voltage value -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_7); // divide by 2^numAdcBits = 2^12 -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->dcBus = value; -+ -+ /* extra functions of FIKAT-Board */ -+ // read the dcBus current value -+ // TODO : hier muss ich mir für den Bias-Wert noch was überlegen ... -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_8); -+ value = _IQ12mpy(value,current_sf); // divide by 2^numAdcBits = 2^12 -+ pAdcData->I_dcBus = value; -+ -+ // read the input values for the external analog inputs ADC24_0 ... ADC24_5 -+ // analog input ADC24_0 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_9); -+ value = _IQ12mpy(value,voltage_sf_analogIn_FIKAT); // divide by 2^numAdcBits = 2^12 -+ pAdcData->AnalogIn[0] = value; -+ -+ // analog input ADC24_1 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_10); -+ value = _IQ12mpy(value,voltage_sf_analogIn_FIKAT); // divide by 2^numAdcBits = 2^12 -+ pAdcData->AnalogIn[1] = value; -+ -+ // analog input ADC24_2 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_11); -+ value = _IQ12mpy(value,voltage_sf_analogIn_FIKAT); // divide by 2^numAdcBits = 2^12 -+ pAdcData->AnalogIn[2] = value; -+ -+ // analog input ADC24_3 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_12); -+ value = _IQ12mpy(value,voltage_sf_analogIn_FIKAT); // divide by 2^numAdcBits = 2^12 -+ pAdcData->AnalogIn[3] = value; -+ -+ // analog input ADC24_4 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_13); -+ value = _IQ12mpy(value,voltage_sf_analogIn_FIKAT); // divide by 2^numAdcBits = 2^12 -+ pAdcData->AnalogIn[4] = value; -+ -+ // analog input ADC24_5 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_14); -+ value = _IQ12mpy(value,voltage_sf_analogIn_FIKAT); // divide by 2^numAdcBits = 2^12 -+ pAdcData->AnalogIn[5] = value; -+ -+ // read the temperature sensor value from ADCIN_B6 -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_15); -+ value = _IQ12mpy(value,_IQ(3.30)); // divide by 2^numAdcBits = 2^12, 3.3V is the maximum ADC input voltage -+ value = value - _IQ(0.60); // 600mV Offset -+ value = _IQdiv(value,_IQ(0.01)); // 10mV/°C gain -+ pAdcData->TempSensor = value; -+ -+ return; -+ } // end of HAL_readAdcData() function -+ -+ -+ //! \brief Reads the ADC data -+ //! \details Reads in the ADC result registers, and -+ //! scales the values according to the settings in user.h. The -+ //! structure gAdcData holds three phase voltages, three line -+ //! currents, and one DC bus voltage. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pAdcData A pointer to the ADC data buffer -+ static inline void HAL_readAdcDataWithOffsets(HAL_Handle handle,HAL_AdcData_t *pAdcData) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq value; -+ _iq current_sf = HAL_getCurrentScaleFactor(handle); -+ _iq voltage_sf = HAL_getVoltageScaleFactor(handle); -+ -+ -+ // convert current A -+ // sample the first sample twice due to errata sprz342f, ignore the first sample -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_1); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[0] = value; -+ -+ // convert current B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_2); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[1] = value; -+ -+ // convert current C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_3); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[2] = value; -+ -+ // convert voltage A -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_4); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[0] = value; -+ -+ // convert voltage B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_5); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[1] = value; -+ -+ // convert voltage C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_6); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[2] = value; -+ -+ // read the dcBus voltage value -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_7); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->dcBus = value; -+ -+ return; -+ } // end of HAL_readAdcDataWithOffsets() function -+ -+ -+ //! \brief Reads the timer count -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \return The timer count -+ static inline uint32_t HAL_readTimerCnt(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint32_t timerCnt = TIMER_getCount(obj->timerHandle[timerNumber]); -+ -+ return(timerCnt); -+ } // end of HAL_readTimerCnt() function -+ -+ -+ //! \brief Reloads the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_reloadTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // reload the specified timer -+ TIMER_reload(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_reloadTimer() function -+ -+ -+ //! \brief Starts the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_startTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // start the specified timer -+ TIMER_start(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_startTimer() function -+ -+ -+ //! \brief Stops the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_stopTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // stop the specified timer -+ TIMER_stop(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_stopTimer() function -+ -+ -+ //! \brief Sets the timer period -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \param[in] period The timer period -+ static inline void HAL_setTimerPeriod(HAL_Handle handle,const uint_least8_t timerNumber, const uint32_t period) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // set the period -+ TIMER_setPeriod(obj->timerHandle[timerNumber], period); -+ -+ return; -+ } // end of HAL_setTimerPeriod() function -+ -+ -+ //! \brief Gets the timer period -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \return The timer period -+ static inline uint32_t HAL_getTimerPeriod(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ uint32_t timerPeriod = TIMER_getPeriod(obj->timerHandle[timerNumber]); -+ -+ return(timerPeriod); -+ } // end of HAL_getTimerPeriod() function -+ -+ -+ //! \brief Sets the ADC SOC sample delay value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] socNumber The SOC number -+ //! \param[in] sampleDelay The delay value for the ADC -+ static inline void HAL_setAdcSocSampleDelay(HAL_Handle handle, -+ const ADC_SocNumber_e socNumber, -+ const ADC_SocSampleDelay_e sampleDelay) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ADC_setSocSampleDelay(obj->adcHandle,socNumber,sampleDelay); -+ -+ return; -+ } // end of HAL_setAdcSocSampleDelay() function -+ -+ -+ //! \brief Sets the ADC bias value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] bias The ADC bias value -+ static inline void HAL_setBias(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ uint_least8_t sensorNumber, -+ const _iq bias) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ obj->adcBias.I.value[sensorNumber] = bias; -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ obj->adcBias.V.value[sensorNumber] = bias; -+ } -+ -+ return; -+ } // end of HAL_setBias() function -+ -+ -+ //! \brief Sets the GPIO pin high -+ //! \details Takes in the enumeration GPIO_Number_e and sets that GPIO -+ //! pin high. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_setGpioHigh(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO high -+ GPIO_setHigh(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioHigh() function -+ -+ -+ //! \brief Reads the specified GPIO pin -+ //! \details Takes in the enumeration GPIO_Number_e and reads that GPIO -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline bool HAL_readGpio(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // read GPIO -+ return(GPIO_read(obj->gpioHandle,gpioNumber)); -+ } // end of HAL_readGpio() function -+ -+ -+ //! \brief Toggles the GPIO pin -+ //! \details Takes in the enumeration GPIO_Number_e and toggles that GPIO -+ //! pin. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_toggleGpio(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO high -+ GPIO_toggle(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioHigh() function -+ -+ -+ //! \brief Sets the GPIO pin low -+ //! \details Takes in the enumeration GPIO_Number_e and clears that GPIO -+ //! pin low. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_setGpioLow(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO low -+ GPIO_setLow(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioLow() function -+ -+ -+ //! \brief Sets the current scale factor in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] current_sf The current scale factor -+ static inline void HAL_setCurrentScaleFactor(HAL_Handle handle,const _iq current_sf) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ obj->current_sf = current_sf; -+ -+ return; -+ } // end of HAL_setCurrentScaleFactor() function -+ -+ -+ //! \brief Sets the number of current sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] numCurrentSensors The number of current sensors -+ static inline void HAL_setNumCurrentSensors(HAL_Handle handle,const uint_least8_t numCurrentSensors) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ obj->numCurrentSensors = numCurrentSensors; -+ -+ return; -+ } // end of HAL_setNumCurrentSensors() function -+ -+ -+ //! \brief Sets the number of voltage sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] numVoltageSensors The number of voltage sensors -+ static inline void HAL_setNumVoltageSensors(HAL_Handle handle,const uint_least8_t numVoltageSensors) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ obj->numVoltageSensors = numVoltageSensors; -+ -+ return; -+ } // end of HAL_setNumVoltageSensors() function -+ -+ -+ //! \brief Sets the value used to set the low pass filter pole for offset estimation -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] beta_lp_pu The value used to set the low pass filter pole, pu -+ static inline void HAL_setOffsetBeta_lp_pu(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber, -+ const _iq beta_lp_pu) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ OFFSET_setBeta(obj->offsetHandle_I[sensorNumber],beta_lp_pu); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ OFFSET_setBeta(obj->offsetHandle_V[sensorNumber],beta_lp_pu); -+ } -+ -+ return; -+ } // end of HAL_setOffsetBeta_lp_pu() function -+ -+ -+ //! \brief Sets the offset initial condition value for offset estimation -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] initCond The initial condition value -+ static inline void HAL_setOffsetInitCond(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber, -+ const _iq initCond) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ OFFSET_setInitCond(obj->offsetHandle_I[sensorNumber],initCond); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ OFFSET_setInitCond(obj->offsetHandle_V[sensorNumber],initCond); -+ } -+ -+ return; -+ } // end of HAL_setOffsetInitCond() function -+ -+ -+ //! \brief Sets the initial offset value for offset estimation -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] value The initial offset value -+ static inline void HAL_setOffsetValue(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber, -+ const _iq value) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ OFFSET_setOffset(obj->offsetHandle_I[sensorNumber],value); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ OFFSET_setOffset(obj->offsetHandle_V[sensorNumber],value); -+ } -+ -+ return; -+ } // end of HAL_setOffsetValue() function -+ -+ -+ //! \brief Sets the voltage scale factor in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] voltage_sf The voltage scale factor -+ static inline void HAL_setVoltageScaleFactor(HAL_Handle handle,const _iq voltage_sf) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ obj->voltage_sf = voltage_sf; -+ -+ return; -+ } // end of HAL_setVoltageScaleFactor() function -+ -+ //! \brief Sets the voltage scale factor for the 6 external analog Inputs in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] voltage_sf The voltage scale factor -+ static inline void HAL_setAnalogInputVoltageScaleFactor(HAL_Handle handle,const _iq voltage_sf) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ obj->analogInVoltage_sf = voltage_sf; -+ -+ return; -+ } // end of HAL_setAnalogInputVoltageScaleFactor() function -+ -+ -+ //! \brief Sets the hardware abstraction layer parameters -+ //! \details Sets up the microcontroller peripherals. Creates all of the scale -+ //! factors for the ADC voltage and current conversions. Sets the initial -+ //! offset values for voltage and current measurements. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pUserParams The pointer to the user parameters -+ extern void HAL_setParams(HAL_Handle handle,const USER_Params *pUserParams); -+ -+ -+ //! \brief Sets up the ADCs (Analog to Digital Converters) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupAdcs(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the clocks -+ //! \details Sets up the micro-controller's main oscillator -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupClks(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the FLASH. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupFlash(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the GPIO (General Purpose I/O) pins -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupGpios(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the peripheral clocks -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPeripheralClks(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the PIE (Peripheral Interrupt Expansion) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPie(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the PLL (Phase Lock Loop) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] clkFreq The clock frequency -+ extern void HAL_setupPll(HAL_Handle handle,const PLL_ClkFreq_e clkFreq); -+ -+ -+ //! \brief Sets up the PWMs (Pulse Width Modulators) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] systemFreq_MHz The system frequency, MHz -+ //! \param[in] pwmPeriod_usec The PWM period, usec -+ //! \param[in] numPwmTicksPerIsrTick The number of PWM clock ticks per ISR clock tick -+ extern void HAL_setupPwms(HAL_Handle handle, -+ const float_t systemFreq_MHz, -+ const float_t pwmPeriod_usec, -+ const uint_least16_t numPwmTicksPerIsrTick); -+ -+ -+ //! \brief Sets up the PWM DACs (Pulse Width Modulator Digital to Analof Converters) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPwmDacs(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the QEP peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupQEP(HAL_Handle handle,HAL_QepSelect_e qep); -+ -+ -+ //! \brief Sets up the spiA peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupSpiA(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the spiB peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupSpiB(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the timers -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] systemFreq_MHz The system frequency, MHz -+ void HAL_setupTimers(HAL_Handle handle,const float_t systemFreq_MHz); -+ -+ -+ //! \brief Updates the ADC bias values -+ //! \details This function is called before the motor is started. It sets the voltage -+ //! and current measurement offsets. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_updateAdcBias(HAL_Handle handle) -+ { -+ uint_least8_t cnt; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ _iq bias; -+ -+ -+ // update the current bias -+ for(cnt=0;cntoffsetHandle_I[cnt]); -+ //*FIKAT?*/bias -= OFFSET_getOffset(obj->offsetHandle_I[cnt]); -+ -+ HAL_setBias(handle,HAL_SensorType_Current,cnt,bias); -+ } -+ -+ -+ // update the voltage bias -+ for(cnt=0;cntoffsetHandle_V[cnt]); -+ -+ HAL_setBias(handle,HAL_SensorType_Voltage,cnt,bias); -+ } -+ -+ return; -+ } // end of HAL_updateAdcBias() function -+ -+ -+ //! \brief Writes DAC data to the PWM comparators for DAC (digital-to-analog conversion) output -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pDacData The pointer to the DAC data -+ static inline void HAL_writeDacData(HAL_Handle handle,HAL_DacData_t *pDacData) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // convert values from _IQ to _IQ15 -+ int16_t dacValue_1 = (int16_t)_IQtoIQ15(pDacData->value[0]); -+ int16_t dacValue_2 = (int16_t)_IQtoIQ15(pDacData->value[1]); -+ int16_t dacValue_3 = (int16_t)_IQtoIQ15(pDacData->value[2]); -+ int16_t dacValue_4 = (int16_t)_IQtoIQ15(pDacData->value[3]); -+ -+ // write the DAC data -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_1],dacValue_1); -+ PWMDAC_write_CmpB(obj->pwmDacHandle[PWMDAC_Number_1],dacValue_2); -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_2],dacValue_3); -+ PWMDAC_write_CmpB(obj->pwmDacHandle[PWMDAC_Number_2],dacValue_4); -+ -+ return; -+ } // end of HAL_writeDacData() function -+ -+ -+ //! \brief Writes PWM data to the PWM comparators for motor control -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pPwmData The pointer to the PWM data -+ static inline void HAL_writePwmData(HAL_Handle handle,HAL_PwmData_t *pPwmData) -+ { -+ uint_least8_t cnt; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ PWM_Obj *pwm; -+ _iq period; -+ _iq pwmData_neg; -+ _iq pwmData_sat; -+ _iq pwmData_sat_dc; -+ _iq value; -+ uint16_t value_sat; -+ -+ for(cnt=0;cnt<3;cnt++) -+ { -+ pwm = (PWM_Obj *)obj->pwmHandle[cnt]; -+ period = (_iq)pwm->TBPRD; -+ pwmData_neg = _IQmpy(pPwmData->Tabc.value[cnt],_IQ(-1.0)); -+ pwmData_sat = _IQsat(pwmData_neg,_IQ(0.5),_IQ(-0.5)); -+ pwmData_sat_dc = pwmData_sat + _IQ(0.5); -+ value = _IQmpy(pwmData_sat_dc, period); -+ value_sat = (uint16_t)_IQsat(value, period, _IQ(0.0)); -+ -+ // write the PWM data -+ PWM_write_CmpA(obj->pwmHandle[cnt],value_sat); -+ } -+ -+ return; -+ } // end of HAL_writePwmData() function -+ -+ -+ //! \brief Reads PWM compare register A -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpA(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpA(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpA() function -+ -+ -+ //! \brief Reads PWM compare mirror register A -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpAM(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpAM(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpAM() function -+ -+ -+ //! \brief Reads PWM compare register B -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpB(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpB(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpB() function -+ -+ -+ //! \brief Reads PWM period register -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM period value -+ static inline uint16_t HAL_readPwmPeriod(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the period value to be returned -+ uint16_t pwmPeriodValue; -+ -+ pwmPeriodValue = PWM_getPeriod(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmPeriodValue); -+ } // end of HAL_readPwmPeriod() function -+ -+ -+ static inline void HAL_setTrigger(HAL_Handle handle,const SVGENCURRENT_IgnoreShunt_e ignoreShunt,const int16_t minwidth, const int16_t cmpOffset) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ PWM_Obj *pwm1 = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ PWM_Obj *pwm2 = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ PWM_Obj *pwm3 = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ PWM_Obj *pwm; -+ -+ uint16_t nextPulse1 = (pwm1->CMPA + pwm1->CMPAM) / 2; -+ uint16_t nextPulse2 = (pwm2->CMPA + pwm2->CMPAM) / 2; -+ uint16_t nextPulse3 = (pwm3->CMPA + pwm3->CMPAM) / 2; -+ uint16_t pwmCMPA1 = pwm1->CMPA; -+ uint16_t pwmCMPA2 = pwm2->CMPA; -+ uint16_t pwmCMPA3 = pwm3->CMPA; -+ -+ int16_t offset; -+ -+ if(ignoreShunt == use_all) -+ { -+ if((nextPulse1 <= nextPulse2) && (nextPulse1 <= nextPulse3)) -+ { -+ pwm = pwm1; -+ } -+ else if((nextPulse2 <= nextPulse1) && (nextPulse2 <= nextPulse3)) -+ { -+ pwm = pwm2; -+ } -+ else -+ { -+ pwm = pwm3; -+ } -+ } -+ else if(ignoreShunt == ignore_a) -+ { -+ offset = pwmCMPA1 + cmpOffset; -+ } -+ else if(ignoreShunt == ignore_b) -+ { -+ offset = pwmCMPA2 + cmpOffset; -+ } -+ else if(ignoreShunt == ignore_c) -+ { -+ offset = pwmCMPA3 + cmpOffset; -+ } -+ else if(ignoreShunt == ignore_ab) -+ { -+ if(pwmCMPA1 > pwmCMPA2) -+ { -+ offset = pwmCMPA1 + cmpOffset; -+ } -+ else -+ { -+ offset = pwmCMPA2 + cmpOffset; -+ } -+ } -+ else if(ignoreShunt == ignore_ac) -+ { -+ if(pwmCMPA1 > pwmCMPA3) -+ { -+ offset = pwmCMPA1 + cmpOffset; -+ } -+ else -+ { -+ offset = pwmCMPA3 + cmpOffset; -+ } -+ } -+ else // when ignoreShunt == ignore_bc -+ { -+ if(pwmCMPA2 > pwmCMPA3) -+ { -+ offset = pwmCMPA2 + cmpOffset; -+ } -+ else -+ { -+ offset = pwmCMPA3 + cmpOffset; -+ } -+ } -+ -+ -+ if(ignoreShunt == use_all) -+ { -+ if(pwm->CMPAM >= (pwm->CMPA + pwm->DBFED)) -+ { -+ pwm1->CMPB = (pwm->CMPAM - (pwm->CMPA + pwm->DBFED)) / 2 + 1; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBDecr); -+ } -+ else -+ { -+ pwm1->CMPB = ((pwm->CMPA + pwm->DBFED) - pwm->CMPAM ) / 2 + 1; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBIncr); -+ } -+ } -+ else -+ { -+ pwm1->CMPB = offset; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBIncr); -+ } -+ -+ return; -+ } // end of HAL_setTrigger() function -+ -+ #ifdef QEP -+ //! \brief Returns the current position count from QEP -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return the current position count from QEP -+ static inline uint32_t HAL_getQepPosnCounts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ #ifdef J5 -+ QEP_Obj *qep = (QEP_Obj *)obj->qepHandle[1]; -+ #else -+ QEP_Obj *qep = (QEP_Obj *)obj->qepHandle[0]; -+ #endif -+ -+ return qep->QPOSCNT; -+ } -+ -+ -+ //! \brief Returns the maximum position count from QEP -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return the maximum position count from QEP -+ static inline uint32_t HAL_getQepPosnMaximum(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ #ifdef J5 -+ QEP_Obj *qep = (QEP_Obj *)obj->qepHandle[1]; -+ #else -+ QEP_Obj *qep = (QEP_Obj *)obj->qepHandle[0]; -+ #endif -+ -+ return qep->QPOSMAX; -+ } -+ #endif -+ -+ //! \brief Selects the analog channel used for calibration -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] chanNumber The channel number -+ void HAL_AdcCalChanSelect(HAL_Handle handle, const ADC_SocChanNumber_e chanNumber); -+ -+ -+ //! \brief Reads the converted value from the selected calibration channel -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The converted value -+ uint16_t HAL_AdcCalConversion(HAL_Handle handle); -+ -+ -+ //! \brief Executes the offset calibration of the ADC -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_AdcOffsetSelfCal(HAL_Handle handle); -+ -+ -+ //! \brief Converts coarse and fine oscillator trim values into a single 16bit word value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] coarse The coarse trim portion of the oscillator trim -+ //! \param[in] fine The fine trim portion of the oscillator trim -+ //! \return The combined trim value -+ uint16_t HAL_getOscTrimValue(int16_t coarse, int16_t fine); -+ -+ -+ //! \brief Executes the oscillator 1 and 2 calibration functions -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_OscTempComp(HAL_Handle handle); -+ -+ -+ //! \brief Executes the oscillator 1 calibration based on input sample -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_osc1Comp(HAL_Handle handle, const int16_t sensorSample); -+ -+ -+ //! \brief Executes the oscillator 2 calibration based on input sample -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_osc2Comp(HAL_Handle handle, const int16_t sensorSample); -+ -+ //! \brief Sets up the McBSPA for the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupMcBSPA(HAL_Handle handle); -+ -+ //! \brief Sets up the DMA for the driver -+ // do not forget, that the memory regions addressed by the DMA have to -+ // be put to the appropriate addresses by calling -+ // #pragma DATA_SECTION(, "DMARAML5") -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupDMA(HAL_Handle handle); -+ -+ //! \brief Calculates the Offset Value for the DcBus - Current Sensor -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gAdcData The data structure holding the ADC-data values -+ void HAL_calculateOffsetDCBusCurrent(HAL_Handle handle, HAL_AdcData_t * gAdcData); -+ -+ //! \brief returns the state of the Calibration for the DC-Bus Current Offset -+ //! \return dcBusCurrentOffsetCalibrationDone -+ bool HAL_getDCbusCurrentOffsetCalibrationDone(); -+ -+ //! \brief Gives the calculated DC-Bus Current Offset -+ //! \return DC-Bus Current Offset if HAL_getOffsetDCBusCurrent() - funtion has -+ // already been called before -+ //! \return -9999.0 otherwise -+ float HAL_getDCbusCurrentOffset(); -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_H_ definition -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.c -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.c 2017-06-08 10:41:26.595348300 +0200 -*************** -*** 0 **** ---- 1,1745 ---- -+ /* --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/boards/drv8301kit_revD/f28x/f2806xF/src/hal.c -+ //! \brief Contains the various functions related to the HAL object (everything outside the CTRL system) -+ //! -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // drivers -+ -+ // modules -+ -+ // platforms -+ #include "hal_2mtr.h" -+ #include "hal_obj_2mtr.h" -+ #include "user1.h" -+ #include "user2.h" -+ -+ -+ #ifdef FLASH -+ #pragma CODE_SECTION(HAL_setupFlash,"ramfuncs"); -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ //HAL_Obj hal; -+ -+ -+ // ************************************************************************** -+ // the functions -+ -+ void HAL_cal(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable the ADC clock -+ CLK_enableAdcClock(obj->clkHandle); -+ -+ -+ // Run the Device_cal() function -+ // This function copies the ADC and oscillator calibration values from TI reserved -+ // OTP into the appropriate trim registers -+ // This boot ROM automatically calls this function to calibrate the interal -+ // oscillators and ADC with device specific calibration data. -+ // If the boot ROM is bypassed by Code Composer Studio during the development process, -+ // then the calibration must be initialized by the application -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ (*Device_cal)(); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ // run offsets calibration in user's memory -+ HAL_AdcOffsetSelfCal(handle); -+ -+ // run oscillator compensation -+ HAL_OscTempComp(handle); -+ -+ // disable the ADC clock -+ CLK_disableAdcClock(obj->clkHandle); -+ -+ return; -+ } // end of HAL_cal() function -+ -+ -+ void HAL_OscTempComp(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t Temperature; -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ // enable non-overlap mode -+ ADC_enableNoOverlapMode(obj->adcHandle); -+ -+ // connect channel A5 internally to the temperature sensor -+ ADC_setTempSensorSrc(obj->adcHandle, ADC_TempSensorSrc_Int); -+ -+ // set SOC0 channel select to ADCINA5 -+ ADC_setSocChanNumber(obj->adcHandle, ADC_SocNumber_0, ADC_SocChanNumber_A5); -+ -+ // set SOC0 acquisition period to 26 ADCCLK -+ ADC_setSocSampleDelay(obj->adcHandle, ADC_SocNumber_0, ADC_SocSampleDelay_64_cycles); -+ -+ // connect ADCINT1 to EOC0 -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_1, ADC_IntSrc_EOC0); -+ -+ // clear ADCINT1 flag -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ // enable ADCINT1 -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_1); -+ -+ // force start of conversion on SOC0 -+ ADC_setSocFrc(obj->adcHandle, ADC_SocFrc_0); -+ -+ // wait for end of conversion -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_1) == 0){} -+ -+ // clear ADCINT1 flag -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ Temperature = ADC_readResult(obj->adcHandle, ADC_ResultNumber_0); -+ -+ HAL_osc1Comp(handle, Temperature); -+ -+ HAL_osc2Comp(handle, Temperature); -+ -+ return; -+ } // end of HAL_OscTempComp() function -+ -+ -+ void HAL_osc1Comp(HAL_Handle handle, const int16_t sensorSample) -+ { -+ int16_t compOscFineTrim; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ compOscFineTrim = ((sensorSample - getRefTempOffset())*(int32_t)getOsc1FineTrimSlope() -+ + OSC_POSTRIM_OFF + FP_ROUND )/FP_SCALE + getOsc1FineTrimOffset() - OSC_POSTRIM; -+ -+ if(compOscFineTrim > 31) -+ { -+ compOscFineTrim = 31; -+ } -+ else if(compOscFineTrim < -31) -+ { -+ compOscFineTrim = -31; -+ } -+ -+ OSC_setTrim(obj->oscHandle, OSC_Number_1, HAL_getOscTrimValue(getOsc1CoarseTrim(), compOscFineTrim)); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_osc1Comp() function -+ -+ -+ void HAL_osc2Comp(HAL_Handle handle, const int16_t sensorSample) -+ { -+ int16_t compOscFineTrim; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ compOscFineTrim = ((sensorSample - getRefTempOffset())*(int32_t)getOsc2FineTrimSlope() -+ + OSC_POSTRIM_OFF + FP_ROUND )/FP_SCALE + getOsc2FineTrimOffset() - OSC_POSTRIM; -+ -+ if(compOscFineTrim > 31) -+ { -+ compOscFineTrim = 31; -+ } -+ else if(compOscFineTrim < -31) -+ { -+ compOscFineTrim = -31; -+ } -+ -+ OSC_setTrim(obj->oscHandle, OSC_Number_2, HAL_getOscTrimValue(getOsc2CoarseTrim(), compOscFineTrim)); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_osc2Comp() function -+ -+ -+ uint16_t HAL_getOscTrimValue(int16_t coarse, int16_t fine) -+ { -+ uint16_t regValue = 0; -+ -+ if(fine < 0) -+ { -+ regValue = ((-fine) | 0x20) << 9; -+ } -+ else -+ { -+ regValue = fine << 9; -+ } -+ -+ if(coarse < 0) -+ { -+ regValue |= ((-coarse) | 0x80); -+ } -+ else -+ { -+ regValue |= coarse; -+ } -+ -+ return regValue; -+ } // end of HAL_getOscTrimValue() function -+ -+ -+ void HAL_AdcOffsetSelfCal(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t AdcConvMean; -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ //Select VREFLO internal connection on B5 -+ ADC_enableVoltRefLoConv(obj->adcHandle); -+ -+ //Select channel B5 for all SOC -+ HAL_AdcCalChanSelect(handle, ADC_SocChanNumber_B5); -+ -+ //Apply artificial offset (+80) to account for a negative offset that may reside in the ADC core -+ ADC_setOffTrim(obj->adcHandle, 80); -+ -+ //Capture ADC conversion on VREFLO -+ AdcConvMean = HAL_AdcCalConversion(handle); -+ -+ //Set offtrim register with new value (i.e remove artical offset (+80) and create a two's compliment of the offset error) -+ ADC_setOffTrim(obj->adcHandle, 80 - AdcConvMean); -+ -+ //Select external ADCIN5 input pin on B5 -+ ADC_disableVoltRefLoConv(obj->adcHandle); -+ -+ return; -+ } // end of HAL_AdcOffsetSelfCal() function -+ -+ -+ void HAL_AdcCalChanSelect(HAL_Handle handle, const ADC_SocChanNumber_e chanNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_0,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_1,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_2,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_3,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_4,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_5,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_6,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_7,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_8,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_9,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_10,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_11,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_12,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_13,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_14,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_15,chanNumber); -+ -+ return; -+ } // end of HAL_AdcCalChanSelect() function -+ -+ -+ uint16_t HAL_AdcCalConversion(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t index, SampleSize, Mean; -+ uint32_t Sum; -+ ADC_SocSampleDelay_e ACQPS_Value; -+ -+ index = 0; //initialize index to 0 -+ SampleSize = 256; //set sample size to 256 (**NOTE: Sample size must be multiples of 2^x where is an integer >= 4) -+ Sum = 0; //set sum to 0 -+ Mean = 999; //initialize mean to known value -+ -+ //Set the ADC sample window to the desired value (Sample window = ACQPS + 1) -+ ACQPS_Value = ADC_SocSampleDelay_7_cycles; -+ -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_0,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_1,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_2,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_3,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_4,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_5,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_6,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_7,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_8,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_9,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_10,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_11,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_12,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_13,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_14,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_15,ACQPS_Value); -+ -+ // Enabled ADCINT1 and ADCINT2 -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_1); -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_2); -+ -+ // Disable continuous sampling for ADCINT1 and ADCINT2 -+ ADC_setIntMode(obj->adcHandle, ADC_IntNumber_1, ADC_IntMode_EOC); -+ ADC_setIntMode(obj->adcHandle, ADC_IntNumber_2, ADC_IntMode_EOC); -+ -+ //ADCINTs trigger at end of conversion -+ ADC_setIntPulseGenMode(obj->adcHandle, ADC_IntPulseGenMode_Prior); -+ -+ // Setup ADCINT1 and ADCINT2 trigger source -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_1, ADC_IntSrc_EOC6); -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_2, ADC_IntSrc_EOC14); -+ -+ // Setup each SOC's ADCINT trigger source -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_0, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_1, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_2, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_3, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_4, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_5, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_6, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_7, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_8, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_9, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_10, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_11, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_12, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_13, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_14, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_15, ADC_Int1TriggersSOC); -+ -+ // Delay before converting ADC channels -+ usDelay(ADC_DELAY_usec); -+ -+ ADC_setSocFrcWord(obj->adcHandle, 0x00FF); -+ -+ while( index < SampleSize ) -+ { -+ //Wait for ADCINT1 to trigger, then add ADCRESULT0-7 registers to sum -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_1) == 0){} -+ -+ //Must clear ADCINT1 flag since INT1CONT = 0 -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_0); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_1); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_2); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_3); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_4); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_5); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_6); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_7); -+ -+ //Wait for ADCINT2 to trigger, then add ADCRESULT8-15 registers to sum -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_2) == 0){} -+ -+ //Must clear ADCINT2 flag since INT2CONT = 0 -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_2); -+ -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_8); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_9); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_10); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_11); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_12); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_13); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_14); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_15); -+ -+ index+=16; -+ -+ } // end data collection -+ -+ //Disable ADCINT1 and ADCINT2 to STOP the ping-pong sampling -+ ADC_disableInt(obj->adcHandle, ADC_IntNumber_1); -+ ADC_disableInt(obj->adcHandle, ADC_IntNumber_2); -+ -+ //Calculate average ADC sample value -+ Mean = Sum / SampleSize; -+ -+ // Clear start of conversion trigger -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_0, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_1, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_2, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_3, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_4, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_5, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_6, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_7, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_8, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_9, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_10, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_11, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_12, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_13, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_14, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_15, ADC_NoIntTriggersSOC); -+ -+ //return the average -+ return(Mean); -+ } // end of HAL_AdcCalConversion() function -+ -+ -+ void HAL_disableWdog(HAL_Handle halHandle) -+ { -+ HAL_Obj *hal = (HAL_Obj *)halHandle; -+ -+ -+ WDOG_disable(hal->wdogHandle); -+ -+ -+ return; -+ } // end of HAL_disableWdog() function -+ -+ -+ void HAL_disableGlobalInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_disableGlobalInts(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_disableGlobalInts() function -+ -+ -+ void HAL_enableAdcInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable the PIE interrupts associated with the ADC interrupts -+ PIE_enableAdcInt(obj->pieHandle,ADC_IntNumber_1); -+ PIE_enableAdcInt(obj->pieHandle,ADC_IntNumber_2); -+ -+ -+ // enable the ADC interrupts -+ ADC_enableInt(obj->adcHandle,ADC_IntNumber_1); -+ ADC_enableInt(obj->adcHandle,ADC_IntNumber_2); -+ -+ -+ // enable the cpu interrupt for ADC interrupts -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_10); -+ -+ return; -+ } // end of HAL_enableAdcInts() function -+ -+ -+ void HAL_enableDebugInt(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_enableDebugInt(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_enableDebugInt() function -+ -+ -+ void HAL_enableDrv(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ DRV8301_enable(obj->drv8301Handle); -+ -+ return; -+ } // end of HAL_enableDrv() function -+ -+ -+ void HAL_enableGlobalInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_enableGlobalInts(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_enableGlobalInts() function -+ -+ -+ void HAL_enablePwmInt(HAL_Handle_mtr handleMtr,HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ HAL_MtrSelect_e mtrNum = objMtr->mtrNum; -+ -+ if(mtrNum == HAL_MTR1) -+ { -+ PIE_enablePwmInt(obj->pieHandle,PWM_Number_4); -+ } -+ else if(mtrNum == HAL_MTR2) -+ { -+ PIE_enablePwmInt(obj->pieHandle,PWM_Number_1); -+ } -+ -+ -+ // enable the interrupt -+ PWM_enableInt(objMtr->pwmHandle[0]); -+ -+ -+ // enable the cpu interrupt for EPWMx_INT -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_3); -+ -+ return; -+ } // end of HAL_enablePwmInt() function -+ -+ -+ void HAL_enableTimer0Int(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_enableTimer0Int(obj->pieHandle); -+ -+ -+ // enable the interrupt -+ TIMER_enableInt(obj->timerHandle[0]); -+ -+ -+ // enable the cpu interrupt for TINT0 -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_1); -+ -+ return; -+ } // end of HAL_enablePwmInt() function -+ -+ -+ void HAL_setupFaults(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ uint_least8_t cnt; -+ -+ -+ // Configure Trip Mechanism for the Motor control software -+ // -Cycle by cycle trip on CPU halt -+ // -One shot fault trip zone -+ // These trips need to be repeated for EPWM1 ,2 & 3 -+ for(cnt=0;cnt<3;cnt++) -+ { -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ6_NOT); -+ -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ3_NOT); -+ -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ2_NOT); -+ -+ // What do we want the OST/CBC events to do? -+ // TZA events can force EPWMxA -+ // TZB events can force EPWMxB -+ -+ PWM_setTripZoneState_TZA(obj->pwmHandle[cnt],PWM_TripZoneState_EPWM_Low); -+ PWM_setTripZoneState_TZB(obj->pwmHandle[cnt],PWM_TripZoneState_EPWM_Low); -+ } -+ -+ return; -+ } // end of HAL_setupFaults() function -+ -+ -+ HAL_Handle HAL_init(void *pMemory,const size_t numBytes) -+ { -+ HAL_Handle handle; -+ HAL_Obj *obj; -+ -+ -+ if(numBytes < sizeof(HAL_Obj)) -+ return((HAL_Handle)NULL); -+ -+ -+ // assign the handle -+ handle = (HAL_Handle)pMemory; -+ -+ -+ // assign the object -+ obj = (HAL_Obj *)handle; -+ -+ -+ // initialize the watchdog driver -+ obj->wdogHandle = WDOG_init((void *)WDOG_BASE_ADDR,sizeof(WDOG_Obj)); -+ -+ -+ // disable watchdog -+ HAL_disableWdog(handle); -+ -+ -+ // initialize the ADC -+ obj->adcHandle = ADC_init((void *)ADC_BASE_ADDR,sizeof(ADC_Obj)); -+ -+ -+ // initialize the clock handle -+ obj->clkHandle = CLK_init((void *)CLK_BASE_ADDR,sizeof(CLK_Obj)); -+ -+ -+ // initialize the CPU handle -+ obj->cpuHandle = CPU_init(&cpu,sizeof(cpu)); -+ -+ -+ // initialize the FLASH handle -+ obj->flashHandle = FLASH_init((void *)FLASH_BASE_ADDR,sizeof(FLASH_Obj)); -+ -+ -+ // initialize the GPIO handle -+ obj->gpioHandle = GPIO_init((void *)GPIO_BASE_ADDR,sizeof(GPIO_Obj)); -+ -+ -+ // initialize the oscillator handle -+ obj->oscHandle = OSC_init((void *)OSC_BASE_ADDR,sizeof(OSC_Obj)); -+ -+ -+ // initialize the PIE handle -+ obj->pieHandle = PIE_init((void *)PIE_BASE_ADDR,sizeof(PIE_Obj)); -+ -+ -+ // initialize the PLL handle -+ obj->pllHandle = PLL_init((void *)PLL_BASE_ADDR,sizeof(PLL_Obj)); -+ -+ -+ // initialize the SPI handles -+ obj->spiAHandle = SPI_init((void *)SPIA_BASE_ADDR,sizeof(SPI_Obj)); -+ obj->spiBHandle = SPI_init((void *)SPIB_BASE_ADDR,sizeof(SPI_Obj)); -+ -+ -+ // initialize PWM DAC handles -+ obj->pwmDacHandle[0] = PWMDAC_init((void *)PWM_ePWM7_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmDacHandle[1] = PWMDAC_init((void *)PWM_ePWM8_BASE_ADDR,sizeof(PWM_Obj)); -+ -+ -+ // initialize power handle -+ obj->pwrHandle = PWR_init((void *)PWR_BASE_ADDR,sizeof(PWR_Obj)); -+ -+ -+ // initialize timer handles -+ obj->timerHandle[0] = TIMER_init((void *)TIMER0_BASE_ADDR,sizeof(TIMER_Obj)); -+ obj->timerHandle[1] = TIMER_init((void *)TIMER1_BASE_ADDR,sizeof(TIMER_Obj)); -+ obj->timerHandle[2] = TIMER_init((void *)TIMER2_BASE_ADDR,sizeof(TIMER_Obj)); -+ -+ -+ return(handle); -+ } // end of HAL_init() function -+ -+ -+ HAL_Handle_mtr HAL_init_mtr(void *pMemory,const size_t numBytes,const HAL_MtrSelect_e mtrNum) -+ { -+ HAL_Handle_mtr handle; -+ HAL_Obj_mtr *obj; -+ -+ if(numBytes < sizeof(HAL_Obj_mtr)) -+ return((HAL_Handle_mtr)NULL); -+ -+ // assign the handle -+ handle = (HAL_Handle_mtr)pMemory; -+ -+ // point to the object -+ obj = (HAL_Obj_mtr *)handle; -+ -+ HAL_setMotorNumber(handle,mtrNum); -+ -+ // initialize PWM handles -+ if(mtrNum == HAL_MTR1) -+ { -+ obj->pwmHandle[0] = PWM_init((void *)PWM_ePWM1_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[1] = PWM_init((void *)PWM_ePWM2_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[2] = PWM_init((void *)PWM_ePWM3_BASE_ADDR,sizeof(PWM_Obj)); -+ } -+ else if(mtrNum == HAL_MTR2) -+ { -+ obj->pwmHandle[0] = PWM_init((void *)PWM_ePWM4_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[1] = PWM_init((void *)PWM_ePWM5_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[2] = PWM_init((void *)PWM_ePWM6_BASE_ADDR,sizeof(PWM_Obj)); -+ } -+ else -+ { -+ obj->pwmHandle[0] = NULL; -+ obj->pwmHandle[1] = NULL; -+ obj->pwmHandle[2] = NULL; -+ } -+ -+ // initialize drv8301 interface -+ obj->drv8301Handle = DRV8301_init(&obj->drv8301,sizeof(obj->drv8301)); -+ -+ // initialize QEP driver -+ #ifdef QEP -+ if(mtrNum == HAL_MTR1) -+ { -+ obj->qepHandle = QEP_init((void*)QEP1_BASE_ADDR,sizeof(QEP_Obj)); -+ } -+ else if(mtrNum == HAL_MTR2) -+ { -+ obj->qepHandle = QEP_init((void*)QEP2_BASE_ADDR,sizeof(QEP_Obj)); -+ } -+ else -+ { -+ obj->qepHandle = NULL; -+ } -+ #endif -+ -+ return(handle); -+ } -+ -+ void HAL_setParams(HAL_Handle handle,const USER_Params *pUserParams) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // disable global interrupts -+ CPU_disableGlobalInts(obj->cpuHandle); -+ -+ -+ // disable cpu interrupts -+ CPU_disableInts(obj->cpuHandle); -+ -+ -+ // clear cpu interrupt flags -+ CPU_clearIntFlags(obj->cpuHandle); -+ -+ -+ // setup the clocks -+ HAL_setupClks(handle); -+ -+ -+ // Setup the PLL -+ HAL_setupPll(handle,PLL_ClkFreq_90_MHz); -+ -+ -+ // setup the PIE -+ HAL_setupPie(handle); -+ -+ -+ // run the device calibration -+ HAL_cal(handle); -+ -+ -+ // setup the peripheral clocks -+ HAL_setupPeripheralClks(handle); -+ -+ -+ // setup the GPIOs -+ HAL_setupGpios(handle); -+ -+ -+ // setup the flash -+ HAL_setupFlash(handle); -+ -+ -+ // setup the ADCs -+ HAL_setupAdcs(handle); -+ -+ -+ // setup the spiA -+ HAL_setupSpiA(handle); -+ -+ -+ // setup the spiB -+ HAL_setupSpiB(handle); -+ -+ -+ // setup the PWM DACs -+ HAL_setupPwmDacs(handle); -+ -+ -+ // setup the timers -+ HAL_setupTimers(handle, -+ (float_t)pUserParams->systemFreq_MHz); -+ -+ -+ return; -+ } // end of HAL_setParams() function -+ -+ -+ void HAL_setParamsMtr(HAL_Handle_mtr handleMtr,HAL_Handle handle,const USER_Params *pUserParams) -+ { -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // setup the PWMs -+ HAL_setupPwms(handleMtr,handle,pUserParams); -+ -+ -+ // setup the drv8301 interface -+ if(objMtr->mtrNum == HAL_MTR1) -+ { -+ DRV8301_setGpioHandle(objMtr->drv8301Handle,obj->gpioHandle); -+ DRV8301_setSpiHandle(objMtr->drv8301Handle,obj->spiAHandle); -+ DRV8301_setGpioNumber(objMtr->drv8301Handle,GPIO_Number_50); -+ } -+ else if(objMtr->mtrNum == HAL_MTR2) -+ { -+ DRV8301_setGpioHandle(objMtr->drv8301Handle,obj->gpioHandle); -+ DRV8301_setSpiHandle(objMtr->drv8301Handle,obj->spiBHandle); -+ DRV8301_setGpioNumber(objMtr->drv8301Handle,GPIO_Number_52); -+ } -+ -+ // set the current scale factor -+ { -+ _iq current_sf = _IQ(pUserParams->current_sf); -+ -+ HAL_setCurrentScaleFactor(handleMtr,current_sf); -+ } -+ -+ -+ // set the voltage scale factor -+ { -+ _iq voltage_sf = _IQ(pUserParams->voltage_sf); -+ -+ HAL_setVoltageScaleFactor(handleMtr,voltage_sf); -+ } -+ -+ -+ #ifdef QEP -+ // setup the QEP -+ if(objMtr->mtrNum == HAL_MTR1) -+ { -+ HAL_setupQEP(handleMtr, USER_MOTOR_ENCODER_LINES); -+ } -+ else if(objMtr->mtrNum == HAL_MTR2) -+ { -+ HAL_setupQEP(handleMtr, USER_MOTOR_ENCODER_LINES_2); -+ } -+ #endif -+ -+ -+ return; -+ }// end of HAL_setParamsMtr() function -+ -+ -+ void HAL_setupAdcs(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ -+ // set the ADC interrupt pulse generation to prior -+ ADC_setIntPulseGenMode(obj->adcHandle,ADC_IntPulseGenMode_Prior); -+ -+ -+ // set the temperature sensor source to external -+ ADC_setTempSensorSrc(obj->adcHandle,ADC_TempSensorSrc_Ext); -+ -+ -+ // configure the interrupt sources -+ ADC_disableInt(obj->adcHandle,ADC_IntNumber_1); -+ ADC_setIntMode(obj->adcHandle,ADC_IntNumber_1,ADC_IntMode_ClearFlag); -+ ADC_setIntSrc(obj->adcHandle,ADC_IntNumber_1,ADC_IntSrc_EOC7); -+ -+ ADC_disableInt(obj->adcHandle,ADC_IntNumber_2); -+ ADC_setIntMode(obj->adcHandle,ADC_IntNumber_2,ADC_IntMode_ClearFlag); -+ ADC_setIntSrc(obj->adcHandle,ADC_IntNumber_2,ADC_IntSrc_EOC14); -+ -+ -+ -+ //configure the SOCs for boostxldrv8301_revB on J1 Connection -+ // Begin Motor 1 sampling -+ // EXT IA-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_0,ADC_SocChanNumber_A0); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_0,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_0,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IA-FB -+ // Duplicate conversion due to ADC Initial Conversion bug (SPRZ342) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_1,ADC_SocChanNumber_A0); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_1,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_1,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IB-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_2,ADC_SocChanNumber_B0); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_2,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_2,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IC-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_3,ADC_SocChanNumber_A1); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_3,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_3,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb1 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_4,ADC_SocChanNumber_B1); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_4,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_4,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb2 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_5,ADC_SocChanNumber_A2); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_5,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_5,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb3 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_6,ADC_SocChanNumber_B2); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_6,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_6,ADC_SocSampleDelay_9_cycles); -+ -+ // VDCBUS -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_7,ADC_SocChanNumber_A7); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_7,ADC_SocTrigSrc_EPWM1_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_7,ADC_SocSampleDelay_9_cycles); -+ // End Motor 1 sampling -+ -+ // Begin Motor 2 sampling -+ // EXT IA-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_8,ADC_SocChanNumber_A3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_8,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_8,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IB-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_9,ADC_SocChanNumber_B3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_9,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_9,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IC-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_10,ADC_SocChanNumber_A4); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_10,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_10,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb1 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_11,ADC_SocChanNumber_B4); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_11,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_11,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb2 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_12,ADC_SocChanNumber_A5); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_12,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_12,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb3 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_13,ADC_SocChanNumber_B5); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_13,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_13,ADC_SocSampleDelay_9_cycles); -+ -+ // VDCBUS -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_14,ADC_SocChanNumber_B7); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_14,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_14,ADC_SocSampleDelay_9_cycles); -+ // End Motor 2 sampling -+ -+ -+ return; -+ } // end of HAL_setupAdcs() function -+ -+ -+ void HAL_setupClks(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable internal oscillator 1 -+ CLK_enableOsc1(obj->clkHandle); -+ -+ // set the oscillator source -+ CLK_setOscSrc(obj->clkHandle,CLK_OscSrc_Internal); -+ -+ // disable the external clock in -+ CLK_disableClkIn(obj->clkHandle); -+ -+ // disable the crystal oscillator -+ CLK_disableCrystalOsc(obj->clkHandle); -+ -+ // disable oscillator 2 -+ CLK_disableOsc2(obj->clkHandle); -+ -+ // set the low speed clock prescaler -+ CLK_setLowSpdPreScaler(obj->clkHandle,CLK_LowSpdPreScaler_SysClkOut_by_1); -+ -+ // set the clock out prescaler -+ CLK_setClkOutPreScaler(obj->clkHandle,CLK_ClkOutPreScaler_SysClkOut_by_1); -+ -+ return; -+ } // end of HAL_setupClks() function -+ -+ -+ void HAL_setupFlash(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ FLASH_enablePipelineMode(obj->flashHandle); -+ -+ FLASH_setNumPagedReadWaitStates(obj->flashHandle,FLASH_NumPagedWaitStates_3); -+ -+ FLASH_setNumRandomReadWaitStates(obj->flashHandle,FLASH_NumRandomWaitStates_3); -+ -+ FLASH_setOtpWaitStates(obj->flashHandle,FLASH_NumOtpWaitStates_5); -+ -+ FLASH_setStandbyWaitCount(obj->flashHandle,FLASH_STANDBY_WAIT_COUNT_DEFAULT); -+ -+ FLASH_setActiveWaitCount(obj->flashHandle,FLASH_ACTIVE_WAIT_COUNT_DEFAULT); -+ -+ return; -+ } // HAL_setupFlash() function -+ -+ -+ void HAL_setupGate(HAL_Handle_mtr handleMtr,SPI_Handle handleSpi,GPIO_Handle handleGpio,const GPIO_Number_e gpio) -+ { -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ -+ -+ DRV8301_setGpioHandle(objMtr->drv8301Handle,handleGpio); -+ DRV8301_setSpiHandle(objMtr->drv8301Handle,handleSpi); -+ DRV8301_setGpioNumber(objMtr->drv8301Handle,gpio); -+ -+ return; -+ } // HAL_setupGate() function -+ -+ -+ void HAL_setupGpios(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // PWM1 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_0,GPIO_0_Mode_EPWM1A); -+ -+ // PWM2 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_1,GPIO_1_Mode_EPWM1B); -+ -+ // PWM3 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_2,GPIO_2_Mode_EPWM2A); -+ -+ // PWM4 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_3,GPIO_3_Mode_EPWM2B); -+ -+ // PWM5 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_4,GPIO_4_Mode_EPWM3A); -+ -+ // PWM6 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_5,GPIO_5_Mode_EPWM3B); -+ -+ // PWM4A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_6,GPIO_6_Mode_EPWM4A); -+ -+ // PWM4B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_7,GPIO_7_Mode_EPWM4B); -+ -+ // PWM5A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_8,GPIO_8_Mode_EPWM5A); -+ -+ // PWM5B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_9,GPIO_9_Mode_EPWM5B); -+ -+ // PWM6A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_10,GPIO_10_Mode_EPWM6A); -+ -+ // PWM6B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_11,GPIO_11_Mode_EPWM6B); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_12,GPIO_12_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_12); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_12,GPIO_Direction_Output); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_13,GPIO_13_Mode_GeneralPurpose); -+ -+ // SPIB CLK -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_14,GPIO_14_Mode_SPICLKB); -+ -+ // UARTB RX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_15,GPIO_15_Mode_SCIRXDB); -+ -+ // Set Qualification Period for GPIO16-23, 22*2*(1/90MHz) = 0.48us -+ GPIO_setQualificationPeriod(obj->gpioHandle,GPIO_Number_16,22); -+ -+ // SPIA SIMO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_16,GPIO_16_Mode_SPISIMOA); -+ -+ // SPIA SOMI -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_17,GPIO_17_Mode_SPISOMIA); -+ -+ // SPIA CLK -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_18,GPIO_18_Mode_SPICLKA); -+ -+ // SPIA CS -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_19,GPIO_19_Mode_SPISTEA_NOT); -+ -+ #ifdef QEP -+ // EQEP1A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_20,GPIO_20_Mode_EQEP1A); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_20,GPIO_Qual_Sample_3); -+ -+ // EQEP1B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_21,GPIO_21_Mode_EQEP1B); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_21,GPIO_Qual_Sample_3); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_22,GPIO_22_Mode_GeneralPurpose); -+ -+ // EQEP1I -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_23,GPIO_23_Mode_EQEP1I); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_23,GPIO_Qual_Sample_3); -+ #else -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_20,GPIO_20_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_20); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_20,GPIO_Direction_Output); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_21,GPIO_21_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_22,GPIO_22_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_23,GPIO_23_Mode_GeneralPurpose); -+ #endif -+ -+ // SPIB SIMO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_24,GPIO_24_Mode_SPISIMOB); -+ -+ // SPIB SOMI -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_25,GPIO_25_Mode_SPISOMIB); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_26,GPIO_26_Mode_GeneralPurpose); -+ -+ // SPIB CS -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_27,GPIO_27_Mode_SPISTEB_NOT); -+ -+ // OCTWn -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_28,GPIO_28_Mode_TZ2_NOT); -+ -+ // FAULTn -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_29,GPIO_29_Mode_TZ3_NOT); -+ -+ // CAN RX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_30,GPIO_30_Mode_CANRXA); -+ -+ // CAN TX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_31,GPIO_31_Mode_CANTXA); -+ -+ // I2C Data -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_32,GPIO_32_Mode_SDAA); -+ -+ // I2C Clock -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_33,GPIO_33_Mode_SCLA); -+ -+ // LED D9 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_34,GPIO_34_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_34); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_34,GPIO_Direction_Output); -+ -+ // JTAG -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_35,GPIO_35_Mode_JTAG_TDI); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_36,GPIO_36_Mode_JTAG_TMS); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_37,GPIO_37_Mode_JTAG_TDO); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_38,GPIO_38_Mode_JTAG_TCK); -+ -+ // LED D10 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_39,GPIO_39_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_39); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_39,GPIO_Direction_Output); -+ -+ // DAC1 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_40,GPIO_40_Mode_EPWM7A); -+ -+ // DAC2 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_41,GPIO_41_Mode_EPWM7B); -+ -+ // DAC3 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_42,GPIO_42_Mode_EPWM8A); -+ -+ // DAC4 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_43,GPIO_43_Mode_EPWM8B); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_44,GPIO_44_Mode_GeneralPurpose); -+ -+ // Set Qualification Period for GPIO50-55, 22*2*(1/90MHz) = 0.48us -+ GPIO_setQualificationPeriod(obj->gpioHandle,GPIO_Number_50,22); -+ -+ // DRV8301 Enable Gate -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_50,GPIO_50_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_50); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_50,GPIO_Direction_Output); -+ -+ // DRV8301 DC Calibration -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_51,GPIO_51_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_51); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_51,GPIO_Direction_Output); -+ -+ // DRV8301 Enable Gate -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_52,GPIO_52_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_52); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_52,GPIO_Direction_Output); -+ -+ // DRV8301 Device Calibration -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_53,GPIO_53_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_53); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_53,GPIO_Direction_Output); -+ -+ // Set Qualification Period for GPIO56-58, 22*2*(1/90MHz) = 0.48us -+ GPIO_setQualificationPeriod(obj->gpioHandle,GPIO_Number_56,22); -+ -+ #ifdef QEP -+ // EQEP2A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_54,GPIO_54_Mode_EQEP2A); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_54,GPIO_Qual_Sample_3); -+ -+ // EQEP2B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_55,GPIO_55_Mode_EQEP2B); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_55,GPIO_Qual_Sample_3); -+ -+ // EQEP2I -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_56,GPIO_56_Mode_EQEP2I); -+ GPIO_setQualification(obj->gpioHandle,GPIO_Number_56,GPIO_Qual_Sample_3); -+ #else -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_54,GPIO_54_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_55,GPIO_55_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_56,GPIO_56_Mode_GeneralPurpose); -+ #endif -+ -+ // No Connection -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_57,GPIO_57_Mode_GeneralPurpose); -+ -+ // UARTB TX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_58,GPIO_58_Mode_SCITXDB); -+ -+ return; -+ } // end of HAL_setupGpios() function -+ -+ -+ void HAL_setupPie(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_disable(obj->pieHandle); -+ -+ PIE_disableAllInts(obj->pieHandle); -+ -+ PIE_clearAllInts(obj->pieHandle); -+ -+ PIE_clearAllFlags(obj->pieHandle); -+ -+ PIE_setDefaultIntVectorTable(obj->pieHandle); -+ -+ PIE_enable(obj->pieHandle); -+ -+ return; -+ } // end of HAL_setupPie() function -+ -+ -+ void HAL_setupPeripheralClks(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CLK_enableAdcClock(obj->clkHandle); -+ -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_1); -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_2); -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_3); -+ -+ CLK_disableEcap1Clock(obj->clkHandle); -+ -+ CLK_enableEcanaClock(obj->clkHandle); -+ -+ #ifdef QEP -+ CLK_enableEqep1Clock(obj->clkHandle); -+ CLK_enableEqep2Clock(obj->clkHandle); -+ #endif -+ -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_1); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_2); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_3); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_4); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_5); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_6); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_7); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_8); -+ -+ CLK_disableHrPwmClock(obj->clkHandle); -+ -+ CLK_enableI2cClock(obj->clkHandle); -+ -+ CLK_disableLinAClock(obj->clkHandle); -+ -+ CLK_disableClaClock(obj->clkHandle); -+ -+ CLK_disableSciaClock(obj->clkHandle); -+ CLK_enableScibClock(obj->clkHandle); -+ -+ CLK_enableSpiaClock(obj->clkHandle); -+ CLK_enableSpibClock(obj->clkHandle); -+ -+ CLK_enableTbClockSync(obj->clkHandle); -+ -+ return; -+ } // end of HAL_setupPeripheralClks() function -+ -+ -+ void HAL_setupPll(HAL_Handle handle,const PLL_ClkFreq_e clkFreq) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // make sure PLL is not running in limp mode -+ if(PLL_getClkStatus(obj->pllHandle) != PLL_ClkStatus_Normal) -+ { -+ // reset the clock detect -+ PLL_resetClkDetect(obj->pllHandle); -+ -+ // ??????? -+ asm(" ESTOP0"); -+ } -+ -+ -+ // Divide Select must be ClkIn/4 before the clock rate can be changed -+ if(PLL_getDivideSelect(obj->pllHandle) != PLL_DivideSelect_ClkIn_by_4) -+ { -+ PLL_setDivideSelect(obj->pllHandle,PLL_DivideSelect_ClkIn_by_4); -+ } -+ -+ -+ if(PLL_getClkFreq(obj->pllHandle) != clkFreq) -+ { -+ // disable the clock detect -+ PLL_disableClkDetect(obj->pllHandle); -+ -+ // set the clock rate -+ PLL_setClkFreq(obj->pllHandle,clkFreq); -+ } -+ -+ -+ // wait until locked -+ while(PLL_getLockStatus(obj->pllHandle) != PLL_LockStatus_Done) {} -+ -+ -+ // enable the clock detect -+ PLL_enableClkDetect(obj->pllHandle); -+ -+ -+ // set divide select to ClkIn/2 to get desired clock rate -+ // NOTE: clock must be locked before setting this register -+ PLL_setDivideSelect(obj->pllHandle,PLL_DivideSelect_ClkIn_by_2); -+ -+ return; -+ } // end of HAL_setupPll() function -+ -+ -+ void HAL_setupPwms(HAL_Handle_mtr handleMtr,HAL_Handle handle,const USER_Params *pUserParams) -+ { -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ float_t systemFreq_MHz = pUserParams->systemFreq_MHz; -+ uint_least16_t numPwmTicksPerIsrTick = pUserParams->numPwmTicksPerIsrTick; -+ uint16_t halfPeriod_cycles = (uint16_t)(systemFreq_MHz*(float_t)pUserParams->pwmPeriod_usec) >> 1; -+ uint_least8_t cnt; -+ -+ -+ // turns off the outputs of the EPWM peripherals which will put the power switches -+ // into a high impedance state. -+ PWM_setOneShotTrip(objMtr->pwmHandle[PWM_Number_1]); -+ PWM_setOneShotTrip(objMtr->pwmHandle[PWM_Number_2]); -+ PWM_setOneShotTrip(objMtr->pwmHandle[PWM_Number_3]); -+ -+ -+ for(cnt=0;cnt<3;cnt++) -+ { -+ // setup the Time-Base Control Register (TBCTL) -+ PWM_setCounterMode(objMtr->pwmHandle[cnt],PWM_CounterMode_UpDown); -+ PWM_disableCounterLoad(objMtr->pwmHandle[cnt]); // Disable phase syncronization -+ PWM_setPeriodLoad(objMtr->pwmHandle[cnt],PWM_PeriodLoad_Immediate); -+ PWM_setSyncMode(objMtr->pwmHandle[cnt],PWM_SyncMode_EPWMxSYNC); -+ PWM_setHighSpeedClkDiv(objMtr->pwmHandle[cnt],PWM_HspClkDiv_by_1); -+ PWM_setClkDiv(objMtr->pwmHandle[cnt],PWM_ClkDiv_by_1); -+ PWM_setRunMode(objMtr->pwmHandle[cnt],PWM_RunMode_FreeRun); -+ -+ // setup the Time-Base Counter Register (TBCTR) -+ PWM_setCount(objMtr->pwmHandle[cnt],0); -+ -+ // setup the Time-Base Period Register (TBPRD) -+ // set to zero initially -+ PWM_setPeriod(objMtr->pwmHandle[cnt],0); -+ -+ // setup the Timer-Based Phase Register (TBPHS) -+ PWM_setPhase(objMtr->pwmHandle[cnt],0); -+ PWM_setPhaseDir(objMtr->pwmHandle[cnt],PWM_PhaseDir_CountUp); -+ -+ // setup the Counter-Compare Control Register (CMPCTL) -+ PWM_setLoadMode_CmpA(objMtr->pwmHandle[cnt],PWM_LoadMode_Zero); -+ PWM_setLoadMode_CmpB(objMtr->pwmHandle[cnt],PWM_LoadMode_Zero); -+ PWM_setShadowMode_CmpA(objMtr->pwmHandle[cnt],PWM_ShadowMode_Shadow); -+ PWM_setShadowMode_CmpB(objMtr->pwmHandle[cnt],PWM_ShadowMode_Immediate); -+ -+ // setup the Action-Qualifier Output A Register (AQCTLA) -+ PWM_setActionQual_CntUp_CmpA_PwmA(objMtr->pwmHandle[cnt],PWM_ActionQual_Set); -+ PWM_setActionQual_CntDown_CmpA_PwmA(objMtr->pwmHandle[cnt],PWM_ActionQual_Clear); -+ -+ // setup the Dead-Band Generator Control Register (DBCTL) -+ PWM_setDeadBandOutputMode(objMtr->pwmHandle[cnt],PWM_DeadBandOutputMode_EPWMxA_Rising_EPWMxB_Falling); -+ PWM_setDeadBandPolarity(objMtr->pwmHandle[cnt],PWM_DeadBandPolarity_EPWMxB_Inverted); -+ -+ // setup the Dead-Band Rising Edge Delay Register (DBRED) -+ PWM_setDeadBandRisingEdgeDelay(objMtr->pwmHandle[cnt],HAL_PWM_DBRED_CNT); -+ -+ // setup the Dead-Band Falling Edge Delay Register (DBFED) -+ PWM_setDeadBandFallingEdgeDelay(objMtr->pwmHandle[cnt],HAL_PWM_DBFED_CNT); -+ // setup the PWM-Chopper Control Register (PCCTL) -+ PWM_disableChopping(objMtr->pwmHandle[cnt]); -+ -+ // setup the Trip Zone Select Register (TZSEL) -+ PWM_disableTripZones(objMtr->pwmHandle[cnt]); -+ } -+ -+ -+ // setup the Event Trigger Selection Register (ETSEL) -+ PWM_disableInt(objMtr->pwmHandle[PWM_Number_1]); -+ PWM_setSocAPulseSrc(objMtr->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualZero); -+ PWM_enableSocAPulse(objMtr->pwmHandle[PWM_Number_1]); -+ -+ // setup the Event Trigger Prescale Register (ETPS) -+ if(numPwmTicksPerIsrTick == 3) -+ { -+ PWM_setIntPeriod(objMtr->pwmHandle[PWM_Number_1],PWM_IntPeriod_ThirdEvent); -+ PWM_setSocAPeriod(objMtr->pwmHandle[PWM_Number_1],PWM_SocPeriod_ThirdEvent); -+ } -+ else if(numPwmTicksPerIsrTick == 2) -+ { -+ PWM_setIntPeriod(objMtr->pwmHandle[PWM_Number_1],PWM_IntPeriod_SecondEvent); -+ PWM_setSocAPeriod(objMtr->pwmHandle[PWM_Number_1],PWM_SocPeriod_SecondEvent); -+ } -+ else -+ { -+ PWM_setIntPeriod(objMtr->pwmHandle[PWM_Number_1],PWM_IntPeriod_FirstEvent); -+ PWM_setSocAPeriod(objMtr->pwmHandle[PWM_Number_1],PWM_SocPeriod_FirstEvent); -+ } -+ -+ -+ // setup the Event Trigger Clear Register (ETCLR) -+ PWM_clearIntFlag(objMtr->pwmHandle[PWM_Number_1]); -+ PWM_clearSocAFlag(objMtr->pwmHandle[PWM_Number_1]); -+ -+ // first step to synchronize the pwms -+ CLK_disableTbClockSync(obj->clkHandle); -+ -+ // since the PWM is configured as an up/down counter, the period register is set to one-half -+ // of the desired PWM period -+ PWM_setPeriod(objMtr->pwmHandle[PWM_Number_1],halfPeriod_cycles); -+ PWM_setPeriod(objMtr->pwmHandle[PWM_Number_2],halfPeriod_cycles); -+ PWM_setPeriod(objMtr->pwmHandle[PWM_Number_3],halfPeriod_cycles); -+ -+ // last step to synchronize the pwms -+ CLK_enableTbClockSync(obj->clkHandle); -+ -+ return; -+ } // end of HAL_setupPwms() function -+ -+ -+ -+ #ifdef QEP -+ void HAL_setupQEP(HAL_Handle_mtr handleMtr, float_t encoderLines) -+ { -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ -+ // hold the counter in reset -+ QEP_reset_counter(objMtr->qepHandle); -+ -+ // set the QPOSINIT register -+ QEP_set_posn_init_count(objMtr->qepHandle, 0); -+ -+ // disable all interrupts -+ QEP_disable_all_interrupts(objMtr->qepHandle); -+ -+ // clear the interrupt flags -+ QEP_clear_all_interrupt_flags(objMtr->qepHandle); -+ -+ // clear the position counter -+ QEP_clear_posn_counter(objMtr->qepHandle); -+ -+ // setup the max position -+ QEP_set_max_posn_count(objMtr->qepHandle, (uint16_t)((4.0 * encoderLines) - 1)); -+ -+ // setup the QDECCTL register -+ QEP_set_QEP_source(objMtr->qepHandle, QEP_Qsrc_Quad_Count_Mode); -+ QEP_disable_sync_out(objMtr->qepHandle); -+ QEP_set_swap_quad_inputs(objMtr->qepHandle, QEP_Swap_Not_Swapped); -+ QEP_disable_gate_index(objMtr->qepHandle); -+ QEP_set_ext_clock_rate(objMtr->qepHandle, QEP_Xcr_2x_Res); -+ QEP_set_A_polarity(objMtr->qepHandle, QEP_Qap_No_Effect); -+ QEP_set_B_polarity(objMtr->qepHandle, QEP_Qbp_No_Effect); -+ QEP_set_index_polarity(objMtr->qepHandle, QEP_Qip_No_Effect); -+ -+ // setup the QEPCTL register -+ QEP_set_emu_control(objMtr->qepHandle, QEPCTL_Freesoft_Unaffected_Halt); -+ QEP_set_posn_count_reset_mode(objMtr->qepHandle, QEPCTL_Pcrm_Max_Reset); -+ QEP_set_strobe_event_init(objMtr->qepHandle, QEPCTL_Sei_Nothing); -+ QEP_set_index_event_init(objMtr->qepHandle, QEPCTL_Iei_Nothing); -+ QEP_set_index_event_latch(objMtr->qepHandle, QEPCTL_Iel_Rising_Edge); -+ QEP_set_soft_init(objMtr->qepHandle, QEPCTL_Swi_Nothing); -+ QEP_disable_unit_timer(objMtr->qepHandle); -+ QEP_disable_watchdog(objMtr->qepHandle); -+ -+ // setup the QPOSCTL register -+ QEP_disable_posn_compare(objMtr->qepHandle); -+ -+ // setup the QCAPCTL register -+ QEP_disable_capture(objMtr->qepHandle); -+ -+ // renable the position counter -+ QEP_enable_counter(objMtr->qepHandle); -+ -+ -+ return; -+ } -+ #endif -+ -+ void HAL_setupSpiA(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ SPI_reset(obj->spiAHandle); -+ SPI_setMode(obj->spiAHandle,SPI_Mode_Master); -+ SPI_setClkPolarity(obj->spiAHandle,SPI_ClkPolarity_OutputRisingEdge_InputFallingEdge); -+ SPI_enableTx(obj->spiAHandle); -+ SPI_enableTxFifoEnh(obj->spiAHandle); -+ SPI_enableTxFifo(obj->spiAHandle); -+ SPI_setTxDelay(obj->spiAHandle,0x0018); -+ SPI_setBaudRate(obj->spiAHandle,(SPI_BaudRate_e)(0x000d)); -+ SPI_setCharLength(obj->spiAHandle,SPI_CharLength_16_Bits); -+ SPI_setSuspend(obj->spiAHandle,SPI_TxSuspend_free); -+ SPI_enable(obj->spiAHandle); -+ -+ return; -+ } // end of HAL_setupSpiA() function -+ -+ -+ void HAL_setupSpiB(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ SPI_reset(obj->spiBHandle); -+ SPI_setMode(obj->spiBHandle,SPI_Mode_Master); -+ SPI_setClkPolarity(obj->spiBHandle,SPI_ClkPolarity_OutputRisingEdge_InputFallingEdge); -+ SPI_enableTx(obj->spiBHandle); -+ SPI_enableTxFifoEnh(obj->spiBHandle); -+ SPI_enableTxFifo(obj->spiBHandle); -+ SPI_setTxDelay(obj->spiBHandle,0x0018); -+ SPI_setBaudRate(obj->spiBHandle,(SPI_BaudRate_e)(0x000d)); -+ SPI_setCharLength(obj->spiBHandle,SPI_CharLength_16_Bits); -+ SPI_setSuspend(obj->spiBHandle,SPI_TxSuspend_free); -+ SPI_enable(obj->spiBHandle); -+ -+ return; -+ } // end of HAL_setupSpiB() function -+ -+ -+ void HAL_setupPwmDacs(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t halfPeriod_cycles = 512; // 3000->10kHz, 1500->20kHz, 1000-> 30kHz, 500->60kHz -+ uint_least8_t cnt; -+ -+ -+ for(cnt=0;cnt<2;cnt++) -+ { -+ // initialize the Time-Base Control Register (TBCTL) -+ PWMDAC_setCounterMode(obj->pwmDacHandle[cnt],PWM_CounterMode_UpDown); -+ PWMDAC_disableCounterLoad(obj->pwmDacHandle[cnt]); -+ PWMDAC_setPeriodLoad(obj->pwmDacHandle[cnt],PWM_PeriodLoad_Immediate); -+ PWMDAC_setSyncMode(obj->pwmDacHandle[cnt],PWM_SyncMode_EPWMxSYNC); -+ PWMDAC_setHighSpeedClkDiv(obj->pwmDacHandle[cnt],PWM_HspClkDiv_by_1); -+ PWMDAC_setClkDiv(obj->pwmDacHandle[cnt],PWM_ClkDiv_by_1); -+ PWMDAC_setPhaseDir(obj->pwmDacHandle[cnt],PWM_PhaseDir_CountUp); -+ PWMDAC_setRunMode(obj->pwmDacHandle[cnt],PWM_RunMode_FreeRun); -+ -+ // initialize the Timer-Based Phase Register (TBPHS) -+ PWMDAC_setPhase(obj->pwmDacHandle[cnt],0); -+ -+ // setup the Time-Base Counter Register (TBCTR) -+ PWMDAC_setCount(obj->pwmDacHandle[cnt],0); -+ -+ // Initialize the Time-Base Period Register (TBPRD) -+ // set to zero initially -+ PWMDAC_setPeriod(obj->pwmDacHandle[cnt],0); -+ -+ // initialize the Counter-Compare Control Register (CMPCTL) -+ PWMDAC_setLoadMode_CmpA(obj->pwmDacHandle[cnt],PWM_LoadMode_Zero); -+ PWMDAC_setLoadMode_CmpB(obj->pwmDacHandle[cnt],PWM_LoadMode_Zero); -+ PWMDAC_setShadowMode_CmpA(obj->pwmDacHandle[cnt],PWM_ShadowMode_Shadow); -+ PWMDAC_setShadowMode_CmpB(obj->pwmDacHandle[cnt],PWM_ShadowMode_Shadow); -+ -+ // Initialize the Action-Qualifier Output A Register (AQCTLA) -+ PWMDAC_setActionQual_CntUp_CmpA_PwmA(obj->pwmDacHandle[cnt],PWM_ActionQual_Clear); -+ PWMDAC_setActionQual_CntDown_CmpA_PwmA(obj->pwmDacHandle[cnt],PWM_ActionQual_Set); -+ PWMDAC_setActionQual_CntUp_CmpB_PwmB(obj->pwmDacHandle[cnt],PWM_ActionQual_Clear); -+ PWMDAC_setActionQual_CntDown_CmpB_PwmB(obj->pwmDacHandle[cnt],PWM_ActionQual_Set); -+ -+ // Initialize the Dead-Band Control Register (DBCTL) -+ PWMDAC_disableDeadBand(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the PWM-Chopper Control Register (PCCTL) -+ PWMDAC_disableChopping(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the Trip-Zone Control Register (TZSEL) -+ PWMDAC_disableTripZones(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the Trip-Zone Control Register (TZCTL) -+ PWMDAC_setTripZoneState_TZA(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_TZB(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCAEVT1(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCAEVT2(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCBEVT1(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ } -+ -+ // since the PWM is configured as an up/down counter, the period register is set to one-half -+ // of the desired PWM period -+ PWMDAC_setPeriod(obj->pwmDacHandle[PWMDAC_Number_1],halfPeriod_cycles); -+ PWMDAC_setPeriod(obj->pwmDacHandle[PWMDAC_Number_2],halfPeriod_cycles); -+ -+ return; -+ } // end of HAL_setupPwmDacs() function -+ -+ -+ void HAL_setupTimers(HAL_Handle handle,const float_t systemFreq_MHz) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint32_t timerPeriod_cnts = (uint32_t)(systemFreq_MHz * (float_t)1000000.0) - 1; -+ -+ // use timer 0 for frequency diagnostics -+ TIMER_setDecimationFactor(obj->timerHandle[0],0); -+ TIMER_setEmulationMode(obj->timerHandle[0],TIMER_EmulationMode_RunFree); -+ TIMER_setPeriod(obj->timerHandle[0],timerPeriod_cnts); -+ TIMER_setPreScaler(obj->timerHandle[0],0); -+ -+ // use timer 1 for CPU usage diagnostics -+ TIMER_setDecimationFactor(obj->timerHandle[1],0); -+ TIMER_setEmulationMode(obj->timerHandle[1],TIMER_EmulationMode_RunFree); -+ TIMER_setPeriod(obj->timerHandle[1],timerPeriod_cnts); -+ TIMER_setPreScaler(obj->timerHandle[1],0); -+ -+ return; -+ } // end of HAL_setupTimers() function -+ -+ -+ void HAL_writeDrvData(HAL_Handle_mtr handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ DRV8301_writeData(obj->drv8301Handle,Spi_8301_Vars); -+ -+ return; -+ } // end of HAL_writeDrvData() function -+ -+ -+ void HAL_readDrvData(HAL_Handle_mtr handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ DRV8301_readData(obj->drv8301Handle,Spi_8301_Vars); -+ -+ return; -+ } // end of HAL_readDrvData() function -+ -+ -+ void HAL_setupDrvSpi(HAL_Handle_mtr handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ DRV8301_setupSpi(obj->drv8301Handle,Spi_8301_Vars); -+ -+ return; -+ } // end of HAL_setupDrvSpi() function -+ -+ -+ // end of file -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_2mtr.h 2017-06-08 10:41:26.595348300 +0200 -*************** -*** 0 **** ---- 1,1464 ---- -+ #ifndef _HAL_H_ -+ #define _HAL_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806x/src/hal.h -+ //! \brief Contains public interface to various functions related -+ //! to the HAL object -+ //! -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ -+ // modules -+ -+ -+ // platforms -+ #include "hal_obj_2mtr.h" -+ #include "sw/modules/svgen/src/32b/svgen_current.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL HAL -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ -+ // ************************************************************************** -+ // the defines -+ -+ //! \brief Defines that a DRV8301 chip SPI port is used on the board. -+ #define DRV8301_SPI -+ -+ #define Device_cal (void (*)(void))0x3D7C80 -+ -+ //! \brief Defines used in oscillator calibration functions -+ //! \brief Defines the scale factor for Q15 fixed point numbers (2^15) -+ #define FP_SCALE 32768 -+ -+ //! \brief Defines the quantity added to Q15 numbers before converting to integer to round the number -+ #define FP_ROUND FP_SCALE/2 -+ -+ //! \brief Defines the amount to add to Q16.15 fixed point number to shift from a fine trim range of -+ //! \brief (-31 to 31) to (1 to 63). This guarantees that the trim is positive and can -+ //! \brief therefore be efficiently rounded -+ #define OSC_POSTRIM 32 -+ #define OSC_POSTRIM_OFF FP_SCALE*OSC_POSTRIM -+ -+ //! \brief The following functions return reference values stored in OTP. -+ -+ //! \brief Defines the slope used to compensate oscillator 1 (fine trim steps / ADC code). Stored in fixed point Q15 format -+ #define getOsc1FineTrimSlope() (*(int16_t (*)(void))0x3D7E90)() -+ -+ //! \brief Defines the oscillator 1 fine trim at high temp -+ #define getOsc1FineTrimOffset() (*(int16_t (*)(void))0x3D7E93)() -+ -+ //! \brief Defines the oscillator 1 coarse trim -+ #define getOsc1CoarseTrim() (*(int16_t (*)(void))0x3D7E96)() -+ -+ //! \brief Defines the slope used to compensate oscillator 2 (fine trim steps / ADC code). Stored -+ //! \brief in fixed point Q15 format. -+ #define getOsc2FineTrimSlope() (*(int16_t (*)(void))0x3D7E99)() -+ -+ //! \brief Defines the oscillator 2 fine trim at high temp -+ #define getOsc2FineTrimOffset() (*(int16_t (*)(void))0x3D7E9C)() -+ -+ //! \brief Defines the oscillator 2 coarse trim -+ #define getOsc2CoarseTrim() (*(int16_t (*)(void))0x3D7E9F)() -+ -+ //! \brief Defines the ADC reading of temperature sensor at reference temperature for compensation -+ #define getRefTempOffset() (*(int16_t (*)(void))0x3D7EA2)() -+ -+ //! \brief Defines the PWM deadband falling edge delay count (system clocks) -+ //! -+ #define HAL_PWM_DBFED_CNT 1 -+ -+ -+ //! \brief Defines the PWM deadband rising edge delay count (system clocks) -+ //! -+ #define HAL_PWM_DBRED_CNT 1 -+ -+ -+ //! \brief Defines the function to turn LEDs off -+ //! -+ #define HAL_turnLedOff HAL_setGpioLow -+ -+ -+ //! \brief Defines the function to turn LEDs on -+ //! -+ #define HAL_turnLedOn HAL_setGpioHigh -+ -+ -+ //! \brief Defines the function to turn LEDs on -+ //! -+ #define HAL_toggleLed HAL_toggleGpio -+ -+ -+ // ************************************************************************** -+ // the typedefs -+ -+ -+ //! \brief Enumeration for the QEP setup -+ //! -+ typedef enum -+ { -+ HAL_Qep_QEP1=0, //!< Select QEP1 -+ HAL_Qep_QEP2=1 //!< Select QEP2 -+ } HAL_QepSelect_e; -+ -+ -+ //! \brief Enumeration for the LED numbers -+ //! -+ typedef enum -+ { -+ HAL_Gpio_LED2=GPIO_Number_34, //!< GPIO pin number for LaunchPad LED D9 -+ HAL_Gpio_LED3=GPIO_Number_39 //!< GPIO pin number for LaunchPad LED D10 -+ } HAL_LedNumber_e; -+ -+ -+ //! \brief Enumeration for the sensor types -+ //! -+ typedef enum -+ { -+ HAL_SensorType_Current=0, //!< Enumeration for current sensor -+ HAL_SensorType_Voltage //!< Enumeration for voltage sensor -+ } HAL_SensorType_e; -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ extern interrupt void motor1_ISR(void); -+ extern interrupt void motor2_ISR(void); -+ -+ -+ // ************************************************************************** -+ // the function prototypes -+ -+ -+ //! \brief Acknowledges an interrupt from the ADC so that another ADC interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] intNumber The interrupt number -+ static inline void HAL_acqAdcInt(HAL_Handle handle,const ADC_IntNumber_e intNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the ADC interrupt flag -+ ADC_clearIntFlag(obj->adcHandle,intNumber); -+ -+ -+ // Acknowledge interrupt from PIE group 10 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_10); -+ -+ return; -+ } // end of HAL_acqAdcInt() function -+ -+ -+ //! \brief Acknowledges an interrupt from the PWM so that another PWM interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ static inline void HAL_acqPwmInt(HAL_Handle_mtr handleMtr,HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ -+ -+ // clear the PWM interrupt flag -+ PWM_clearIntFlag(objMtr->pwmHandle[pwmNumber]); -+ -+ -+ // clear the SOCA flag -+ PWM_clearSocAFlag(objMtr->pwmHandle[pwmNumber]); -+ -+ -+ // Acknowledge interrupt from PIE group 3 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_3); -+ -+ return; -+ } // end of HAL_acqPwmInt() function -+ -+ -+ //! \brief Acknowledges an interrupt from Timer 0 so that another Timer 0 interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_acqTimer0Int(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the Timer 0 interrupt flag -+ TIMER_clearFlag(obj->timerHandle[0]); -+ -+ -+ // Acknowledge interrupt from PIE group 1 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_1); -+ -+ return; -+ } // end of HAL_acqTimer0Int() function -+ -+ -+ //! \brief Executes calibration routines -+ //! \details Values for offset and gain are programmed into OTP memory at -+ //! the TI factory. This calls and internal function that programs -+ //! these offsets and gains into the ADC registers. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_cal(HAL_Handle handle); -+ -+ -+ //! \brief Disables global interrupts -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_disableGlobalInts(HAL_Handle handle); -+ -+ -+ //! \brief Disables the watch dog -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_disableWdog(HAL_Handle handle); -+ -+ -+ //! \brief Disables the PWM device -+ //! \details Turns off the outputs of the EPWM peripherals which will put -+ //! the power switches into a high impedance state. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_disablePwm(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ return; -+ } // end of HAL_disablePwm() function -+ -+ -+ //! \brief Enables the ADC interrupts -+ //! \details Enables the ADC interrupt in the PIE, and CPU. Enables the -+ //! interrupt to be sent from the ADC peripheral. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableAdcInts(HAL_Handle handle); -+ -+ -+ //! \brief Enables the debug interrupt -+ //! \details The debug interrupt is used for the real-time debugger. It is -+ //! not needed if the real-time debugger is not used. Clears -+ //! bit 1 of ST1. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableDebugInt(HAL_Handle handle); -+ -+ -+ //! \brief Enables global interrupts -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableGlobalInts(HAL_Handle handle); -+ -+ -+ //! \brief Enables the 8301 device -+ //! \details Provides the correct timing to enable the drv8301 -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableDrv(HAL_Handle_mtr handle); -+ -+ -+ //! \brief Enables the PWM devices -+ //! \details Turns on the outputs of the EPWM peripheral which will allow -+ //! the power switches to be controlled. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_enablePwm(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ return; -+ } // end of HAL_enablePwm() function -+ -+ -+ //! \brief Enables the PWM interrupt -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enablePwmInt(HAL_Handle_mtr handleMtr,HAL_Handle handle); -+ -+ -+ //! \brief Enables the Timer 0 interrupt -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableTimer0Int(HAL_Handle handle); -+ -+ -+ //! \brief Gets the ADC delay value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] socNumber The ADC SOC number -+ //! \return The ADC delay value -+ static inline ADC_SocSampleDelay_e HAL_getAdcSocSampleDelay(HAL_Handle handle, -+ const ADC_SocNumber_e socNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(ADC_getSocSampleDelay(obj->adcHandle,socNumber)); -+ } // end of HAL_getAdcSocSampleDelay() function -+ -+ -+ ////! \brief Gets the ADC bias value -+ ////! \details The ADC bias contains the feedback circuit's offset and bias. -+ ////! Bias is the mathematical offset used when a bi-polar signal -+ ////! is read into a uni-polar ADC. -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \return The ADC bias value -+ //static inline _iq HAL_getBias(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // uint_least8_t sensorNumber) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // _iq bias = _IQ(0.0); -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // bias = obj->adcBias.I.value[sensorNumber]; -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // bias = obj->adcBias.V.value[sensorNumber]; -+ // } -+ // -+ // return(bias); -+ //} // end of HAL_getBias() function -+ -+ -+ //! \brief Gets the current scale factor -+ //! \details The current scale factor is defined as -+ //! USER_ADC_FULL_SCALE_CURRENT_A/USER_IQ_FULL_SCALE_CURRENT_A. -+ //! This scale factor is not used when converting between PU amps -+ //! and real amps. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The current scale factor -+ static inline _iq HAL_getCurrentScaleFactor(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ return(obj->current_sf); -+ } // end of HAL_getCurrentScaleFactor() function -+ -+ -+ //! \brief Gets the number of current sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The number of current sensors -+ static inline uint_least8_t HAL_getNumCurrentSensors(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ -+ return(obj->numCurrentSensors); -+ } // end of HAL_getNumCurrentSensors() function -+ -+ -+ //! \brief Gets the number of voltage sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The number of voltage sensors -+ static inline uint_least8_t HAL_getNumVoltageSensors(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ -+ return(obj->numVoltageSensors); -+ } // end of HAL_getNumVoltageSensors() function -+ -+ -+ ////! \brief Gets the value used to set the low pass filter pole for offset estimation -+ ////! \details An IIR single pole low pass filter is used to find the feedback circuit's -+ ////! offsets. This function returns the value of that pole. -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \return The value used to set the low pass filter pole, pu -+ //static inline _iq HAL_getOffsetBeta_lp_pu(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // const uint_least8_t sensorNumber) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // _iq beta_lp_pu = _IQ(0.0); -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // beta_lp_pu = OFFSET_getBeta(obj->offsetHandle_I[sensorNumber]); -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // beta_lp_pu = OFFSET_getBeta(obj->offsetHandle_V[sensorNumber]); -+ // } -+ // -+ // return(beta_lp_pu); -+ //} // end of HAL_getOffsetBeta_lp_pu() function -+ -+ -+ ////! \brief Gets the offset value -+ ////! \details The offsets that are calculated during the feedback circuits calibrations -+ ////! are returned from the IIR filter object. -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \return The offset value -+ //static inline _iq HAL_getOffsetValue(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // const uint_least8_t sensorNumber) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // _iq offset = _IQ(0.0); -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // offset = OFFSET_getOffset(obj->offsetHandle_I[sensorNumber]); -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // offset = OFFSET_getOffset(obj->offsetHandle_V[sensorNumber]); -+ // } -+ // -+ // return(offset); -+ //} // end of HAL_getOffsetValue() function -+ -+ -+ //! \brief Gets the voltage scale factor -+ //! \details The voltage scale factor is defined as -+ //! USER_ADC_FULL_SCALE_VOLTAGE_V/USER_IQ_FULL_SCALE_VOLTAGE_V. -+ //! This scale factor is not used when converting between PU volts -+ //! and real volts. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The voltage scale factor -+ static inline _iq HAL_getVoltageScaleFactor(HAL_Handle_mtr handle) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ return(obj->voltage_sf); -+ } // end of HAL_getVoltageScaleFactor() function -+ -+ -+ //! \brief Configures the fault protection logic -+ //! \details Sets up the trip zone inputs so that when a comparator -+ //! signal from outside the micro-controller trips a fault, -+ //! the EPWM peripheral blocks will force the -+ //! power switches into a high impedance state. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupFaults(HAL_Handle_mtr handle); -+ -+ -+ //! \brief Initializes the hardware abstraction layer (HAL) object -+ //! \details Initializes all handles to the microcontroller peripherals. -+ //! Returns a handle to the HAL object. -+ //! \param[in] pMemory A pointer to the memory for the hardware abstraction layer object -+ //! \param[in] numBytes The number of bytes allocated for the hardware abstraction layer object, bytes -+ //! \return The hardware abstraction layer (HAL) object handle -+ extern HAL_Handle HAL_init(void *pMemory,const size_t numBytes); -+ -+ -+ //! \brief Initializes the hardware abstraction layer motor object -+ //! \details Initializes and eturns a handle to the HAL motor object. -+ //! \param[in] pMemory A pointer to the memory for the hardware abstraction layer object -+ //! \param[in] numBytes The number of bytes allocated for the hardware abstraction layer object, bytes -+ //! \return The hardware abstraction layer motor object handle -+ HAL_Handle_mtr HAL_init_mtr(void *pMemory,const size_t numBytes,const HAL_MtrSelect_e mtrNum); -+ -+ -+ //! \brief Initializes the interrupt vector table -+ //! \details Points ADCINT1 to motor1_ISR -+ //! \details Points ADCINT2 to motor2_ISR -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_initIntVectorTable(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ PIE_Obj *pie = (PIE_Obj *)obj->pieHandle; -+ -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ pie->ADCINT1 = &motor1_ISR; -+ pie->ADCINT2 = &motor2_ISR; -+ -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_initIntVectorTable() function -+ -+ -+ ////! \brief Reads the ADC data -+ ////! \details Reads in the ADC result registers, adjusts for offsets, and -+ ////! scales the values according to the settings in user.h. The -+ ////! structure gAdcData holds three phase voltages, three line -+ ////! currents, and one DC bus voltage. -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] pAdcData A pointer to the ADC data buffer -+ //static inline void HAL_readAdcData(HAL_Handle handle,HAL_AdcData_t *pAdcData) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // _iq value; -+ // _iq current_sf = HAL_getCurrentScaleFactor(handle); -+ // _iq voltage_sf = HAL_getVoltageScaleFactor(handle); -+ // -+ // -+ // // convert current A -+ // // sample the first sample twice due to errata sprz342f, ignore the first sample -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_1); -+ // value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[0]; // divide by 2^numAdcBits = 2^12 -+ // pAdcData->I.value[0] = value; -+ // -+ // // convert current B -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_2); -+ // value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[1]; // divide by 2^numAdcBits = 2^12 -+ // pAdcData->I.value[1] = value; -+ // -+ // // convert current C -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_3); -+ // value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[2]; // divide by 2^numAdcBits = 2^12 -+ // pAdcData->I.value[2] = value; -+ // -+ // // convert voltage A -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_4); -+ // value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[0]; // divide by 2^numAdcBits = 2^12 -+ // pAdcData->V.value[0] = value; -+ // -+ // // convert voltage B -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_5); -+ // value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[1]; // divide by 2^numAdcBits = 2^12 -+ // pAdcData->V.value[1] = value; -+ // -+ // // convert voltage C -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_6); -+ // value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[2]; // divide by 2^numAdcBits = 2^12 -+ // pAdcData->V.value[2] = value; -+ // -+ // // read the dcBus voltage value -+ // value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_7); // divide by 2^numAdcBits = 2^12 -+ // value = _IQ12mpy(value,voltage_sf); -+ // pAdcData->dcBus = value; -+ // -+ // return; -+ //} // end of HAL_readAdcData() function -+ -+ -+ //! \brief Reads the ADC data -+ //! \details Reads in the ADC result registers, and -+ //! scales the values according to the settings in user.h. The -+ //! structure gAdcData holds three phase voltages, three line -+ //! currents, and one DC bus voltage. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pAdcData A pointer to the ADC data buffer -+ static inline void HAL_readAdcDataWithOffsets(HAL_Handle handle,HAL_Handle_mtr handleMtr,HAL_AdcData_t *pAdcData) -+ { -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq value; -+ _iq current_sf = HAL_getCurrentScaleFactor(handleMtr); -+ _iq voltage_sf = HAL_getVoltageScaleFactor(handleMtr); -+ HAL_MtrSelect_e mtrNum = objMtr->mtrNum; -+ -+ if(mtrNum == HAL_MTR1) -+ { -+ // convert current A -+ // sample the first sample twice due to errata sprz342f, ignore the first sample -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_1); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[0] = value; -+ -+ // convert current B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_2); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[1] = value; -+ -+ // convert current C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_3); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[2] = value; -+ -+ // convert voltage A -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_4); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[0] = value; -+ -+ // convert voltage B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_5); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[1] = value; -+ -+ // convert voltage C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_6); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[2] = value; -+ -+ // read the dcBus voltage value -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_7); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->dcBus = value; -+ } -+ else -+ { -+ // convert current A -+ // sample the first sample twice due to errata sprz342f, ignore the first sample -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_8); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[0] = value; -+ -+ // convert current B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_9); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[1] = value; -+ -+ // convert current C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_10); -+ value = _IQ12mpy(value,current_sf); -+ pAdcData->I.value[2] = value; -+ -+ // convert voltage A -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_11); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[0] = value; -+ -+ // convert voltage B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_12); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[1] = value; -+ -+ // convert voltage C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_13); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->V.value[2] = value; -+ -+ // read the dcBus voltage value -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_14); -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->dcBus = value; -+ } -+ -+ return; -+ } // end of HAL_readAdcDataWithOffsets() function -+ -+ -+ //! \brief Reads the timer count -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \return The timer count -+ static inline uint32_t HAL_readTimerCnt(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint32_t timerCnt = TIMER_getCount(obj->timerHandle[timerNumber]); -+ -+ return(timerCnt); -+ } // end of HAL_readTimerCnt() function -+ -+ -+ //! \brief Reloads the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_reloadTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // reload the specified timer -+ TIMER_reload(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_reloadTimer() function -+ -+ -+ //! \brief Sets up the GATE object -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] handleMtr The hardware abstraction layer for the individual motor -+ //! \param[in] gpio The gpio to the enable pin of the drv8301 -+ void HAL_setupGate(HAL_Handle_mtr handleMtr,SPI_Handle handleSpi,GPIO_Handle handleGpio,const GPIO_Number_e gpio); -+ -+ -+ //! \brief Starts the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_startTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // start the specified timer -+ TIMER_start(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_startTimer() function -+ -+ -+ //! \brief Stops the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_stopTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // stop the specified timer -+ TIMER_stop(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_stopTimer() function -+ -+ //! \brief Sets the motor number -+ //! \param[in] handle The motor hardware abstraction layer handle -+ //! \param[in] mtrNum The motor number HAL_MTR1, or HAL_MTR2 -+ static inline void HAL_setMotorNumber(HAL_Handle_mtr handle,const HAL_MtrSelect_e mtrNum) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ // set the motor number -+ obj->mtrNum = mtrNum; -+ -+ return; -+ } // end of HAL_setMotorNumber() function -+ -+ -+ //! \brief Sets the timer period -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \param[in] period The timer period -+ static inline void HAL_setTimerPeriod(HAL_Handle handle,const uint_least8_t timerNumber, const uint32_t period) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // set the period -+ TIMER_setPeriod(obj->timerHandle[timerNumber], period); -+ -+ return; -+ } // end of HAL_setTimerPeriod() function -+ -+ -+ //! \brief Gets the timer period -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \return The timer period -+ static inline uint32_t HAL_getTimerPeriod(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ uint32_t timerPeriod = TIMER_getPeriod(obj->timerHandle[timerNumber]); -+ -+ return(timerPeriod); -+ } // end of HAL_getTimerPeriod() function -+ -+ -+ //! \brief Sets the ADC SOC sample delay value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] socNumber The SOC number -+ //! \param[in] sampleDelay The delay value for the ADC -+ static inline void HAL_setAdcSocSampleDelay(HAL_Handle handle, -+ const ADC_SocNumber_e socNumber, -+ const ADC_SocSampleDelay_e sampleDelay) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ADC_setSocSampleDelay(obj->adcHandle,socNumber,sampleDelay); -+ -+ return; -+ } // end of HAL_setAdcSocSampleDelay() function -+ -+ -+ ////! \brief Sets the ADC bias value -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \param[in] bias The ADC bias value -+ //static inline void HAL_setBias(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // uint_least8_t sensorNumber, -+ // const _iq bias) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // obj->adcBias.I.value[sensorNumber] = bias; -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // obj->adcBias.V.value[sensorNumber] = bias; -+ // } -+ // -+ // return; -+ //} // end of HAL_setBias() function -+ -+ -+ //! \brief Sets the GPIO pin high -+ //! \details Takes in the enumeration GPIO_Number_e and sets that GPIO -+ //! pin high. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_setGpioHigh(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO high -+ GPIO_setHigh(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioHigh() function -+ -+ -+ //! \brief Reads the specified GPIO pin -+ //! \details Takes in the enumeration GPIO_Number_e and reads that GPIO -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline bool HAL_readGpio(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // read GPIO -+ return(GPIO_read(obj->gpioHandle,gpioNumber)); -+ } // end of HAL_readGpio() function -+ -+ -+ //! \brief Toggles the GPIO pin -+ //! \details Takes in the enumeration GPIO_Number_e and toggles that GPIO -+ //! pin. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_toggleGpio(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO high -+ GPIO_toggle(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioHigh() function -+ -+ -+ //! \brief Sets the GPIO pin low -+ //! \details Takes in the enumeration GPIO_Number_e and clears that GPIO -+ //! pin low. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_setGpioLow(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO low -+ GPIO_setLow(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioLow() function -+ -+ -+ //! \brief Sets the current scale factor in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] current_sf The current scale factor -+ static inline void HAL_setCurrentScaleFactor(HAL_Handle_mtr handle,const _iq current_sf) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ -+ obj->current_sf = current_sf; -+ -+ return; -+ } // end of HAL_setCurrentScaleFactor() function -+ -+ -+ //! \brief Sets the number of current sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] numCurrentSensors The number of current sensors -+ static inline void HAL_setNumCurrentSensors(HAL_Handle_mtr handle,const uint_least8_t numCurrentSensors) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ -+ obj->numCurrentSensors = numCurrentSensors; -+ -+ return; -+ } // end of HAL_setNumCurrentSensors() function -+ -+ -+ //! \brief Sets the number of voltage sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] numVoltageSensors The number of voltage sensors -+ static inline void HAL_setNumVoltageSensors(HAL_Handle_mtr handle,const uint_least8_t numVoltageSensors) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ -+ obj->numVoltageSensors = numVoltageSensors; -+ -+ return; -+ } // end of HAL_setNumVoltageSensors() function -+ -+ -+ ////! \brief Sets the value used to set the low pass filter pole for offset estimation -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \param[in] beta_lp_pu The value used to set the low pass filter pole, pu -+ //static inline void HAL_setOffsetBeta_lp_pu(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // const uint_least8_t sensorNumber, -+ // const _iq beta_lp_pu) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // OFFSET_setBeta(obj->offsetHandle_I[sensorNumber],beta_lp_pu); -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // OFFSET_setBeta(obj->offsetHandle_V[sensorNumber],beta_lp_pu); -+ // } -+ // -+ // return; -+ //} // end of HAL_setOffsetBeta_lp_pu() function -+ -+ -+ ////! \brief Sets the offset initial condition value for offset estimation -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \param[in] initCond The initial condition value -+ //static inline void HAL_setOffsetInitCond(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // const uint_least8_t sensorNumber, -+ // const _iq initCond) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // OFFSET_setInitCond(obj->offsetHandle_I[sensorNumber],initCond); -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // OFFSET_setInitCond(obj->offsetHandle_V[sensorNumber],initCond); -+ // } -+ // -+ // return; -+ //} // end of HAL_setOffsetInitCond() function -+ -+ -+ ////! \brief Sets the initial offset value for offset estimation -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ ////! \param[in] sensorType The sensor type -+ ////! \param[in] sensorNumber The sensor number -+ ////! \param[in] value The initial offset value -+ //static inline void HAL_setOffsetValue(HAL_Handle handle, -+ // const HAL_SensorType_e sensorType, -+ // const uint_least8_t sensorNumber, -+ // const _iq value) -+ //{ -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // -+ // if(sensorType == HAL_SensorType_Current) -+ // { -+ // OFFSET_setOffset(obj->offsetHandle_I[sensorNumber],value); -+ // } -+ // else if(sensorType == HAL_SensorType_Voltage) -+ // { -+ // OFFSET_setOffset(obj->offsetHandle_V[sensorNumber],value); -+ // } -+ // -+ // return; -+ //} // end of HAL_setOffsetValue() function -+ -+ -+ //! \brief Sets the voltage scale factor in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] voltage_sf The voltage scale factor -+ static inline void HAL_setVoltageScaleFactor(HAL_Handle_mtr handle,const _iq voltage_sf) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ obj->voltage_sf = voltage_sf; -+ -+ return; -+ } // end of HAL_setVoltageScaleFactor() function -+ -+ -+ //! \brief Sets the hardware abstraction layer parameters -+ //! \details Sets up the microcontroller peripherals. Creates all of the scale -+ //! factors for the ADC voltage and current conversions. Sets the initial -+ //! offset values for voltage and current measurements. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pUserParams The pointer to the user parameters -+ extern void HAL_setParams(HAL_Handle handle,const USER_Params *pUserParams); -+ -+ -+ //! \brief Sets the hardware abstraction layer individual motor parameters -+ //! \details Sets up the motor specific parameters. Creates all of the scale -+ //! factors for the ADC voltage and current conversions. Sets the initial -+ //! offset values for voltage and current measurements. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pUserParams The pointer to the user parameters -+ //! \param[in] gpio The enable gpio number for the drv8301 -+ void HAL_setParamsMtr(HAL_Handle_mtr handleMtr,HAL_Handle handle,const USER_Params *pUserParams); -+ -+ -+ //! \brief Sets up the ADCs (Analog to Digital Converters) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupAdcs(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the clocks -+ //! \details Sets up the micro-controller's main oscillator -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupClks(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the FLASH. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupFlash(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the GPIO (General Purpose I/O) pins -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupGpios(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the peripheral clocks -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPeripheralClks(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the PIE (Peripheral Interrupt Expansion) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPie(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the PLL (Phase Lock Loop) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] clkFreq The clock frequency -+ extern void HAL_setupPll(HAL_Handle handle,const PLL_ClkFreq_e clkFreq); -+ -+ -+ //! \brief Sets up the PWMs (Pulse Width Modulators) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] systemFreq_MHz The system frequency, MHz -+ //! \param[in] pwmPeriod_usec The PWM period, usec -+ //! \param[in] numPwmTicksPerIsrTick The number of PWM clock ticks per ISR clock tick -+ void HAL_setupPwms(HAL_Handle_mtr,HAL_Handle,const USER_Params *); -+ -+ -+ //! \brief Sets up the PWM DACs (Pulse Width Modulator Digital to Analof Converters) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPwmDacs(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the QEP peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupQEP(HAL_Handle_mtr handleMtr, float_t encoderLines); -+ -+ -+ //! \brief Sets up the spiA peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupSpiA(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the spiB peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupSpiB(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the timers -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] systemFreq_MHz The system frequency, MHz -+ void HAL_setupTimers(HAL_Handle handle,const float_t systemFreq_MHz); -+ -+ -+ ////! \brief Updates the ADC bias values -+ ////! \details This function is called before the motor is started. It sets the voltage -+ ////! and current measurement offsets. -+ ////! \param[in] handle The hardware abstraction layer (HAL) handle -+ //static inline void HAL_updateAdcBias(HAL_Handle handle) -+ //{ -+ // uint_least8_t cnt; -+ // HAL_Obj *obj = (HAL_Obj *)handle; -+ // _iq bias; -+ // -+ // -+ // // update the current bias -+ // for(cnt=0;cntoffsetHandle_I[cnt]); -+ // -+ // HAL_setBias(handle,HAL_SensorType_Current,cnt,bias); -+ // } -+ // -+ // -+ // // update the voltage bias -+ // for(cnt=0;cntoffsetHandle_V[cnt]); -+ // -+ // HAL_setBias(handle,HAL_SensorType_Voltage,cnt,bias); -+ // } -+ // -+ // return; -+ //} // end of HAL_updateAdcBias() function -+ -+ -+ //! \brief Writes DAC data to the PWM comparators for DAC (digital-to-analog conversion) output -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pDacData The pointer to the DAC data -+ static inline void HAL_writeDacData(HAL_Handle handle,HAL_DacData_t *pDacData) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // convert values from _IQ to _IQ15 -+ int16_t dacValue_1 = (int16_t)_IQtoIQ15(pDacData->value[0]); -+ int16_t dacValue_2 = (int16_t)_IQtoIQ15(pDacData->value[1]); -+ int16_t dacValue_3 = (int16_t)_IQtoIQ15(pDacData->value[2]); -+ int16_t dacValue_4 = (int16_t)_IQtoIQ15(pDacData->value[3]); -+ -+ // write the DAC data -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_1],dacValue_1); -+ PWMDAC_write_CmpB(obj->pwmDacHandle[PWMDAC_Number_1],dacValue_2); -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_2],dacValue_3); -+ PWMDAC_write_CmpB(obj->pwmDacHandle[PWMDAC_Number_2],dacValue_4); -+ -+ return; -+ } // end of HAL_writeDacData() function -+ -+ -+ //! \brief Writes PWM data to the PWM comparators for motor control -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pPwmData The pointer to the PWM data -+ static inline void HAL_writePwmData(HAL_Handle_mtr handle,HAL_PwmData_t *pPwmData) -+ { -+ uint_least8_t cnt; -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ PWM_Obj *pwm; -+ _iq period; -+ _iq pwmData_neg; -+ _iq pwmData_sat; -+ _iq pwmData_sat_dc; -+ _iq value; -+ uint16_t value_sat; -+ -+ for(cnt=0;cnt<3;cnt++) -+ { -+ pwm = (PWM_Obj *)obj->pwmHandle[cnt]; -+ period = (_iq)pwm->TBPRD; -+ pwmData_neg = _IQmpy(pPwmData->Tabc.value[cnt],_IQ(-1.0)); -+ pwmData_sat = _IQsat(pwmData_neg,_IQ(0.5),_IQ(-0.5)); -+ pwmData_sat_dc = pwmData_sat + _IQ(0.5); -+ value = _IQmpy(pwmData_sat_dc, period); -+ value_sat = (uint16_t)_IQsat(value, period, _IQ(0.0)); -+ -+ // write the PWM data -+ PWM_write_CmpA(obj->pwmHandle[cnt],value_sat); -+ } -+ -+ return; -+ } // end of HAL_writePwmData() function -+ -+ -+ //! \brief Reads PWM compare register A -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpA(HAL_Handle_mtr handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpA(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpA() function -+ -+ -+ //! \brief Reads PWM compare mirror register A -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpAM(HAL_Handle_mtr handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpAM(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpAM() function -+ -+ -+ //! \brief Reads PWM compare register B -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpB(HAL_Handle_mtr handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpB(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpB() function -+ -+ -+ //! \brief Reads PWM period register -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM period value -+ static inline uint16_t HAL_readPwmPeriod(HAL_Handle_mtr handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ // the period value to be returned -+ uint16_t pwmPeriodValue; -+ -+ pwmPeriodValue = PWM_getPeriod(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmPeriodValue); -+ } // end of HAL_readPwmPeriod() function -+ -+ -+ static inline void HAL_setTrigger(HAL_Handle_mtr handle,const SVGENCURRENT_IgnoreShunt_e ignoreShunt,const int16_t minwidth, const int16_t cmpOffset) -+ { -+ HAL_Obj_mtr *obj = (HAL_Obj_mtr *)handle; -+ -+ PWM_Obj *pwm1 = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ PWM_Obj *pwm2 = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ PWM_Obj *pwm3 = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ PWM_Obj *pwm; -+ -+ uint16_t nextPulse1 = (pwm1->CMPA + pwm1->CMPAM) / 2; -+ uint16_t nextPulse2 = (pwm2->CMPA + pwm2->CMPAM) / 2; -+ uint16_t nextPulse3 = (pwm3->CMPA + pwm3->CMPAM) / 2; -+ uint16_t pwmCMPA1 = pwm1->CMPA; -+ uint16_t pwmCMPA2 = pwm2->CMPA; -+ uint16_t pwmCMPA3 = pwm3->CMPA; -+ -+ int16_t offset; -+ -+ if(ignoreShunt == use_all) -+ { -+ if((nextPulse1 <= nextPulse2) && (nextPulse1 <= nextPulse3)) -+ { -+ pwm = pwm1; -+ } -+ else if((nextPulse2 <= nextPulse1) && (nextPulse2 <= nextPulse3)) -+ { -+ pwm = pwm2; -+ } -+ else -+ { -+ pwm = pwm3; -+ } -+ } -+ else if(ignoreShunt == ignore_a) -+ { -+ offset = pwmCMPA1 + cmpOffset; -+ } -+ else if(ignoreShunt == ignore_b) -+ { -+ offset = pwmCMPA2 + cmpOffset; -+ } -+ else if(ignoreShunt == ignore_c) -+ { -+ offset = pwmCMPA3 + cmpOffset; -+ } -+ else if(ignoreShunt == ignore_ab) -+ { -+ if(pwmCMPA1 > pwmCMPA2) -+ { -+ offset = pwmCMPA1 + cmpOffset; -+ } -+ else -+ { -+ offset = pwmCMPA2 + cmpOffset; -+ } -+ } -+ else if(ignoreShunt == ignore_ac) -+ { -+ if(pwmCMPA1 > pwmCMPA3) -+ { -+ offset = pwmCMPA1 + cmpOffset; -+ } -+ else -+ { -+ offset = pwmCMPA3 + cmpOffset; -+ } -+ } -+ else // when ignoreShunt == ignore_bc -+ { -+ if(pwmCMPA2 > pwmCMPA3) -+ { -+ offset = pwmCMPA2 + cmpOffset; -+ } -+ else -+ { -+ offset = pwmCMPA3 + cmpOffset; -+ } -+ } -+ -+ -+ if(ignoreShunt == use_all) -+ { -+ if(pwm->CMPAM >= (pwm->CMPA + pwm->DBFED)) -+ { -+ pwm1->CMPB = (pwm->CMPAM - (pwm->CMPA + pwm->DBFED)) / 2 + 1; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBDecr); -+ } -+ else -+ { -+ pwm1->CMPB = ((pwm->CMPA + pwm->DBFED) - pwm->CMPAM ) / 2 + 1; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBIncr); -+ } -+ } -+ else -+ { -+ pwm1->CMPB = offset; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBIncr); -+ } -+ -+ return; -+ } // end of HAL_setTrigger() function -+ -+ #ifdef QEP -+ //! \brief Returns the current position count from QEP -+ //! \param[in] handleMtr The hardware abstraction layer (HAL) handle for a specific motor -+ //! \return the current position count from QEP -+ static inline uint32_t HAL_getQepPosnCounts(HAL_Handle_mtr handleMtr) -+ { -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ QEP_Obj *qep = (QEP_Obj *)objMtr->qepHandle; -+ -+ return qep->QPOSCNT; -+ } -+ -+ -+ //! \brief Returns the maximum position count from QEP -+ //! \param[in] handleMtr The hardware abstraction layer (HAL) handle for a specific motor -+ //! \return the maximum position count from QEP -+ static inline uint32_t HAL_getQepPosnMaximum(HAL_Handle_mtr handleMtr) -+ { -+ HAL_Obj_mtr *objMtr = (HAL_Obj_mtr *)handleMtr; -+ QEP_Obj *qep = (QEP_Obj *)objMtr->qepHandle; -+ -+ return qep->QPOSMAX; -+ } -+ #endif -+ -+ //! \brief Selects the analog channel used for calibration -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] chanNumber The channel number -+ void HAL_AdcCalChanSelect(HAL_Handle handle, const ADC_SocChanNumber_e chanNumber); -+ -+ -+ //! \brief Reads the converted value from the selected calibration channel -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The converted value -+ uint16_t HAL_AdcCalConversion(HAL_Handle handle); -+ -+ -+ //! \brief Executes the offset calibration of the ADC -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_AdcOffsetSelfCal(HAL_Handle handle); -+ -+ -+ //! \brief Converts coarse and fine oscillator trim values into a single 16bit word value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] coarse The coarse trim portion of the oscillator trim -+ //! \param[in] fine The fine trim portion of the oscillator trim -+ //! \return The combined trim value -+ uint16_t HAL_getOscTrimValue(int16_t coarse, int16_t fine); -+ -+ -+ //! \brief Executes the oscillator 1 and 2 calibration functions -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_OscTempComp(HAL_Handle handle); -+ -+ -+ //! \brief Executes the oscillator 1 calibration based on input sample -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_osc1Comp(HAL_Handle handle, const int16_t sensorSample); -+ -+ -+ //! \brief Executes the oscillator 2 calibration based on input sample -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_osc2Comp(HAL_Handle handle, const int16_t sensorSample); -+ -+ -+ //! \brief Writes data to the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] Spi_8301_Vars SPI variables -+ void HAL_writeDrvData(HAL_Handle_mtr handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars); -+ -+ -+ //! \brief Reads data from the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] Spi_8301_Vars SPI variables -+ void HAL_readDrvData(HAL_Handle_mtr handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars); -+ -+ -+ //! \brief Sets up the SPI interface for the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] Spi_8301_Vars SPI variables -+ void HAL_setupDrvSpi(HAL_Handle_mtr handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars); -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_H_ definition -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.c -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.c 2017-06-08 10:41:26.595348300 +0200 -*************** -*** 0 **** ---- 1,1608 ---- -+ /* --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/boards/drv8301kit_revD/f28x/f2806xF/src/hal.c -+ //! \brief Contains the various functions related to the HAL object (everything outside the CTRL system) -+ //! -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // drivers -+ -+ // modules -+ -+ // platforms -+ #include "hal.h" -+ #include "user.h" -+ #include "hal_obj.h" -+ -+ #ifdef FLASH -+ #pragma CODE_SECTION(HAL_setupFlash,"ramfuncs"); -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ HAL_Obj hal; -+ -+ -+ // ************************************************************************** -+ // the functions -+ -+ void HAL_cal(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable the ADC clock -+ CLK_enableAdcClock(obj->clkHandle); -+ -+ -+ // Run the Device_cal() function -+ // This function copies the ADC and oscillator calibration values from TI reserved -+ // OTP into the appropriate trim registers -+ // This boot ROM automatically calls this function to calibrate the interal -+ // oscillators and ADC with device specific calibration data. -+ // If the boot ROM is bypassed by Code Composer Studio during the development process, -+ // then the calibration must be initialized by the application -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ (*Device_cal)(); -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ // run offsets calibration in user's memory -+ HAL_AdcOffsetSelfCal(handle); -+ -+ // run oscillator compensation -+ HAL_OscTempComp(handle); -+ -+ // disable the ADC clock -+ CLK_disableAdcClock(obj->clkHandle); -+ -+ return; -+ } // end of HAL_cal() function -+ -+ -+ void HAL_OscTempComp(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t Temperature; -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ // enable non-overlap mode -+ ADC_enableNoOverlapMode(obj->adcHandle); -+ -+ // connect channel A5 internally to the temperature sensor -+ ADC_setTempSensorSrc(obj->adcHandle, ADC_TempSensorSrc_Int); -+ -+ // set SOC0 channel select to ADCINA5 -+ ADC_setSocChanNumber(obj->adcHandle, ADC_SocNumber_0, ADC_SocChanNumber_A5); -+ -+ // set SOC0 acquisition period to 26 ADCCLK -+ ADC_setSocSampleDelay(obj->adcHandle, ADC_SocNumber_0, ADC_SocSampleDelay_64_cycles); -+ -+ // connect ADCINT1 to EOC0 -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_1, ADC_IntSrc_EOC0); -+ -+ // clear ADCINT1 flag -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ // enable ADCINT1 -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_1); -+ -+ // force start of conversion on SOC0 -+ ADC_setSocFrc(obj->adcHandle, ADC_SocFrc_0); -+ -+ // wait for end of conversion -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_1) == 0){} -+ -+ // clear ADCINT1 flag -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ Temperature = ADC_readResult(obj->adcHandle, ADC_ResultNumber_0); -+ -+ HAL_osc1Comp(handle, Temperature); -+ -+ HAL_osc2Comp(handle, Temperature); -+ -+ return; -+ } // end of HAL_OscTempComp() function -+ -+ -+ void HAL_osc1Comp(HAL_Handle handle, const int16_t sensorSample) -+ { -+ int16_t compOscFineTrim; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ compOscFineTrim = ((sensorSample - getRefTempOffset())*(int32_t)getOsc1FineTrimSlope() -+ + OSC_POSTRIM_OFF + FP_ROUND )/FP_SCALE + getOsc1FineTrimOffset() - OSC_POSTRIM; -+ -+ if(compOscFineTrim > 31) -+ { -+ compOscFineTrim = 31; -+ } -+ else if(compOscFineTrim < -31) -+ { -+ compOscFineTrim = -31; -+ } -+ -+ OSC_setTrim(obj->oscHandle, OSC_Number_1, HAL_getOscTrimValue(getOsc1CoarseTrim(), compOscFineTrim)); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_osc1Comp() function -+ -+ -+ void HAL_osc2Comp(HAL_Handle handle, const int16_t sensorSample) -+ { -+ int16_t compOscFineTrim; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ compOscFineTrim = ((sensorSample - getRefTempOffset())*(int32_t)getOsc2FineTrimSlope() -+ + OSC_POSTRIM_OFF + FP_ROUND )/FP_SCALE + getOsc2FineTrimOffset() - OSC_POSTRIM; -+ -+ if(compOscFineTrim > 31) -+ { -+ compOscFineTrim = 31; -+ } -+ else if(compOscFineTrim < -31) -+ { -+ compOscFineTrim = -31; -+ } -+ -+ OSC_setTrim(obj->oscHandle, OSC_Number_2, HAL_getOscTrimValue(getOsc2CoarseTrim(), compOscFineTrim)); -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_osc2Comp() function -+ -+ -+ uint16_t HAL_getOscTrimValue(int16_t coarse, int16_t fine) -+ { -+ uint16_t regValue = 0; -+ -+ if(fine < 0) -+ { -+ regValue = ((-fine) | 0x20) << 9; -+ } -+ else -+ { -+ regValue = fine << 9; -+ } -+ -+ if(coarse < 0) -+ { -+ regValue |= ((-coarse) | 0x80); -+ } -+ else -+ { -+ regValue |= coarse; -+ } -+ -+ return regValue; -+ } // end of HAL_getOscTrimValue() function -+ -+ -+ void HAL_AdcOffsetSelfCal(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t AdcConvMean; -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ //Select VREFLO internal connection on B5 -+ ADC_enableVoltRefLoConv(obj->adcHandle); -+ -+ //Select channel B5 for all SOC -+ HAL_AdcCalChanSelect(handle, ADC_SocChanNumber_B5); -+ -+ //Apply artificial offset (+80) to account for a negative offset that may reside in the ADC core -+ ADC_setOffTrim(obj->adcHandle, 80); -+ -+ //Capture ADC conversion on VREFLO -+ AdcConvMean = HAL_AdcCalConversion(handle); -+ -+ //Set offtrim register with new value (i.e remove artical offset (+80) and create a two's compliment of the offset error) -+ ADC_setOffTrim(obj->adcHandle, 80 - AdcConvMean); -+ -+ //Select external ADCIN5 input pin on B5 -+ ADC_disableVoltRefLoConv(obj->adcHandle); -+ -+ return; -+ } // end of HAL_AdcOffsetSelfCal() function -+ -+ -+ void HAL_AdcCalChanSelect(HAL_Handle handle, const ADC_SocChanNumber_e chanNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_0,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_1,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_2,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_3,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_4,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_5,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_6,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_7,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_8,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_9,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_10,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_11,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_12,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_13,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_14,chanNumber); -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_15,chanNumber); -+ -+ return; -+ } // end of HAL_AdcCalChanSelect() function -+ -+ -+ uint16_t HAL_AdcCalConversion(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t index, SampleSize, Mean; -+ uint32_t Sum; -+ ADC_SocSampleDelay_e ACQPS_Value; -+ -+ index = 0; //initialize index to 0 -+ SampleSize = 256; //set sample size to 256 (**NOTE: Sample size must be multiples of 2^x where is an integer >= 4) -+ Sum = 0; //set sum to 0 -+ Mean = 999; //initialize mean to known value -+ -+ //Set the ADC sample window to the desired value (Sample window = ACQPS + 1) -+ ACQPS_Value = ADC_SocSampleDelay_7_cycles; -+ -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_0,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_1,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_2,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_3,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_4,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_5,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_6,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_7,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_8,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_9,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_10,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_11,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_12,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_13,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_14,ACQPS_Value); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_15,ACQPS_Value); -+ -+ // Enabled ADCINT1 and ADCINT2 -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_1); -+ ADC_enableInt(obj->adcHandle, ADC_IntNumber_2); -+ -+ // Disable continuous sampling for ADCINT1 and ADCINT2 -+ ADC_setIntMode(obj->adcHandle, ADC_IntNumber_1, ADC_IntMode_EOC); -+ ADC_setIntMode(obj->adcHandle, ADC_IntNumber_2, ADC_IntMode_EOC); -+ -+ //ADCINTs trigger at end of conversion -+ ADC_setIntPulseGenMode(obj->adcHandle, ADC_IntPulseGenMode_Prior); -+ -+ // Setup ADCINT1 and ADCINT2 trigger source -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_1, ADC_IntSrc_EOC6); -+ ADC_setIntSrc(obj->adcHandle, ADC_IntNumber_2, ADC_IntSrc_EOC14); -+ -+ // Setup each SOC's ADCINT trigger source -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_0, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_1, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_2, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_3, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_4, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_5, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_6, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_7, ADC_Int2TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_8, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_9, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_10, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_11, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_12, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_13, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_14, ADC_Int1TriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_15, ADC_Int1TriggersSOC); -+ -+ // Delay before converting ADC channels -+ usDelay(ADC_DELAY_usec); -+ -+ ADC_setSocFrcWord(obj->adcHandle, 0x00FF); -+ -+ while( index < SampleSize ) -+ { -+ //Wait for ADCINT1 to trigger, then add ADCRESULT0-7 registers to sum -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_1) == 0){} -+ -+ //Must clear ADCINT1 flag since INT1CONT = 0 -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_1); -+ -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_0); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_1); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_2); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_3); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_4); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_5); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_6); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_7); -+ -+ //Wait for ADCINT2 to trigger, then add ADCRESULT8-15 registers to sum -+ while (ADC_getIntFlag(obj->adcHandle, ADC_IntNumber_2) == 0){} -+ -+ //Must clear ADCINT2 flag since INT2CONT = 0 -+ ADC_clearIntFlag(obj->adcHandle, ADC_IntNumber_2); -+ -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_8); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_9); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_10); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_11); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_12); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_13); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_14); -+ Sum += ADC_readResult(obj->adcHandle, ADC_ResultNumber_15); -+ -+ index+=16; -+ -+ } // end data collection -+ -+ //Disable ADCINT1 and ADCINT2 to STOP the ping-pong sampling -+ ADC_disableInt(obj->adcHandle, ADC_IntNumber_1); -+ ADC_disableInt(obj->adcHandle, ADC_IntNumber_2); -+ -+ //Calculate average ADC sample value -+ Mean = Sum / SampleSize; -+ -+ // Clear start of conversion trigger -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_0, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_1, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_2, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_3, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_4, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_5, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_6, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_7, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_8, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_9, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_10, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_11, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_12, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_13, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_14, ADC_NoIntTriggersSOC); -+ ADC_setupSocTrigSrc(obj->adcHandle, ADC_SocNumber_15, ADC_NoIntTriggersSOC); -+ -+ //return the average -+ return(Mean); -+ } // end of HAL_AdcCalConversion() function -+ -+ -+ void HAL_disableWdog(HAL_Handle halHandle) -+ { -+ HAL_Obj *hal = (HAL_Obj *)halHandle; -+ -+ -+ WDOG_disable(hal->wdogHandle); -+ -+ -+ return; -+ } // end of HAL_disableWdog() function -+ -+ -+ void HAL_disableGlobalInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_disableGlobalInts(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_disableGlobalInts() function -+ -+ -+ void HAL_enableAdcInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable the PIE interrupts associated with the ADC interrupts -+ PIE_enableAdcInt(obj->pieHandle,ADC_IntNumber_1); -+ -+ -+ // enable the ADC interrupts -+ ADC_enableInt(obj->adcHandle,ADC_IntNumber_1); -+ -+ -+ // enable the cpu interrupt for ADC interrupts -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_10); -+ -+ return; -+ } // end of HAL_enableAdcInts() function -+ -+ -+ void HAL_enableDebugInt(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_enableDebugInt(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_enableDebugInt() function -+ -+ #error fix this -+ void HAL_enableDrv(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ DRV8301_enable(obj->drv8301Handle); -+ -+ return; -+ } // end of HAL_enableDrv() function -+ -+ -+ void HAL_enableGlobalInts(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CPU_enableGlobalInts(obj->cpuHandle); -+ -+ return; -+ } // end of HAL_enableGlobalInts() function -+ -+ -+ void HAL_enablePwmInt(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_enablePwmInt(obj->pieHandle,PWM_Number_1); -+ -+ -+ // enable the interrupt -+ PWM_enableInt(obj->pwmHandle[0]); -+ -+ -+ // enable the cpu interrupt for EPWM1_INT -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_3); -+ -+ return; -+ } // end of HAL_enablePwmInt() function -+ -+ -+ void HAL_enableTimer0Int(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_enableTimer0Int(obj->pieHandle); -+ -+ -+ // enable the interrupt -+ TIMER_enableInt(obj->timerHandle[0]); -+ -+ -+ // enable the cpu interrupt for TINT0 -+ CPU_enableInt(obj->cpuHandle,CPU_IntNumber_1); -+ -+ return; -+ } // end of HAL_enablePwmInt() function -+ -+ -+ void HAL_setupFaults(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint_least8_t cnt; -+ -+ -+ // Configure Trip Mechanism for the Motor control software -+ // -Cycle by cycle trip on CPU halt -+ // -One shot fault trip zone -+ // These trips need to be repeated for EPWM1 ,2 & 3 -+ for(cnt=0;cnt<3;cnt++) -+ { -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ6_NOT); -+ -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ3_NOT); -+ -+ PWM_enableTripZoneSrc(obj->pwmHandle[cnt],PWM_TripZoneSrc_CycleByCycle_TZ2_NOT); -+ -+ // What do we want the OST/CBC events to do? -+ // TZA events can force EPWMxA -+ // TZB events can force EPWMxB -+ -+ PWM_setTripZoneState_TZA(obj->pwmHandle[cnt],PWM_TripZoneState_EPWM_Low); -+ PWM_setTripZoneState_TZB(obj->pwmHandle[cnt],PWM_TripZoneState_EPWM_Low); -+ } -+ -+ return; -+ } // end of HAL_setupFaults() function -+ -+ -+ HAL_Handle HAL_init(void *pMemory,const size_t numBytes) -+ { -+ uint_least8_t cnt; -+ HAL_Handle handle; -+ HAL_Obj *obj; -+ -+ -+ if(numBytes < sizeof(HAL_Obj)) -+ return((HAL_Handle)NULL); -+ -+ -+ // assign the handle -+ handle = (HAL_Handle)pMemory; -+ -+ -+ // assign the object -+ obj = (HAL_Obj *)handle; -+ -+ -+ // initialize the watchdog driver -+ obj->wdogHandle = WDOG_init((void *)WDOG_BASE_ADDR,sizeof(WDOG_Obj)); -+ -+ -+ // disable watchdog -+ HAL_disableWdog(handle); -+ -+ -+ // initialize the ADC -+ obj->adcHandle = ADC_init((void *)ADC_BASE_ADDR,sizeof(ADC_Obj)); -+ -+ -+ // initialize the clock handle -+ obj->clkHandle = CLK_init((void *)CLK_BASE_ADDR,sizeof(CLK_Obj)); -+ -+ -+ // initialize the CPU handle -+ obj->cpuHandle = CPU_init(&cpu,sizeof(cpu)); -+ -+ -+ // initialize the FLASH handle -+ obj->flashHandle = FLASH_init((void *)FLASH_BASE_ADDR,sizeof(FLASH_Obj)); -+ -+ -+ // initialize the GPIO handle -+ obj->gpioHandle = GPIO_init((void *)GPIO_BASE_ADDR,sizeof(GPIO_Obj)); -+ -+ -+ // initialize the current offset estimator handles -+ for(cnt=0;cntoffsetHandle_I[cnt] = OFFSET_init(&obj->offset_I[cnt],sizeof(obj->offset_I[cnt])); -+ } -+ -+ -+ // initialize the voltage offset estimator handles -+ for(cnt=0;cntoffsetHandle_V[cnt] = OFFSET_init(&obj->offset_V[cnt],sizeof(obj->offset_V[cnt])); -+ } -+ -+ -+ // initialize the oscillator handle -+ obj->oscHandle = OSC_init((void *)OSC_BASE_ADDR,sizeof(OSC_Obj)); -+ -+ -+ // initialize the PIE handle -+ obj->pieHandle = PIE_init((void *)PIE_BASE_ADDR,sizeof(PIE_Obj)); -+ -+ -+ // initialize the PLL handle -+ obj->pllHandle = PLL_init((void *)PLL_BASE_ADDR,sizeof(PLL_Obj)); -+ -+ -+ // initialize the SPIA handle -+ obj->spiAHandle = SPI_init((void *)SPIA_BASE_ADDR,sizeof(SPI_Obj)); -+ -+ -+ // initialize the SPIB handle -+ obj->spiBHandle = SPI_init((void *)SPIB_BASE_ADDR,sizeof(SPI_Obj)); -+ -+ -+ // initialize PWM handles -+ obj->pwmHandle[0] = PWM_init((void *)PWM_ePWM1_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[1] = PWM_init((void *)PWM_ePWM2_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[2] = PWM_init((void *)PWM_ePWM3_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[3] = PWM_init((void *)PWM_ePWM4_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[4] = PWM_init((void *)PWM_ePWM5_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmHandle[5] = PWM_init((void *)PWM_ePWM6_BASE_ADDR,sizeof(PWM_Obj)); -+ -+ -+ // initialize PWM DAC handles -+ obj->pwmDacHandle[0] = PWMDAC_init((void *)PWM_ePWM7_BASE_ADDR,sizeof(PWM_Obj)); -+ obj->pwmDacHandle[1] = PWMDAC_init((void *)PWM_ePWM8_BASE_ADDR,sizeof(PWM_Obj)); -+ -+ -+ // initialize power handle -+ obj->pwrHandle = PWR_init((void *)PWR_BASE_ADDR,sizeof(PWR_Obj)); -+ -+ -+ // initialize timer handles -+ obj->timerHandle[0] = TIMER_init((void *)TIMER0_BASE_ADDR,sizeof(TIMER_Obj)); -+ obj->timerHandle[1] = TIMER_init((void *)TIMER1_BASE_ADDR,sizeof(TIMER_Obj)); -+ obj->timerHandle[2] = TIMER_init((void *)TIMER2_BASE_ADDR,sizeof(TIMER_Obj)); -+ -+ -+ // initialize drv8301 interface -+ obj->drv8301Handle[0] = DRV8301_init(&obj->drv8301[0],sizeof(obj->drv8301[0])); -+ obj->drv8301Handle[1] = DRV8301_init(&obj->drv8301[1],sizeof(obj->drv8301[1])); -+ -+ -+ #ifdef QEP -+ // initialize QEP driver -+ obj->qepHandle[0] = QEP_init((void*)QEP1_BASE_ADDR,sizeof(QEP_Obj)); -+ obj->qepHandle[1] = QEP_init((void*)QEP2_BASE_ADDR,sizeof(QEP_Obj)); -+ #endif -+ -+ return(handle); -+ } // end of HAL_init() function -+ -+ -+ void HAL_setParams(HAL_Handle handle,const USER_Params *pUserParams) -+ { -+ uint_least8_t cnt; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ _iq beta_lp_pu = _IQ(pUserParams->offsetPole_rps/(float_t)pUserParams->ctrlFreq_Hz); -+ -+ -+ HAL_setNumCurrentSensors(handle,pUserParams->numCurrentSensors); -+ HAL_setNumVoltageSensors(handle,pUserParams->numVoltageSensors); -+ -+ -+ for(cnt=0;cntcpuHandle); -+ -+ -+ // disable cpu interrupts -+ CPU_disableInts(obj->cpuHandle); -+ -+ -+ // clear cpu interrupt flags -+ CPU_clearIntFlags(obj->cpuHandle); -+ -+ -+ // setup the clocks -+ HAL_setupClks(handle); -+ -+ -+ // Setup the PLL -+ HAL_setupPll(handle,PLL_ClkFreq_90_MHz); -+ -+ -+ // setup the PIE -+ HAL_setupPie(handle); -+ -+ -+ // run the device calibration -+ HAL_cal(handle); -+ -+ -+ // setup the peripheral clocks -+ HAL_setupPeripheralClks(handle); -+ -+ -+ // setup the GPIOs -+ HAL_setupGpios(handle); -+ -+ -+ // setup the flash -+ HAL_setupFlash(handle); -+ -+ -+ // setup the ADCs -+ HAL_setupAdcs(handle); -+ -+ -+ // setup the PWMs -+ HAL_setupPwms(handle, -+ (float_t)pUserParams->systemFreq_MHz, -+ pUserParams->pwmPeriod_usec, -+ USER_NUM_PWM_TICKS_PER_ISR_TICK); -+ -+ -+ // setup the spiA -+ HAL_setupSpiA(handle); -+ -+ -+ // setup the spiB -+ HAL_setupSpiB(handle); -+ -+ -+ // setup the PWM DACs -+ HAL_setupPwmDacs(handle); -+ -+ -+ // setup the timers -+ HAL_setupTimers(handle, -+ (float_t)pUserParams->systemFreq_MHz); -+ -+ -+ // setup the drv8301 interface -+ HAL_setupGate(handle); -+ -+ -+ // set the default current bias -+ { -+ uint_least8_t cnt; -+ _iq bias = _IQ12mpy(ADC_dataBias,_IQ(pUserParams->current_sf)); -+ -+ for(cnt=0;cntcurrent_sf); -+ -+ HAL_setCurrentScaleFactor(handle,current_sf); -+ } -+ -+ -+ // set the default voltage bias -+ { -+ uint_least8_t cnt; -+ _iq bias = _IQ(0.0); -+ -+ for(cnt=0;cntvoltage_sf); -+ -+ HAL_setVoltageScaleFactor(handle,voltage_sf); -+ } -+ -+ return; -+ } // end of HAL_setParams() function -+ -+ -+ void HAL_setupAdcs(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // disable the ADCs -+ ADC_disable(obj->adcHandle); -+ -+ -+ // power up the bandgap circuit -+ ADC_enableBandGap(obj->adcHandle); -+ -+ -+ // set the ADC voltage reference source to internal -+ ADC_setVoltRefSrc(obj->adcHandle,ADC_VoltageRefSrc_Int); -+ -+ -+ // enable the ADC reference buffers -+ ADC_enableRefBuffers(obj->adcHandle); -+ -+ -+ // Set main clock scaling factor (max45MHz clock for the ADC module) -+ ADC_setDivideSelect(obj->adcHandle,ADC_DivideSelect_ClkIn_by_2); -+ -+ -+ // power up the ADCs -+ ADC_powerUp(obj->adcHandle); -+ -+ -+ // enable the ADCs -+ ADC_enable(obj->adcHandle); -+ -+ -+ // set the ADC interrupt pulse generation to prior -+ ADC_setIntPulseGenMode(obj->adcHandle,ADC_IntPulseGenMode_Prior); -+ -+ -+ // set the temperature sensor source to external -+ ADC_setTempSensorSrc(obj->adcHandle,ADC_TempSensorSrc_Ext); -+ -+ -+ // configure the interrupt sources -+ ADC_disableInt(obj->adcHandle,ADC_IntNumber_1); -+ ADC_setIntMode(obj->adcHandle,ADC_IntNumber_1,ADC_IntMode_ClearFlag); -+ ADC_setIntSrc(obj->adcHandle,ADC_IntNumber_1,ADC_IntSrc_EOC7); -+ -+ #error "Setup ADCs for 2 motor sampling" -+ //configure the SOCs for boostxldrv8301_revB on J1 & J5 Connection -+ // EXT IA-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_0,ADC_SocChanNumber_A3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_0,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_0,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IA-FB -+ // Duplicate conversion due to ADC Initial Conversion bug (SPRZ342) -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_1,ADC_SocChanNumber_A3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_1,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_1,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IB-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_2,ADC_SocChanNumber_B3); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_2,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_2,ADC_SocSampleDelay_9_cycles); -+ -+ // EXT IC-FB -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_3,ADC_SocChanNumber_A4); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_3,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_3,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb1 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_4,ADC_SocChanNumber_B4); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_4,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_4,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb2 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_5,ADC_SocChanNumber_A5); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_5,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_5,ADC_SocSampleDelay_9_cycles); -+ -+ // ADC-Vhb3 -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_6,ADC_SocChanNumber_B5); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_6,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_6,ADC_SocSampleDelay_9_cycles); -+ -+ // VDCBUS -+ ADC_setSocChanNumber(obj->adcHandle,ADC_SocNumber_7,ADC_SocChanNumber_B7); -+ ADC_setSocTrigSrc(obj->adcHandle,ADC_SocNumber_7,ADC_SocTrigSrc_EPWM4_ADCSOCA); -+ ADC_setSocSampleDelay(obj->adcHandle,ADC_SocNumber_7,ADC_SocSampleDelay_9_cycles); -+ -+ return; -+ } // end of HAL_setupAdcs() function -+ -+ -+ void HAL_setupClks(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // enable internal oscillator 1 -+ CLK_enableOsc1(obj->clkHandle); -+ -+ // set the oscillator source -+ CLK_setOscSrc(obj->clkHandle,CLK_OscSrc_Internal); -+ -+ // disable the external clock in -+ CLK_disableClkIn(obj->clkHandle); -+ -+ // disable the crystal oscillator -+ CLK_disableCrystalOsc(obj->clkHandle); -+ -+ // disable oscillator 2 -+ CLK_disableOsc2(obj->clkHandle); -+ -+ // set the low speed clock prescaler -+ CLK_setLowSpdPreScaler(obj->clkHandle,CLK_LowSpdPreScaler_SysClkOut_by_1); -+ -+ // set the clock out prescaler -+ CLK_setClkOutPreScaler(obj->clkHandle,CLK_ClkOutPreScaler_SysClkOut_by_1); -+ -+ return; -+ } // end of HAL_setupClks() function -+ -+ -+ void HAL_setupFlash(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ FLASH_enablePipelineMode(obj->flashHandle); -+ -+ FLASH_setNumPagedReadWaitStates(obj->flashHandle,FLASH_NumPagedWaitStates_3); -+ -+ FLASH_setNumRandomReadWaitStates(obj->flashHandle,FLASH_NumRandomWaitStates_3); -+ -+ FLASH_setOtpWaitStates(obj->flashHandle,FLASH_NumOtpWaitStates_5); -+ -+ FLASH_setStandbyWaitCount(obj->flashHandle,FLASH_STANDBY_WAIT_COUNT_DEFAULT); -+ -+ FLASH_setActiveWaitCount(obj->flashHandle,FLASH_ACTIVE_WAIT_COUNT_DEFAULT); -+ -+ return; -+ } // HAL_setupFlash() function -+ -+ -+ void HAL_setupGate(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ DRV8301_setSpiHandle(obj->drv8301Handle[0],obj->spiAHandle); -+ DRV8301_setGpioHandle(obj->drv8301Handle[0],obj->gpioHandle); -+ DRV8301_setGpioNumber(obj->drv8301Handle[0],GPIO_Number_50); -+ -+ DRV8301_setSpiHandle(obj->drv8301Handle[1],obj->spiBHandle); -+ DRV8301_setGpioHandle(obj->drv8301Handle[1],obj->gpioHandle); -+ DRV8301_setGpioNumber(obj->drv8301Handle[1],GPIO_Number_52); -+ -+ return; -+ } // HAL_setupGate() function -+ -+ -+ void HAL_setupGpios(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // PWM1 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_0,GPIO_0_Mode_EPWM1A); -+ -+ // PWM2 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_1,GPIO_1_Mode_EPWM1B); -+ -+ // PWM3 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_2,GPIO_2_Mode_EPWM2A); -+ -+ // PWM4 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_3,GPIO_3_Mode_EPWM2B); -+ -+ // PWM5 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_4,GPIO_4_Mode_EPWM3A); -+ -+ // PWM6 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_5,GPIO_5_Mode_EPWM3B); -+ -+ // PWM4A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_6,GPIO_6_Mode_EPWM4A); -+ -+ // PWM4B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_7,GPIO_7_Mode_EPWM4B); -+ -+ // PWM5A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_8,GPIO_8_Mode_EPWM5A); -+ -+ // PWM5B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_9,GPIO_9_Mode_EPWM5B); -+ -+ // PWM6A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_10,GPIO_10_Mode_EPWM6A); -+ -+ // PWM6B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_11,GPIO_11_Mode_EPWM6B); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_12,GPIO_12_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_13,GPIO_13_Mode_GeneralPurpose); -+ -+ // SPIB CLK -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_14,GPIO_14_Mode_SPICLKB); -+ -+ // UARTB RX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_15,GPIO_15_Mode_SCIRXDB); -+ -+ // SPIA SIMO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_16,GPIO_16_Mode_SPISIMOA); -+ -+ // SPIA SOMI -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_17,GPIO_17_Mode_SPISOMIA); -+ -+ // SPIA CLK -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_18,GPIO_18_Mode_SPICLKA); -+ -+ // SPIA CS -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_19,GPIO_19_Mode_SPISTEA_NOT); -+ -+ #ifdef QEP -+ // EQEP1A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_20,GPIO_20_Mode_EQEP1A); -+ -+ // EQEP1B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_21,GPIO_21_Mode_EQEP1B); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_22,GPIO_22_Mode_GeneralPurpose); -+ -+ // EQEP1I -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_23,GPIO_23_Mode_EQEP1I); -+ #else -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_20,GPIO_20_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_21,GPIO_21_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_22,GPIO_22_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_23,GPIO_23_Mode_GeneralPurpose); -+ #endif -+ -+ // SPIB SIMO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_24,GPIO_24_Mode_SPISIMOB); -+ -+ // SPIB SOMI -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_25,GPIO_25_Mode_SPISOMIB); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_26,GPIO_26_Mode_GeneralPurpose); -+ -+ // SPIB CS -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_27,GPIO_27_Mode_SPISTEB_NOT); -+ -+ // OCTWn -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_28,GPIO_28_Mode_TZ2_NOT); -+ -+ // FAULTn -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_29,GPIO_29_Mode_TZ3_NOT); -+ -+ // CAN RX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_30,GPIO_30_Mode_CANRXA); -+ -+ // CAN TX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_31,GPIO_31_Mode_CANTXA); -+ -+ // I2C Data -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_32,GPIO_32_Mode_SDAA); -+ -+ // I2C Clock -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_33,GPIO_33_Mode_SCLA); -+ -+ // LED D9 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_34,GPIO_34_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_34); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_34,GPIO_Direction_Output); -+ -+ // JTAG -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_35,GPIO_35_Mode_JTAG_TDI); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_36,GPIO_36_Mode_JTAG_TMS); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_37,GPIO_37_Mode_JTAG_TDO); -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_38,GPIO_38_Mode_JTAG_TCK); -+ -+ // LED D10 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_39,GPIO_39_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_39); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_39,GPIO_Direction_Output); -+ -+ // DAC1 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_40,GPIO_40_Mode_EPWM7A); -+ -+ // DAC2 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_41,GPIO_41_Mode_EPWM7B); -+ -+ // DAC3 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_42,GPIO_42_Mode_EPWM8A); -+ -+ // DAC4 -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_43,GPIO_43_Mode_EPWM8B); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_44,GPIO_44_Mode_GeneralPurpose); -+ -+ // DRV8301 Enable Gate -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_50,GPIO_50_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_50); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_50,GPIO_Direction_Output); -+ -+ // DRV8301 DC Calibration -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_51,GPIO_51_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_51); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_51,GPIO_Direction_Output); -+ -+ // DRV8301 Enable Gate -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_52,GPIO_52_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_52); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_52,GPIO_Direction_Output); -+ -+ // DRV8301 Device Calibration -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_53,GPIO_53_Mode_GeneralPurpose); -+ GPIO_setLow(obj->gpioHandle,GPIO_Number_53); -+ GPIO_setDirection(obj->gpioHandle,GPIO_Number_53,GPIO_Direction_Output); -+ -+ #ifdef QEP -+ // EQEP2A -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_54,GPIO_54_Mode_EQEP2A); -+ -+ // EQEP2B -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_55,GPIO_55_Mode_EQEP2B); -+ -+ // EQEP2I -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_56,GPIO_56_Mode_EQEP2I); -+ #else -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_54,GPIO_54_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_55,GPIO_55_Mode_GeneralPurpose); -+ -+ // GPIO -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_56,GPIO_56_Mode_GeneralPurpose); -+ #endif -+ -+ // No Connection -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_57,GPIO_57_Mode_GeneralPurpose); -+ -+ // UARTB TX -+ GPIO_setMode(obj->gpioHandle,GPIO_Number_58,GPIO_58_Mode_SCITXDB); -+ -+ return; -+ } // end of HAL_setupGpios() function -+ -+ -+ void HAL_setupPie(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ PIE_disable(obj->pieHandle); -+ -+ PIE_disableAllInts(obj->pieHandle); -+ -+ PIE_clearAllInts(obj->pieHandle); -+ -+ PIE_clearAllFlags(obj->pieHandle); -+ -+ PIE_setDefaultIntVectorTable(obj->pieHandle); -+ -+ PIE_enable(obj->pieHandle); -+ -+ return; -+ } // end of HAL_setupPie() function -+ -+ -+ void HAL_setupPeripheralClks(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ CLK_enableAdcClock(obj->clkHandle); -+ -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_1); -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_2); -+ CLK_enableCompClock(obj->clkHandle,CLK_CompNumber_3); -+ -+ CLK_disableEcap1Clock(obj->clkHandle); -+ -+ CLK_enableEcanaClock(obj->clkHandle); -+ -+ #ifdef QEP -+ CLK_enableEqep1Clock(obj->clkHandle); -+ CLK_enableEqep2Clock(obj->clkHandle); -+ #endif -+ -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_1); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_2); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_3); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_4); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_5); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_6); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_7); -+ CLK_enablePwmClock(obj->clkHandle,PWM_Number_8); -+ -+ CLK_disableHrPwmClock(obj->clkHandle); -+ -+ CLK_enableI2cClock(obj->clkHandle); -+ -+ CLK_disableLinAClock(obj->clkHandle); -+ -+ CLK_disableClaClock(obj->clkHandle); -+ -+ CLK_disableSciaClock(obj->clkHandle); -+ CLK_enableScibClock(obj->clkHandle); -+ -+ CLK_enableSpiaClock(obj->clkHandle); -+ CLK_enableSpibClock(obj->clkHandle); -+ -+ CLK_enableTbClockSync(obj->clkHandle); -+ -+ return; -+ } // end of HAL_setupPeripheralClks() function -+ -+ -+ void HAL_setupPll(HAL_Handle handle,const PLL_ClkFreq_e clkFreq) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // make sure PLL is not running in limp mode -+ if(PLL_getClkStatus(obj->pllHandle) != PLL_ClkStatus_Normal) -+ { -+ // reset the clock detect -+ PLL_resetClkDetect(obj->pllHandle); -+ -+ // ??????? -+ asm(" ESTOP0"); -+ } -+ -+ -+ // Divide Select must be ClkIn/4 before the clock rate can be changed -+ if(PLL_getDivideSelect(obj->pllHandle) != PLL_DivideSelect_ClkIn_by_4) -+ { -+ PLL_setDivideSelect(obj->pllHandle,PLL_DivideSelect_ClkIn_by_4); -+ } -+ -+ -+ if(PLL_getClkFreq(obj->pllHandle) != clkFreq) -+ { -+ // disable the clock detect -+ PLL_disableClkDetect(obj->pllHandle); -+ -+ // set the clock rate -+ PLL_setClkFreq(obj->pllHandle,clkFreq); -+ } -+ -+ -+ // wait until locked -+ while(PLL_getLockStatus(obj->pllHandle) != PLL_LockStatus_Done) {} -+ -+ -+ // enable the clock detect -+ PLL_enableClkDetect(obj->pllHandle); -+ -+ -+ // set divide select to ClkIn/2 to get desired clock rate -+ // NOTE: clock must be locked before setting this register -+ PLL_setDivideSelect(obj->pllHandle,PLL_DivideSelect_ClkIn_by_2); -+ -+ return; -+ } // end of HAL_setupPll() function -+ -+ -+ void HAL_setupPwms(HAL_Handle handle, -+ const float_t systemFreq_MHz, -+ const float_t pwmPeriod_usec, -+ const uint_least16_t numPwmTicksPerIsrTick) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t halfPeriod_cycles = (uint16_t)(systemFreq_MHz*pwmPeriod_usec) >> 1; -+ uint_least8_t cnt; -+ -+ -+ // turns off the outputs of the EPWM peripherals which will put the power switches -+ // into a high impedance state. -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ for(cnt=0;cnt<3;cnt++) -+ { -+ // setup the Time-Base Control Register (TBCTL) -+ PWM_setCounterMode(obj->pwmHandle[cnt],PWM_CounterMode_UpDown); -+ PWM_disableCounterLoad(obj->pwmHandle[cnt]); -+ PWM_setPeriodLoad(obj->pwmHandle[cnt],PWM_PeriodLoad_Immediate); -+ PWM_setSyncMode(obj->pwmHandle[cnt],PWM_SyncMode_EPWMxSYNC); -+ PWM_setHighSpeedClkDiv(obj->pwmHandle[cnt],PWM_HspClkDiv_by_1); -+ PWM_setClkDiv(obj->pwmHandle[cnt],PWM_ClkDiv_by_1); -+ PWM_setPhaseDir(obj->pwmHandle[cnt],PWM_PhaseDir_CountUp); -+ PWM_setRunMode(obj->pwmHandle[cnt],PWM_RunMode_FreeRun); -+ -+ // setup the Timer-Based Phase Register (TBPHS) -+ PWM_setPhase(obj->pwmHandle[cnt],0); -+ -+ // setup the Time-Base Counter Register (TBCTR) -+ PWM_setCount(obj->pwmHandle[cnt],0); -+ -+ // setup the Time-Base Period Register (TBPRD) -+ // set to zero initially -+ PWM_setPeriod(obj->pwmHandle[cnt],0); -+ -+ // setup the Counter-Compare Control Register (CMPCTL) -+ PWM_setLoadMode_CmpA(obj->pwmHandle[cnt],PWM_LoadMode_Zero); -+ PWM_setLoadMode_CmpB(obj->pwmHandle[cnt],PWM_LoadMode_Zero); -+ PWM_setShadowMode_CmpA(obj->pwmHandle[cnt],PWM_ShadowMode_Shadow); -+ PWM_setShadowMode_CmpB(obj->pwmHandle[cnt],PWM_ShadowMode_Immediate); -+ -+ // setup the Action-Qualifier Output A Register (AQCTLA) -+ PWM_setActionQual_CntUp_CmpA_PwmA(obj->pwmHandle[cnt],PWM_ActionQual_Set); -+ PWM_setActionQual_CntDown_CmpA_PwmA(obj->pwmHandle[cnt],PWM_ActionQual_Clear); -+ -+ // setup the Dead-Band Generator Control Register (DBCTL) -+ PWM_setDeadBandOutputMode(obj->pwmHandle[cnt],PWM_DeadBandOutputMode_EPWMxA_Rising_EPWMxB_Falling); -+ PWM_setDeadBandPolarity(obj->pwmHandle[cnt],PWM_DeadBandPolarity_EPWMxB_Inverted); -+ -+ // setup the Dead-Band Rising Edge Delay Register (DBRED) -+ PWM_setDeadBandRisingEdgeDelay(obj->pwmHandle[cnt],HAL_PWM_DBRED_CNT); -+ -+ // setup the Dead-Band Falling Edge Delay Register (DBFED) -+ PWM_setDeadBandFallingEdgeDelay(obj->pwmHandle[cnt],HAL_PWM_DBFED_CNT); -+ // setup the PWM-Chopper Control Register (PCCTL) -+ PWM_disableChopping(obj->pwmHandle[cnt]); -+ -+ // setup the Trip Zone Select Register (TZSEL) -+ PWM_disableTripZones(obj->pwmHandle[cnt]); -+ } -+ -+ -+ // setup the Event Trigger Selection Register (ETSEL) -+ PWM_disableInt(obj->pwmHandle[PWM_Number_1]); -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualZero); -+ PWM_enableSocAPulse(obj->pwmHandle[PWM_Number_1]); -+ -+ -+ // setup the Event Trigger Prescale Register (ETPS) -+ if(numPwmTicksPerIsrTick == 3) -+ { -+ PWM_setIntPeriod(obj->pwmHandle[PWM_Number_1],PWM_IntPeriod_ThirdEvent); -+ PWM_setSocAPeriod(obj->pwmHandle[PWM_Number_1],PWM_SocPeriod_ThirdEvent); -+ } -+ else if(numPwmTicksPerIsrTick == 2) -+ { -+ PWM_setIntPeriod(obj->pwmHandle[PWM_Number_1],PWM_IntPeriod_SecondEvent); -+ PWM_setSocAPeriod(obj->pwmHandle[PWM_Number_1],PWM_SocPeriod_SecondEvent); -+ } -+ else -+ { -+ PWM_setIntPeriod(obj->pwmHandle[PWM_Number_1],PWM_IntPeriod_FirstEvent); -+ PWM_setSocAPeriod(obj->pwmHandle[PWM_Number_1],PWM_SocPeriod_FirstEvent); -+ } -+ -+ -+ // setup the Event Trigger Clear Register (ETCLR) -+ PWM_clearIntFlag(obj->pwmHandle[PWM_Number_1]); -+ PWM_clearSocAFlag(obj->pwmHandle[PWM_Number_1]); -+ -+ // first step to synchronize the pwms -+ CLK_disableTbClockSync(obj->clkHandle); -+ -+ // since the PWM is configured as an up/down counter, the period register is set to one-half -+ // of the desired PWM period -+ PWM_setPeriod(obj->pwmHandle[PWM_Number_1],halfPeriod_cycles); -+ PWM_setPeriod(obj->pwmHandle[PWM_Number_2],halfPeriod_cycles); -+ PWM_setPeriod(obj->pwmHandle[PWM_Number_3],halfPeriod_cycles); -+ -+ // last step to synchronize the pwms -+ CLK_enableTbClockSync(obj->clkHandle); -+ -+ return; -+ } // end of HAL_setupPwms() function -+ -+ -+ void HAL_setupSpiA(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ SPI_reset(obj->spiAHandle); -+ SPI_setMode(obj->spiAHandle,SPI_Mode_Master); -+ SPI_setClkPolarity(obj->spiAHandle,SPI_ClkPolarity_OutputRisingEdge_InputFallingEdge); -+ SPI_enableTx(obj->spiAHandle); -+ SPI_enableTxFifoEnh(obj->spiAHandle); -+ SPI_enableTxFifo(obj->spiAHandle); -+ SPI_setTxDelay(obj->spiAHandle,0x0018); -+ SPI_setBaudRate(obj->spiAHandle,(SPI_BaudRate_e)(0x000d)); -+ SPI_setCharLength(obj->spiAHandle,SPI_CharLength_16_Bits); -+ SPI_setSuspend(obj->spiAHandle,SPI_TxSuspend_free); -+ SPI_enable(obj->spiAHandle); -+ -+ return; -+ } // end of HAL_setupSpiA() function -+ -+ -+ void HAL_setupSpiB(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ SPI_reset(obj->spiBHandle); -+ SPI_setMode(obj->spiBHandle,SPI_Mode_Master); -+ SPI_setClkPolarity(obj->spiBHandle,SPI_ClkPolarity_OutputRisingEdge_InputFallingEdge); -+ SPI_enableTx(obj->spiBHandle); -+ SPI_enableTxFifoEnh(obj->spiBHandle); -+ SPI_enableTxFifo(obj->spiBHandle); -+ SPI_setTxDelay(obj->spiBHandle,0x0018); -+ SPI_setBaudRate(obj->spiBHandle,(SPI_BaudRate_e)(0x000d)); -+ SPI_setCharLength(obj->spiBHandle,SPI_CharLength_16_Bits); -+ SPI_setSuspend(obj->spiBHandle,SPI_TxSuspend_free); -+ SPI_enable(obj->spiBHandle); -+ -+ return; -+ } // end of HAL_setupSpiB() function -+ -+ -+ void HAL_setupPwmDacs(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint16_t halfPeriod_cycles = 512; // 3000->10kHz, 1500->20kHz, 1000-> 30kHz, 500->60kHz -+ uint_least8_t cnt; -+ -+ -+ for(cnt=0;cnt<2;cnt++) -+ { -+ // initialize the Time-Base Control Register (TBCTL) -+ PWMDAC_setCounterMode(obj->pwmDacHandle[cnt],PWM_CounterMode_UpDown); -+ PWMDAC_disableCounterLoad(obj->pwmDacHandle[cnt]); -+ PWMDAC_setPeriodLoad(obj->pwmDacHandle[cnt],PWM_PeriodLoad_Immediate); -+ PWMDAC_setSyncMode(obj->pwmDacHandle[cnt],PWM_SyncMode_EPWMxSYNC); -+ PWMDAC_setHighSpeedClkDiv(obj->pwmDacHandle[cnt],PWM_HspClkDiv_by_1); -+ PWMDAC_setClkDiv(obj->pwmDacHandle[cnt],PWM_ClkDiv_by_1); -+ PWMDAC_setPhaseDir(obj->pwmDacHandle[cnt],PWM_PhaseDir_CountUp); -+ PWMDAC_setRunMode(obj->pwmDacHandle[cnt],PWM_RunMode_FreeRun); -+ -+ // initialize the Timer-Based Phase Register (TBPHS) -+ PWMDAC_setPhase(obj->pwmDacHandle[cnt],0); -+ -+ // setup the Time-Base Counter Register (TBCTR) -+ PWMDAC_setCount(obj->pwmDacHandle[cnt],0); -+ -+ // Initialize the Time-Base Period Register (TBPRD) -+ // set to zero initially -+ PWMDAC_setPeriod(obj->pwmDacHandle[cnt],0); -+ -+ // initialize the Counter-Compare Control Register (CMPCTL) -+ PWMDAC_setLoadMode_CmpA(obj->pwmDacHandle[cnt],PWM_LoadMode_Zero); -+ PWMDAC_setLoadMode_CmpB(obj->pwmDacHandle[cnt],PWM_LoadMode_Zero); -+ PWMDAC_setShadowMode_CmpA(obj->pwmDacHandle[cnt],PWM_ShadowMode_Shadow); -+ PWMDAC_setShadowMode_CmpB(obj->pwmDacHandle[cnt],PWM_ShadowMode_Shadow); -+ -+ // Initialize the Action-Qualifier Output A Register (AQCTLA) -+ PWMDAC_setActionQual_CntUp_CmpA_PwmA(obj->pwmDacHandle[cnt],PWM_ActionQual_Clear); -+ PWMDAC_setActionQual_CntDown_CmpA_PwmA(obj->pwmDacHandle[cnt],PWM_ActionQual_Set); -+ PWMDAC_setActionQual_CntUp_CmpB_PwmB(obj->pwmDacHandle[cnt],PWM_ActionQual_Clear); -+ PWMDAC_setActionQual_CntDown_CmpB_PwmB(obj->pwmDacHandle[cnt],PWM_ActionQual_Set); -+ -+ // Initialize the Dead-Band Control Register (DBCTL) -+ PWMDAC_disableDeadBand(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the PWM-Chopper Control Register (PCCTL) -+ PWMDAC_disableChopping(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the Trip-Zone Control Register (TZSEL) -+ PWMDAC_disableTripZones(obj->pwmDacHandle[cnt]); -+ -+ // Initialize the Trip-Zone Control Register (TZCTL) -+ PWMDAC_setTripZoneState_TZA(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_TZB(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCAEVT1(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCAEVT2(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ PWMDAC_setTripZoneState_DCBEVT1(obj->pwmDacHandle[cnt],PWM_TripZoneState_HighImp); -+ } -+ -+ // since the PWM is configured as an up/down counter, the period register is set to one-half -+ // of the desired PWM period -+ PWMDAC_setPeriod(obj->pwmDacHandle[PWMDAC_Number_1],halfPeriod_cycles); -+ PWMDAC_setPeriod(obj->pwmDacHandle[PWMDAC_Number_2],halfPeriod_cycles); -+ -+ return; -+ } // end of HAL_setupPwmDacs() function -+ -+ -+ void HAL_setupTimers(HAL_Handle handle,const float_t systemFreq_MHz) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint32_t timerPeriod_cnts = (uint32_t)(systemFreq_MHz * (float_t)1000000.0) - 1; -+ -+ // use timer 0 for frequency diagnostics -+ TIMER_setDecimationFactor(obj->timerHandle[0],0); -+ TIMER_setEmulationMode(obj->timerHandle[0],TIMER_EmulationMode_RunFree); -+ TIMER_setPeriod(obj->timerHandle[0],timerPeriod_cnts); -+ TIMER_setPreScaler(obj->timerHandle[0],0); -+ -+ // use timer 1 for CPU usage diagnostics -+ TIMER_setDecimationFactor(obj->timerHandle[1],0); -+ TIMER_setEmulationMode(obj->timerHandle[1],TIMER_EmulationMode_RunFree); -+ TIMER_setPeriod(obj->timerHandle[1],timerPeriod_cnts); -+ TIMER_setPreScaler(obj->timerHandle[1],0); -+ -+ return; -+ } // end of HAL_setupTimers() function -+ -+ #error fix the DRV8301 interface functions -+ void HAL_writeDrvData(HAL_Handle handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ DRV8301_writeData(obj->drv8301Handle,Spi_8301_Vars); -+ -+ return; -+ } // end of HAL_writeDrvData() function -+ -+ -+ void HAL_readDrvData(HAL_Handle handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ DRV8301_readData(obj->drv8301Handle,Spi_8301_Vars); -+ -+ return; -+ } // end of HAL_readDrvData() function -+ -+ -+ void HAL_setupDrvSpi(HAL_Handle handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ DRV8301_setupSpi(obj->drv8301Handle,Spi_8301_Vars); -+ -+ return; -+ } // end of HAL_setupDrvSpi() function -+ -+ -+ // end of file -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_both.h 2017-06-08 10:41:26.610948300 +0200 -*************** -*** 0 **** ---- 1,1285 ---- -+ #ifndef _HAL_H_ -+ #define _HAL_H_ -+ /* --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/boards/drv8301kit_revD/f28x/f2806xF/src/hal.h -+ //! \brief Contains public interface to various functions related -+ //! to the HAL object -+ //! -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ -+ // modules -+ -+ -+ // platforms -+ #include "hal_obj.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL HAL -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ -+ // ************************************************************************** -+ // the defines -+ -+ //! \brief Defines that a DRV8301 chip SPI port is used on the board. -+ #define DRV8301_SPI -+ -+ #define Device_cal (void (*)(void))0x3D7C80 -+ -+ //! \brief Defines used in oscillator calibration functions -+ //! \brief Defines the scale factor for Q15 fixed point numbers (2^15) -+ #define FP_SCALE 32768 -+ -+ //! \brief Defines the quantity added to Q15 numbers before converting to integer to round the number -+ #define FP_ROUND FP_SCALE/2 -+ -+ //! \brief Defines the amount to add to Q16.15 fixed point number to shift from a fine trim range of -+ //! \brief (-31 to 31) to (1 to 63). This guarantees that the trim is positive and can -+ //! \brief therefore be efficiently rounded -+ #define OSC_POSTRIM 32 -+ #define OSC_POSTRIM_OFF FP_SCALE*OSC_POSTRIM -+ -+ //! \brief The following functions return reference values stored in OTP. -+ -+ //! \brief Defines the slope used to compensate oscillator 1 (fine trim steps / ADC code). Stored in fixed point Q15 format -+ #define getOsc1FineTrimSlope() (*(int16_t (*)(void))0x3D7E90)() -+ -+ //! \brief Defines the oscillator 1 fine trim at high temp -+ #define getOsc1FineTrimOffset() (*(int16_t (*)(void))0x3D7E93)() -+ -+ //! \brief Defines the oscillator 1 coarse trim -+ #define getOsc1CoarseTrim() (*(int16_t (*)(void))0x3D7E96)() -+ -+ //! \brief Defines the slope used to compensate oscillator 2 (fine trim steps / ADC code). Stored -+ //! \brief in fixed point Q15 format. -+ #define getOsc2FineTrimSlope() (*(int16_t (*)(void))0x3D7E99)() -+ -+ //! \brief Defines the oscillator 2 fine trim at high temp -+ #define getOsc2FineTrimOffset() (*(int16_t (*)(void))0x3D7E9C)() -+ -+ //! \brief Defines the oscillator 2 coarse trim -+ #define getOsc2CoarseTrim() (*(int16_t (*)(void))0x3D7E9F)() -+ -+ //! \brief Defines the ADC reading of temperature sensor at reference temperature for compensation -+ #define getRefTempOffset() (*(int16_t (*)(void))0x3D7EA2)() -+ -+ //! \brief Defines the PWM deadband falling edge delay count (system clocks) -+ //! -+ #define HAL_PWM_DBFED_CNT 1 -+ -+ -+ //! \brief Defines the PWM deadband rising edge delay count (system clocks) -+ //! -+ #define HAL_PWM_DBRED_CNT 1 -+ -+ -+ //! \brief Defines the function to turn LEDs off -+ //! -+ #define HAL_turnLedOff HAL_setGpioLow -+ -+ -+ //! \brief Defines the function to turn LEDs on -+ //! -+ #define HAL_turnLedOn HAL_setGpioHigh -+ -+ -+ //! \brief Defines the function to turn LEDs on -+ //! -+ #define HAL_toggleLed HAL_toggleGpio -+ -+ -+ // ************************************************************************** -+ // the typedefs -+ -+ -+ //! \brief Enumeration for the QEP setup -+ //! -+ typedef enum -+ { -+ HAL_Qep_QEP1=0, //!< Select QEP1 -+ HAL_Qep_QEP2=1 //!< Select QEP2 -+ } HAL_QepSelect_e; -+ -+ -+ //! \brief Enumeration for the LED numbers -+ //! -+ typedef enum -+ { -+ HAL_Gpio_LED2=GPIO_Number_34, //!< GPIO pin number for LaunchPad LED D9 -+ HAL_Gpio_LED3=GPIO_Number_39 //!< GPIO pin number for LaunchPad LED D10 -+ } HAL_LedNumber_e; -+ -+ -+ //! \brief Enumeration for the sensor types -+ //! -+ typedef enum -+ { -+ HAL_SensorType_Current=0, //!< Enumeration for current sensor -+ HAL_SensorType_Voltage //!< Enumeration for voltage sensor -+ } HAL_SensorType_e; -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ extern interrupt void mainISR(void); -+ -+ -+ // ************************************************************************** -+ // the function prototypes -+ -+ -+ //! \brief Acknowledges an interrupt from the ADC so that another ADC interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] intNumber The interrupt number -+ static inline void HAL_acqAdcInt(HAL_Handle handle,const ADC_IntNumber_e intNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the ADC interrupt flag -+ ADC_clearIntFlag(obj->adcHandle,intNumber); -+ -+ -+ // Acknowledge interrupt from PIE group 10 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_10); -+ -+ return; -+ } // end of HAL_acqAdcInt() function -+ -+ -+ //! \brief Acknowledges an interrupt from the PWM so that another PWM interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ static inline void HAL_acqPwmInt(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the PWM interrupt flag -+ PWM_clearIntFlag(obj->pwmHandle[pwmNumber]); -+ -+ -+ // clear the SOCA flag -+ PWM_clearSocAFlag(obj->pwmHandle[pwmNumber]); -+ -+ -+ // Acknowledge interrupt from PIE group 3 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_3); -+ -+ return; -+ } // end of HAL_acqPwmInt() function -+ -+ -+ //! \brief Acknowledges an interrupt from Timer 0 so that another Timer 0 interrupt can -+ //! happen again. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_acqTimer0Int(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // clear the Timer 0 interrupt flag -+ TIMER_clearFlag(obj->timerHandle[0]); -+ -+ -+ // Acknowledge interrupt from PIE group 1 -+ PIE_clearInt(obj->pieHandle,PIE_GroupNumber_1); -+ -+ return; -+ } // end of HAL_acqTimer0Int() function -+ -+ -+ //! \brief Executes calibration routines -+ //! \details Values for offset and gain are programmed into OTP memory at -+ //! the TI factory. This calls and internal function that programs -+ //! these offsets and gains into the ADC registers. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_cal(HAL_Handle handle); -+ -+ -+ //! \brief Disables global interrupts -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_disableGlobalInts(HAL_Handle handle); -+ -+ -+ //! \brief Disables the watch dog -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_disableWdog(HAL_Handle handle); -+ -+ -+ //! \brief Disables the PWM device -+ //! \details Turns off the outputs of the EPWM peripherals which will put -+ //! the power switches into a high impedance state. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_disablePwm(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_setOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ return; -+ } // end of HAL_disablePwm() function -+ -+ -+ //! \brief Enables the ADC interrupts -+ //! \details Enables the ADC interrupt in the PIE, and CPU. Enables the -+ //! interrupt to be sent from the ADC peripheral. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableAdcInts(HAL_Handle handle); -+ -+ -+ //! \brief Enables the debug interrupt -+ //! \details The debug interrupt is used for the real-time debugger. It is -+ //! not needed if the real-time debugger is not used. Clears -+ //! bit 1 of ST1. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableDebugInt(HAL_Handle handle); -+ -+ -+ //! \brief Enables global interrupts -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableGlobalInts(HAL_Handle handle); -+ -+ -+ //! \brief Enables the 8301 device -+ //! \details Provides the correct timing to enable the drv8301 -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableDrv(HAL_Handle handle); -+ -+ -+ //! \brief Enables the PWM devices -+ //! \details Turns on the outputs of the EPWM peripheral which will allow -+ //! the power switches to be controlled. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_enablePwm(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_1]); -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_2]); -+ PWM_clearOneShotTrip(obj->pwmHandle[PWM_Number_3]); -+ -+ return; -+ } // end of HAL_enablePwm() function -+ -+ -+ //! \brief Enables the PWM interrupt -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enablePwmInt(HAL_Handle handle); -+ -+ -+ //! \brief Enables the Timer 0 interrupt -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_enableTimer0Int(HAL_Handle handle); -+ -+ -+ //! \brief Gets the ADC delay value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] socNumber The ADC SOC number -+ //! \return The ADC delay value -+ static inline ADC_SocSampleDelay_e HAL_getAdcSocSampleDelay(HAL_Handle handle, -+ const ADC_SocNumber_e socNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(ADC_getSocSampleDelay(obj->adcHandle,socNumber)); -+ } // end of HAL_getAdcSocSampleDelay() function -+ -+ -+ //! \brief Gets the ADC bias value -+ //! \details The ADC bias contains the feedback circuit's offset and bias. -+ //! Bias is the mathematical offset used when a bi-polar signal -+ //! is read into a uni-polar ADC. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \return The ADC bias value -+ static inline _iq HAL_getBias(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ uint_least8_t sensorNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ _iq bias = _IQ(0.0); -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ bias = obj->adcBias.I.value[sensorNumber]; -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ bias = obj->adcBias.V.value[sensorNumber]; -+ } -+ -+ return(bias); -+ } // end of HAL_getBias() function -+ -+ -+ //! \brief Gets the current scale factor -+ //! \details The current scale factor is defined as -+ //! USER_ADC_FULL_SCALE_CURRENT_A/USER_IQ_FULL_SCALE_CURRENT_A. -+ //! This scale factor is not used when converting between PU amps -+ //! and real amps. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The current scale factor -+ static inline _iq HAL_getCurrentScaleFactor(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(obj->current_sf); -+ } // end of HAL_getCurrentScaleFactor() function -+ -+ -+ //! \brief Gets the number of current sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The number of current sensors -+ static inline uint_least8_t HAL_getNumCurrentSensors(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ return(obj->numCurrentSensors); -+ } // end of HAL_getNumCurrentSensors() function -+ -+ -+ //! \brief Gets the number of voltage sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The number of voltage sensors -+ static inline uint_least8_t HAL_getNumVoltageSensors(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ return(obj->numVoltageSensors); -+ } // end of HAL_getNumVoltageSensors() function -+ -+ -+ //! \brief Gets the value used to set the low pass filter pole for offset estimation -+ //! \details An IIR single pole low pass filter is used to find the feedback circuit's -+ //! offsets. This function returns the value of that pole. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \return The value used to set the low pass filter pole, pu -+ static inline _iq HAL_getOffsetBeta_lp_pu(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq beta_lp_pu = _IQ(0.0); -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ beta_lp_pu = OFFSET_getBeta(obj->offsetHandle_I[sensorNumber]); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ beta_lp_pu = OFFSET_getBeta(obj->offsetHandle_V[sensorNumber]); -+ } -+ -+ return(beta_lp_pu); -+ } // end of HAL_getOffsetBeta_lp_pu() function -+ -+ -+ //! \brief Gets the offset value -+ //! \details The offsets that are calculated during the feedback circuits calibrations -+ //! are returned from the IIR filter object. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \return The offset value -+ static inline _iq HAL_getOffsetValue(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq offset = _IQ(0.0); -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ offset = OFFSET_getOffset(obj->offsetHandle_I[sensorNumber]); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ offset = OFFSET_getOffset(obj->offsetHandle_V[sensorNumber]); -+ } -+ -+ return(offset); -+ } // end of HAL_getOffsetValue() function -+ -+ -+ //! \brief Gets the voltage scale factor -+ //! \details The voltage scale factor is defined as -+ //! USER_ADC_FULL_SCALE_VOLTAGE_V/USER_IQ_FULL_SCALE_VOLTAGE_V. -+ //! This scale factor is not used when converting between PU volts -+ //! and real volts. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The voltage scale factor -+ static inline _iq HAL_getVoltageScaleFactor(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ return(obj->voltage_sf); -+ } // end of HAL_getVoltageScaleFactor() function -+ -+ -+ //! \brief Configures the fault protection logic -+ //! \details Sets up the trip zone inputs so that when a comparator -+ //! signal from outside the micro-controller trips a fault, -+ //! the EPWM peripheral blocks will force the -+ //! power switches into a high impedance state. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupFaults(HAL_Handle handle); -+ -+ -+ //! \brief Initializes the hardware abstraction layer (HAL) object -+ //! \details Initializes all handles to the microcontroller peripherals. -+ //! Returns a handle to the HAL object. -+ //! \param[in] pMemory A pointer to the memory for the hardware abstraction layer object -+ //! \param[in] numBytes The number of bytes allocated for the hardware abstraction layer object, bytes -+ //! \return The hardware abstraction layer (HAL) object handle -+ extern HAL_Handle HAL_init(void *pMemory,const size_t numBytes); -+ -+ -+ //! \brief Initializes the interrupt vector table -+ //! \details Points ADCINT1 to mainISR -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_initIntVectorTable(HAL_Handle handle) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ PIE_Obj *pie = (PIE_Obj *)obj->pieHandle; -+ -+ -+ ENABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ pie->ADCINT1 = &mainISR; -+ -+ DISABLE_PROTECTED_REGISTER_WRITE_MODE; -+ -+ return; -+ } // end of HAL_initIntVectorTable() function -+ -+ -+ //! \brief Reads the ADC data -+ //! \details Reads in the ADC result registers, adjusts for offsets, and -+ //! scales the values according to the settings in user.h. The -+ //! structure gAdcData holds three phase voltages, three line -+ //! currents, and one DC bus voltage. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pAdcData A pointer to the ADC data buffer -+ static inline void HAL_readAdcData(HAL_Handle handle,HAL_AdcData_t *pAdcData) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ _iq value; -+ _iq current_sf = HAL_getCurrentScaleFactor(handle); -+ _iq voltage_sf = HAL_getVoltageScaleFactor(handle); -+ -+ -+ // convert current A -+ // sample the first sample twice due to errata sprz342f, ignore the first sample -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_1); -+ value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[0]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->I.value[0] = value; -+ -+ // convert current B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_2); -+ value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[1]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->I.value[1] = value; -+ -+ // convert current C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_3); -+ value = _IQ12mpy(value,current_sf) - obj->adcBias.I.value[2]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->I.value[2] = value; -+ -+ // convert voltage A -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_4); -+ value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[0]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->V.value[0] = value; -+ -+ // convert voltage B -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_5); -+ value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[1]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->V.value[1] = value; -+ -+ // convert voltage C -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_6); -+ value = _IQ12mpy(value,voltage_sf) - obj->adcBias.V.value[2]; // divide by 2^numAdcBits = 2^12 -+ pAdcData->V.value[2] = value; -+ -+ // read the dcBus voltage value -+ value = (_iq)ADC_readResult(obj->adcHandle,ADC_ResultNumber_7); // divide by 2^numAdcBits = 2^12 -+ value = _IQ12mpy(value,voltage_sf); -+ pAdcData->dcBus = value; -+ -+ return; -+ } // end of HAL_readAdcData() function -+ -+ -+ //! \brief Reads the timer count -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \return The timer count -+ static inline uint32_t HAL_readTimerCnt(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ uint32_t timerCnt = TIMER_getCount(obj->timerHandle[timerNumber]); -+ -+ return(timerCnt); -+ } // end of HAL_readTimerCnt() function -+ -+ -+ //! \brief Reloads the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_reloadTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // reload the specified timer -+ TIMER_reload(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_reloadTimer() function -+ -+ -+ //! \brief Sets up the GATE object -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_setupGate(HAL_Handle handle); -+ -+ -+ //! \brief Starts the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_startTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // start the specified timer -+ TIMER_start(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_startTimer() function -+ -+ -+ //! \brief Stops the timer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ static inline void HAL_stopTimer(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // stop the specified timer -+ TIMER_stop(obj->timerHandle[timerNumber]); -+ -+ return; -+ } // end of HAL_stopTimer() function -+ -+ -+ //! \brief Sets the timer period -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \param[in] period The timer period -+ static inline void HAL_setTimerPeriod(HAL_Handle handle,const uint_least8_t timerNumber, const uint32_t period) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // set the period -+ TIMER_setPeriod(obj->timerHandle[timerNumber], period); -+ -+ return; -+ } // end of HAL_setTimerPeriod() function -+ -+ -+ //! \brief Gets the timer period -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] timerNumber The timer number, 0,1 or 2 -+ //! \return The timer period -+ static inline uint32_t HAL_getTimerPeriod(HAL_Handle handle,const uint_least8_t timerNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ uint32_t timerPeriod = TIMER_getPeriod(obj->timerHandle[timerNumber]); -+ -+ return(timerPeriod); -+ } // end of HAL_getTimerPeriod() function -+ -+ -+ //! \brief Sets the ADC SOC sample delay value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] socNumber The SOC number -+ //! \param[in] sampleDelay The delay value for the ADC -+ static inline void HAL_setAdcSocSampleDelay(HAL_Handle handle, -+ const ADC_SocNumber_e socNumber, -+ const ADC_SocSampleDelay_e sampleDelay) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ ADC_setSocSampleDelay(obj->adcHandle,socNumber,sampleDelay); -+ -+ return; -+ } // end of HAL_setAdcSocSampleDelay() function -+ -+ -+ //! \brief Sets the ADC bias value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] bias The ADC bias value -+ static inline void HAL_setBias(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ uint_least8_t sensorNumber, -+ const _iq bias) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ obj->adcBias.I.value[sensorNumber] = bias; -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ obj->adcBias.V.value[sensorNumber] = bias; -+ } -+ -+ return; -+ } // end of HAL_setBias() function -+ -+ -+ //! \brief Sets the GPIO pin high -+ //! \details Takes in the enumeration GPIO_Number_e and sets that GPIO -+ //! pin high. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_setGpioHigh(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO high -+ GPIO_setHigh(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioHigh() function -+ -+ -+ //! \brief Reads the specified GPIO pin -+ //! \details Takes in the enumeration GPIO_Number_e and reads that GPIO -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline bool HAL_readGpio(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // read GPIO -+ return(GPIO_read(obj->gpioHandle,gpioNumber)); -+ } // end of HAL_readGpio() function -+ -+ -+ //! \brief Toggles the GPIO pin -+ //! \details Takes in the enumeration GPIO_Number_e and toggles that GPIO -+ //! pin. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_toggleGpio(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO high -+ GPIO_toggle(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioHigh() function -+ -+ -+ //! \brief Sets the GPIO pin low -+ //! \details Takes in the enumeration GPIO_Number_e and clears that GPIO -+ //! pin low. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] gpioNumber The GPIO number -+ static inline void HAL_setGpioLow(HAL_Handle handle,const GPIO_Number_e gpioNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ // set GPIO low -+ GPIO_setLow(obj->gpioHandle,gpioNumber); -+ -+ return; -+ } // end of HAL_setGpioLow() function -+ -+ -+ //! \brief Sets the current scale factor in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] current_sf The current scale factor -+ static inline void HAL_setCurrentScaleFactor(HAL_Handle handle,const _iq current_sf) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ obj->current_sf = current_sf; -+ -+ return; -+ } // end of HAL_setCurrentScaleFactor() function -+ -+ -+ //! \brief Sets the number of current sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] numCurrentSensors The number of current sensors -+ static inline void HAL_setNumCurrentSensors(HAL_Handle handle,const uint_least8_t numCurrentSensors) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ obj->numCurrentSensors = numCurrentSensors; -+ -+ return; -+ } // end of HAL_setNumCurrentSensors() function -+ -+ -+ //! \brief Sets the number of voltage sensors -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] numVoltageSensors The number of voltage sensors -+ static inline void HAL_setNumVoltageSensors(HAL_Handle handle,const uint_least8_t numVoltageSensors) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ -+ obj->numVoltageSensors = numVoltageSensors; -+ -+ return; -+ } // end of HAL_setNumVoltageSensors() function -+ -+ -+ //! \brief Sets the value used to set the low pass filter pole for offset estimation -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] beta_lp_pu The value used to set the low pass filter pole, pu -+ static inline void HAL_setOffsetBeta_lp_pu(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber, -+ const _iq beta_lp_pu) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ OFFSET_setBeta(obj->offsetHandle_I[sensorNumber],beta_lp_pu); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ OFFSET_setBeta(obj->offsetHandle_V[sensorNumber],beta_lp_pu); -+ } -+ -+ return; -+ } // end of HAL_setOffsetBeta_lp_pu() function -+ -+ -+ //! \brief Sets the offset initial condition value for offset estimation -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] initCond The initial condition value -+ static inline void HAL_setOffsetInitCond(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber, -+ const _iq initCond) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ OFFSET_setInitCond(obj->offsetHandle_I[sensorNumber],initCond); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ OFFSET_setInitCond(obj->offsetHandle_V[sensorNumber],initCond); -+ } -+ -+ return; -+ } // end of HAL_setOffsetInitCond() function -+ -+ -+ //! \brief Sets the initial offset value for offset estimation -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] sensorType The sensor type -+ //! \param[in] sensorNumber The sensor number -+ //! \param[in] value The initial offset value -+ static inline void HAL_setOffsetValue(HAL_Handle handle, -+ const HAL_SensorType_e sensorType, -+ const uint_least8_t sensorNumber, -+ const _iq value) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ if(sensorType == HAL_SensorType_Current) -+ { -+ OFFSET_setOffset(obj->offsetHandle_I[sensorNumber],value); -+ } -+ else if(sensorType == HAL_SensorType_Voltage) -+ { -+ OFFSET_setOffset(obj->offsetHandle_V[sensorNumber],value); -+ } -+ -+ return; -+ } // end of HAL_setOffsetValue() function -+ -+ -+ //! \brief Sets the voltage scale factor in the hardware abstraction layer -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] voltage_sf The voltage scale factor -+ static inline void HAL_setVoltageScaleFactor(HAL_Handle handle,const _iq voltage_sf) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ obj->voltage_sf = voltage_sf; -+ -+ return; -+ } // end of HAL_setVoltageScaleFactor() function -+ -+ -+ //! \brief Sets the hardware abstraction layer parameters -+ //! \details Sets up the microcontroller peripherals. Creates all of the scale -+ //! factors for the ADC voltage and current conversions. Sets the initial -+ //! offset values for voltage and current measurements. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pUserParams The pointer to the user parameters -+ extern void HAL_setParams(HAL_Handle handle,const USER_Params *pUserParams); -+ -+ -+ //! \brief Sets up the ADCs (Analog to Digital Converters) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupAdcs(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the clocks -+ //! \details Sets up the micro-controller's main oscillator -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupClks(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the FLASH. -+ extern void HAL_setupFlash(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the GPIO (General Purpose I/O) pins -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupGpios(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the peripheral clocks -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPeripheralClks(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the PIE (Peripheral Interrupt Expansion) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPie(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the PLL (Phase Lock Loop) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] clkFreq The clock frequency -+ extern void HAL_setupPll(HAL_Handle handle,const PLL_ClkFreq_e clkFreq); -+ -+ -+ //! \brief Sets up the PWMs (Pulse Width Modulators) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] systemFreq_MHz The system frequency, MHz -+ //! \param[in] pwmPeriod_usec The PWM period, usec -+ //! \param[in] numPwmTicksPerIsrTick The number of PWM clock ticks per ISR clock tick -+ extern void HAL_setupPwms(HAL_Handle handle, -+ const float_t systemFreq_MHz, -+ const float_t pwmPeriod_usec, -+ const uint_least16_t numPwmTicksPerIsrTick); -+ -+ -+ //! \brief Sets up the PWM DACs (Pulse Width Modulator Digital to Analof Converters) -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupPwmDacs(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the spiA peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupSpiA(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the spiB peripheral -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ extern void HAL_setupSpiB(HAL_Handle handle); -+ -+ -+ //! \brief Sets up the timers -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] systemFreq_MHz The system frequency, MHz -+ void HAL_setupTimers(HAL_Handle handle,const float_t systemFreq_MHz); -+ -+ -+ //! \brief Updates the ADC bias values -+ //! \details This function is called before the motor is started. It sets the voltage -+ //! and current measurement offsets. -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ static inline void HAL_updateAdcBias(HAL_Handle handle) -+ { -+ uint_least8_t cnt; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ _iq bias; -+ -+ -+ // update the current bias -+ for(cnt=0;cntoffsetHandle_I[cnt]); -+ -+ HAL_setBias(handle,HAL_SensorType_Current,cnt,bias); -+ } -+ -+ -+ // update the voltage bias -+ for(cnt=0;cntoffsetHandle_V[cnt]); -+ -+ HAL_setBias(handle,HAL_SensorType_Voltage,cnt,bias); -+ } -+ -+ return; -+ } // end of HAL_updateAdcBias() function -+ -+ -+ //! \brief Writes DAC data to the PWM comparators for DAC (digital-to-analog conversion) output -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pDacData The pointer to the DAC data -+ static inline void HAL_writeDacData(HAL_Handle handle,HAL_DacData_t *pDacData) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // convert values from _IQ to _IQ15 -+ int16_t dacValue_1 = (int16_t)_IQtoIQ15(pDacData->value[0]); -+ int16_t dacValue_2 = (int16_t)_IQtoIQ15(pDacData->value[1]); -+ int16_t dacValue_3 = (int16_t)_IQtoIQ15(pDacData->value[2]); -+ int16_t dacValue_4 = (int16_t)_IQtoIQ15(pDacData->value[3]); -+ -+ // write the DAC data -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_1],dacValue_1); -+ PWMDAC_write_CmpB(obj->pwmDacHandle[PWMDAC_Number_1],dacValue_2); -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_2],dacValue_3); -+ PWMDAC_write_CmpA(obj->pwmDacHandle[PWMDAC_Number_2],dacValue_4); -+ -+ return; -+ } // end of HAL_writeDacData() function -+ -+ -+ //! \brief Writes PWM data to the PWM comparators for motor control -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pPwmData The pointer to the PWM data -+ static inline void HAL_writePwmData(HAL_Handle handle,HAL_PwmData_t *pPwmData) -+ { -+ uint_least8_t cnt; -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ PWM_Obj *pwm; -+ _iq period; -+ _iq pwmData_neg; -+ _iq pwmData_sat; -+ _iq pwmData_sat_dc; -+ _iq value; -+ uint16_t value_sat; -+ -+ for(cnt=0;cnt<3;cnt++) -+ { -+ pwm = (PWM_Obj *)obj->pwmHandle[cnt]; -+ period = (_iq)pwm->TBPRD; -+ pwmData_neg = _IQmpy(pPwmData->Tabc.value[cnt],_IQ(-1.0)); -+ pwmData_sat = _IQsat(pwmData_neg,_IQ(0.5),_IQ(-0.5)); -+ pwmData_sat_dc = pwmData_sat + _IQ(0.5); -+ value = _IQmpy(pwmData_sat_dc, period); -+ value_sat = (uint16_t)_IQsat(value, period, _IQ(0.0)); -+ -+ // write the PWM data -+ PWM_write_CmpA(obj->pwmHandle[cnt],value_sat); -+ } -+ -+ return; -+ } // end of HAL_writePwmData() function -+ -+ -+ //! \brief Reads PWM compare register A -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpA(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpA(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpA() function -+ -+ -+ //! \brief Reads PWM compare register B -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM compare value -+ static inline uint16_t HAL_readPwmCmpB(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the compare value to be returned -+ uint16_t pwmValue; -+ -+ pwmValue = PWM_get_CmpB(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmValue); -+ } // end of HAL_readPwmCmpB() function -+ -+ -+ //! \brief Reads PWM period register -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] pwmNumber The PWM number -+ //! \return The PWM period value -+ static inline uint16_t HAL_readPwmPeriod(HAL_Handle handle,const PWM_Number_e pwmNumber) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ -+ // the period value to be returned -+ uint16_t pwmPeriodValue; -+ -+ pwmPeriodValue = PWM_getPeriod(obj->pwmHandle[pwmNumber]); -+ -+ return(pwmPeriodValue); -+ } // end of HAL_readPwmPeriod() function -+ -+ -+ static inline void HAL_setTrigger(HAL_Handle handle,const int16_t minwidth) -+ { -+ HAL_Obj *obj = (HAL_Obj *)handle; -+ PWM_Obj *pwm1 = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ PWM_Obj *pwm2 = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ PWM_Obj *pwm3 = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ PWM_Obj *pwm; -+ bool ignorepwm1 = false; -+ bool ignorepwm2 = false; -+ bool ignorepwm3 = false; -+ -+ uint16_t nextPulse1 = (pwm1->CMPA + pwm1->CMPAM) / 2; -+ uint16_t nextPulse2 = (pwm2->CMPA + pwm2->CMPAM) / 2; -+ uint16_t nextPulse3 = (pwm3->CMPA + pwm3->CMPAM) / 2; -+ uint16_t minNextPulse; -+ -+ if(nextPulse1 < minwidth) ignorepwm1 = true; -+ if(nextPulse2 < minwidth) ignorepwm2 = true; -+ if(nextPulse3 < minwidth) ignorepwm3 = true; -+ -+ if((ignorepwm1 == false) && (ignorepwm2 == false) && (ignorepwm3 == false)) -+ { -+ minNextPulse = nextPulse1; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ -+ if(minNextPulse > nextPulse2) -+ { -+ minNextPulse = nextPulse2; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ } -+ -+ if(minNextPulse > nextPulse3) -+ { -+ minNextPulse = nextPulse3; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ } -+ } -+ else if((ignorepwm1 == false) && (ignorepwm2 == false) && (ignorepwm3 == true)) -+ { -+ minNextPulse = nextPulse1; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ -+ if(minNextPulse > nextPulse2) -+ { -+ minNextPulse = nextPulse2; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ } -+ } -+ else if((ignorepwm1 == false) && (ignorepwm2 == true) && (ignorepwm3 == false)) -+ { -+ minNextPulse = nextPulse1; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ -+ if(minNextPulse > nextPulse3) -+ { -+ minNextPulse = nextPulse3; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ } -+ } -+ else if((ignorepwm1 == false) && (ignorepwm2 == true) && (ignorepwm3 == true)) -+ { -+ minNextPulse = nextPulse1; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ } -+ else if((ignorepwm1 == true) && (ignorepwm2 == false) && (ignorepwm3 == false)) -+ { -+ minNextPulse = nextPulse2; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ -+ if(minNextPulse > nextPulse3) -+ { -+ minNextPulse = nextPulse3; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ } -+ } -+ else if((ignorepwm1 == true) && (ignorepwm2 == false) && (ignorepwm3 == true)) -+ { -+ minNextPulse = nextPulse2; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_2]; -+ } -+ else if((ignorepwm1 == true) && (ignorepwm2 == true) && (ignorepwm3 == false)) -+ { -+ minNextPulse = nextPulse3; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_3]; -+ } -+ else -+ { -+ minNextPulse = nextPulse1; -+ pwm = (PWM_Obj *)obj->pwmHandle[PWM_Number_1]; -+ } -+ -+ if(pwm->CMPAM >= (pwm->CMPA + pwm->DBFED)) -+ { -+ pwm1->CMPB = (pwm->CMPAM - (pwm->CMPA + pwm->DBFED)) / 2 + 1; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBDecr); -+ } -+ else -+ { -+ pwm1->CMPB = ((pwm->CMPA + pwm->DBFED) - pwm->CMPAM) / 2 + 1; -+ PWM_setSocAPulseSrc(obj->pwmHandle[PWM_Number_1],PWM_SocPulseSrc_CounterEqualCmpBIncr); -+ } -+ -+ return; -+ } // end of HAL_setTrigger() function -+ -+ -+ //! \brief Selects the analog channel used for calibration -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] chanNumber The channel number -+ void HAL_AdcCalChanSelect(HAL_Handle handle, const ADC_SocChanNumber_e chanNumber); -+ -+ -+ //! \brief Reads the converted value from the selected calibration channel -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \return The converted value -+ uint16_t HAL_AdcCalConversion(HAL_Handle handle); -+ -+ -+ //! \brief Executes the offset calibration of the ADC -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_AdcOffsetSelfCal(HAL_Handle handle); -+ -+ -+ //! \brief Converts coarse and fine oscillator trim values into a single 16bit word value -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] coarse The coarse trim portion of the oscillator trim -+ //! \param[in] fine The fine trim portion of the oscillator trim -+ //! \return The combined trim value -+ uint16_t HAL_getOscTrimValue(int16_t coarse, int16_t fine); -+ -+ -+ //! \brief Executes the oscillator 1 and 2 calibration functions -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_OscTempComp(HAL_Handle handle); -+ -+ -+ //! \brief Executes the oscillator 1 calibration based on input sample -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_osc1Comp(HAL_Handle handle, const int16_t sensorSample); -+ -+ -+ //! \brief Executes the oscillator 2 calibration based on input sample -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ void HAL_osc2Comp(HAL_Handle handle, const int16_t sensorSample); -+ -+ -+ //! \brief Writes data to the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] Spi_8301_Vars SPI variables -+ void HAL_writeDrvData(HAL_Handle handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars); -+ -+ -+ //! \brief Reads data from the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] Spi_8301_Vars SPI variables -+ void HAL_readDrvData(HAL_Handle handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars); -+ -+ -+ //! \brief Sets up the SPI interface for the driver -+ //! \param[in] handle The hardware abstraction layer (HAL) handle -+ //! \param[in] Spi_8301_Vars SPI variables -+ void HAL_setupDrvSpi(HAL_Handle handle, DRV_SPI_8301_Vars_t *Spi_8301_Vars); -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_H_ definition -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj.h 2017-06-08 10:41:26.610948300 +0200 -*************** -*** 0 **** ---- 1,246 ---- -+ #ifndef _HAL_OBJ_H_ -+ #define _HAL_OBJ_H_ -+ /* --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/hal_obj.h -+ //! \brief Defines the structures for the HAL object -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // drivers -+ #include "sw/drivers/adc/src/32b/f28x/f2806x/adc.h" -+ #include "sw/drivers/clk/src/32b/f28x/f2806x/clk.h" -+ #include "sw/drivers/cpu/src/32b/f28x/f2806x/cpu.h" -+ #include "sw/drivers/flash/src/32b/f28x/f2806x/flash.h" -+ #include "sw/drivers/gpio/src/32b/f28x/f2806x/gpio.h" -+ #include "sw/drivers/osc/src/32b/f28x/f2806x/osc.h" -+ #include "sw/drivers/pie/src/32b/f28x/f2806x/pie.h" -+ #include "sw/drivers/pll/src/32b/f28x/f2806x/pll.h" -+ #include "sw/drivers/pwm/src/32b/f28x/f2806x/pwm.h" -+ #include "sw/drivers/pwmdac/src/32b/f28x/f2806x/pwmdac.h" -+ #include "sw/drivers/pwr/src/32b/f28x/f2806x/pwr.h" -+ #include "sw/drivers/spi/src/32b/f28x/f2806x/spi.h" -+ #include "sw/drivers/timer/src/32b/f28x/f2806x/timer.h" -+ #include "sw/drivers/wdog/src/32b/f28x/f2806x/wdog.h" -+ -+ -+ #ifdef QEP -+ #include "sw/drivers/qep/src/32b/f28x/f2806x/qep.h" -+ #endif -+ -+ // add custom drivers for usage of SPI -+ #include "sw/drivers/mcbsp/SPImcBSP.h" -+ #include "sw/drivers/dma/dma.h" -+ -+ // modules -+ #include "sw/modules/offset/src/32b/offset.h" -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/usDelay/src/32b/usDelay.h" -+ -+ -+ // platforms -+ #include "user.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL_OBJ HAL_OBJ -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ //! \brief Defines the ADC data -+ //! \details This data structure contains the voltage and current values that are used when -+ //! performing a HAL_AdcRead and then this structure is passed to the CTRL controller -+ //! and the FAST estimator. -+ //! -+ typedef struct _HAL_AdcData_t_ -+ { -+ MATH_vec3 I; //!< the current values -+ -+ MATH_vec3 V; //!< the voltage values -+ -+ _iq dcBus; //!< the dcBus value -+ -+ _iq I_dcBus; //!< the dcBus Current value -+ -+ _iq TempSensor; //!< the ADC-Data for the Temperature Sensor "TEMP.SEN." -+ -+ _iq AnalogIn[6];//!< the sampled Voltages at ADC24_0 ... ADC24_5 -+ -+ } HAL_AdcData_t; -+ -+ -+ //! \brief Defines the DAC data -+ //! \details This data structure contains the pwm values that are used for the DAC output -+ //! on a lot of the hardware kits for debugging. -+ //! -+ typedef struct _HAL_DacData_t_ -+ { -+ _iq value[4]; //!< the DAC data -+ -+ } HAL_DacData_t; -+ -+ -+ //! \brief Defines the PWM data -+ //! \details This structure contains the pwm voltage values for the three phases. A -+ //! HAL_PwmData_t variable is filled with values from, for example, a space -+ //! vector modulator and then sent to functions like HAL_writePwmData() to -+ //! write to the PWM peripheral. -+ //! -+ typedef struct _HAL_PwmData_t_ -+ { -+ MATH_vec3 Tabc; //!< the PWM time-durations for each motor phase -+ -+ } HAL_PwmData_t; -+ -+ -+ //! \brief Defines the hardware abstraction layer (HAL) data -+ //! \details The HAL object contains all handles to peripherals. When accessing a -+ //! peripheral on a processor, use a HAL function along with the HAL handle -+ //! for that processor to access its peripherals. -+ //! -+ typedef struct _HAL_Obj_ -+ { -+ ADC_Handle adcHandle; //!< the ADC handle -+ -+ CLK_Handle clkHandle; //!< the clock handle -+ -+ CPU_Handle cpuHandle; //!< the CPU handle -+ -+ FLASH_Handle flashHandle; //!< the flash handle -+ -+ GPIO_Handle gpioHandle; //!< the GPIO handle -+ -+ OFFSET_Handle offsetHandle_I[3]; //!< the handles for the current offset estimators -+ OFFSET_Obj offset_I[3]; //!< the current offset objects -+ -+ OFFSET_Handle offsetHandle_V[3]; //!< the handles for the voltage offset estimators -+ OFFSET_Obj offset_V[3]; //!< the voltage offset objects -+ -+ OSC_Handle oscHandle; //!< the oscillator handle -+ -+ PIE_Handle pieHandle; //numCurrentSensors;cnt++) -+ { -+ OFFSET_run(obj->offsetHandle_I[cnt],pAdcData->I.value[cnt]); -+ } -+ -+ -+ // estimate the voltage offsets -+ for(cnt=0;cntnumVoltageSensors;cnt++) -+ { -+ OFFSET_run(obj->offsetHandle_V[cnt],pAdcData->V.value[cnt]); -+ } -+ -+ return; -+ } // end of HAL_runOffsetEst() function -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_OBJ_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_2mtr.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_2mtr.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_2mtr.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_2mtr.h 2017-06-08 10:41:26.626548300 +0200 -*************** -*** 0 **** ---- 1,270 ---- -+ #ifndef _HAL_OBJ_H_ -+ #define _HAL_OBJ_H_ -+ /* --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/hal_obj.h -+ //! \brief Defines the structures for the HAL object -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // drivers -+ #include "sw/drivers/adc/src/32b/f28x/f2806x/adc.h" -+ #include "sw/drivers/clk/src/32b/f28x/f2806x/clk.h" -+ #include "sw/drivers/cpu/src/32b/f28x/f2806x/cpu.h" -+ #include "sw/drivers/flash/src/32b/f28x/f2806x/flash.h" -+ #include "sw/drivers/gpio/src/32b/f28x/f2806x/gpio.h" -+ #include "sw/drivers/osc/src/32b/f28x/f2806x/osc.h" -+ #include "sw/drivers/pie/src/32b/f28x/f2806x/pie.h" -+ #include "sw/drivers/pll/src/32b/f28x/f2806x/pll.h" -+ #include "sw/drivers/pwm/src/32b/f28x/f2806x/pwm.h" -+ #include "sw/drivers/pwmdac/src/32b/f28x/f2806x/pwmdac.h" -+ #include "sw/drivers/pwr/src/32b/f28x/f2806x/pwr.h" -+ #include "sw/drivers/spi/src/32b/f28x/f2806x/spi.h" -+ #include "sw/drivers/timer/src/32b/f28x/f2806x/timer.h" -+ #include "sw/drivers/wdog/src/32b/f28x/f2806x/wdog.h" -+ #include "sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.h" -+ -+ -+ #ifdef QEP -+ #include "sw/drivers/qep/src/32b/f28x/f2806x/qep.h" -+ #endif -+ -+ // modules -+ #include "sw/modules/offset/src/32b/offset.h" -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/usDelay/src/32b/usDelay.h" -+ -+ -+ // platforms -+ #include "user1.h" -+ #include "user2.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL_OBJ HAL_OBJ -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the typedefs -+ -+ //! \brief Enumeration for the Motor setup -+ //! -+ typedef enum -+ { -+ HAL_MTR1=0, //!< Select Motor 1 -+ HAL_MTR2=1 //!< Select Motor 2 -+ } HAL_MtrSelect_e; -+ -+ -+ //! \brief Defines the ADC data -+ //! \details This data structure contains the voltage and current values that are used when -+ //! performing a HAL_AdcRead and then this structure is passed to the CTRL controller -+ //! and the FAST estimator. -+ //! -+ typedef struct _HAL_AdcData_t_ -+ { -+ MATH_vec3 I; //!< the current values -+ -+ MATH_vec3 V; //!< the voltage values -+ -+ _iq dcBus; //!< the dcBus value -+ -+ } HAL_AdcData_t; -+ -+ -+ //! \brief Defines the DAC data -+ //! \details This data structure contains the pwm values that are used for the DAC output -+ //! on a lot of the hardware kits for debugging. -+ //! -+ typedef struct _HAL_DacData_t_ -+ { -+ _iq value[4]; //!< the DAC data -+ -+ } HAL_DacData_t; -+ -+ -+ //! \brief Defines the PWM data -+ //! \details This structure contains the pwm voltage values for the three phases. A -+ //! HAL_PwmData_t variable is filled with values from, for example, a space -+ //! vector modulator and then sent to functions like HAL_writePwmData() to -+ //! write to the PWM peripheral. -+ //! -+ typedef struct _HAL_PwmData_t_ -+ { -+ MATH_vec3 Tabc; //!< the PWM time-durations for each motor phase -+ -+ } HAL_PwmData_t; -+ -+ -+ //! \brief Defines the hardware abstraction layer (HAL) data -+ //! \details The HAL object contains all handles to peripherals. When accessing a -+ //! peripheral on a processor, use a HAL function along with the HAL handle -+ //! for that processor to access its peripherals. -+ //! -+ typedef struct _HAL_Obj_ -+ { -+ ADC_Handle adcHandle; //!< the ADC handle -+ -+ CLK_Handle clkHandle; //!< the clock handle -+ -+ CPU_Handle cpuHandle; //!< the CPU handle -+ -+ FLASH_Handle flashHandle; //!< the flash handle -+ -+ GPIO_Handle gpioHandle; //!< the GPIO handle -+ -+ OSC_Handle oscHandle; //!< the oscillator handlefs -+ -+ PIE_Handle pieHandle; //numCurrentSensors;cnt++) -+ // { -+ // OFFSET_run(obj->offsetHandle_I[cnt],pAdcData->I.value[cnt]); -+ // } -+ -+ -+ // // estimate the voltage offsets -+ // for(cnt=0;cntnumVoltageSensors;cnt++) -+ // { -+ // OFFSET_run(obj->offsetHandle_V[cnt],pAdcData->V.value[cnt]); -+ // } -+ -+ // return; -+ //} // end of HAL_runOffsetEst() function -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_OBJ_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_both.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_both.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_both.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_both.h 2017-06-08 10:41:26.626548300 +0200 -*************** -*** 0 **** ---- 1,234 ---- -+ #ifndef _HAL_OBJ_H_ -+ #define _HAL_OBJ_H_ -+ /* --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/hal_obj.h -+ //! \brief Defines the structures for the HAL object -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // drivers -+ #include "sw/drivers/adc/src/32b/f28x/f2806x/adc.h" -+ #include "sw/drivers/clk/src/32b/f28x/f2806x/clk.h" -+ #include "sw/drivers/cpu/src/32b/f28x/f2806x/cpu.h" -+ #include "sw/drivers/flash/src/32b/f28x/f2806x/flash.h" -+ #include "sw/drivers/gpio/src/32b/f28x/f2806x/gpio.h" -+ #include "sw/drivers/osc/src/32b/f28x/f2806x/osc.h" -+ #include "sw/drivers/pie/src/32b/f28x/f2806x/pie.h" -+ #include "sw/drivers/pll/src/32b/f28x/f2806x/pll.h" -+ #include "sw/drivers/pwm/src/32b/f28x/f2806x/pwm.h" -+ #include "sw/drivers/pwmdac/src/32b/f28x/f2806x/pwmdac.h" -+ #include "sw/drivers/pwr/src/32b/f28x/f2806x/pwr.h" -+ #include "sw/drivers/spi/src/32b/f28x/f2806x/spi.h" -+ #include "sw/drivers/timer/src/32b/f28x/f2806x/timer.h" -+ #include "sw/drivers/wdog/src/32b/f28x/f2806x/wdog.h" -+ #include "sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.h" -+ -+ -+ #ifdef QEP -+ #include "sw/drivers/qep/src/32b/f28x/f2806x/qep.h" -+ #endif -+ -+ // modules -+ #include "sw/modules/offset/src/32b/offset.h" -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/usDelay/src/32b/usDelay.h" -+ -+ -+ // platforms -+ #include "user.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL_OBJ HAL_OBJ -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ //! \brief Defines the ADC data -+ //! \details This data structure contains the voltage and current values that are used when -+ //! performing a HAL_AdcRead and then this structure is passed to the CTRL controller -+ //! and the FAST estimator. -+ //! -+ typedef struct _HAL_AdcData_t_ -+ { -+ MATH_vec3 I; //!< the current values -+ -+ MATH_vec3 V; //!< the voltage values -+ -+ _iq dcBus; //!< the dcBus value -+ -+ } HAL_AdcData_t; -+ -+ -+ //! \brief Defines the DAC data -+ //! \details This data structure contains the pwm values that are used for the DAC output -+ //! on a lot of the hardware kits for debugging. -+ //! -+ typedef struct _HAL_DacData_t_ -+ { -+ _iq value[4]; //!< the DAC data -+ -+ } HAL_DacData_t; -+ -+ -+ //! \brief Defines the PWM data -+ //! \details This structure contains the pwm voltage values for the three phases. A -+ //! HAL_PwmData_t variable is filled with values from, for example, a space -+ //! vector modulator and then sent to functions like HAL_writePwmData() to -+ //! write to the PWM peripheral. -+ //! -+ typedef struct _HAL_PwmData_t_ -+ { -+ MATH_vec3 Tabc; //!< the PWM time-durations for each motor phase -+ -+ } HAL_PwmData_t; -+ -+ -+ //! \brief Defines the hardware abstraction layer (HAL) data -+ //! \details The HAL object contains all handles to peripherals. When accessing a -+ //! peripheral on a processor, use a HAL function along with the HAL handle -+ //! for that processor to access its peripherals. -+ //! -+ typedef struct _HAL_Obj_ -+ { -+ ADC_Handle adcHandle; //!< the ADC handle -+ -+ CLK_Handle clkHandle; //!< the clock handle -+ -+ CPU_Handle cpuHandle; //!< the CPU handle -+ -+ FLASH_Handle flashHandle; //!< the flash handle -+ -+ GPIO_Handle gpioHandle; //!< the GPIO handle -+ #error fix these for 2 motor -+ OFFSET_Handle offsetHandle_I[3]; //!< the handles for the current offset estimators -+ OFFSET_Obj offset_I[3]; //!< the current offset objects -+ -+ OFFSET_Handle offsetHandle_V[3]; //!< the handles for the voltage offset estimators -+ OFFSET_Obj offset_V[3]; //!< the voltage offset objects -+ -+ OSC_Handle oscHandle; //!< the oscillator handle -+ -+ PIE_Handle pieHandle; //numCurrentSensors;cnt++) -+ { -+ OFFSET_run(obj->offsetHandle_I[cnt],pAdcData->I.value[cnt]); -+ } -+ -+ -+ // estimate the voltage offsets -+ for(cnt=0;cntnumVoltageSensors;cnt++) -+ { -+ OFFSET_run(obj->offsetHandle_V[cnt],pAdcData->V.value[cnt]); -+ } -+ -+ return; -+ } // end of HAL_runOffsetEst() function -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_OBJ_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_mtr.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_mtr.h -*** motorware/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_mtr.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal_obj_mtr.h 2017-06-08 10:41:26.626548300 +0200 -*************** -*** 0 **** ---- 1,231 ---- -+ #ifndef _HAL_OBJ_H_ -+ #define _HAL_OBJ_H_ -+ /* --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/hal_obj.h -+ //! \brief Defines the structures for the HAL object -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // drivers -+ #include "sw/drivers/adc/src/32b/f28x/f2806x/adc.h" -+ #include "sw/drivers/clk/src/32b/f28x/f2806x/clk.h" -+ #include "sw/drivers/cpu/src/32b/f28x/f2806x/cpu.h" -+ #include "sw/drivers/flash/src/32b/f28x/f2806x/flash.h" -+ #include "sw/drivers/gpio/src/32b/f28x/f2806x/gpio.h" -+ #include "sw/drivers/osc/src/32b/f28x/f2806x/osc.h" -+ #include "sw/drivers/pie/src/32b/f28x/f2806x/pie.h" -+ #include "sw/drivers/pll/src/32b/f28x/f2806x/pll.h" -+ #include "sw/drivers/pwm/src/32b/f28x/f2806x/pwm.h" -+ #include "sw/drivers/pwmdac/src/32b/f28x/f2806x/pwmdac.h" -+ #include "sw/drivers/pwr/src/32b/f28x/f2806x/pwr.h" -+ #include "sw/drivers/spi/src/32b/f28x/f2806x/spi.h" -+ #include "sw/drivers/timer/src/32b/f28x/f2806x/timer.h" -+ #include "sw/drivers/wdog/src/32b/f28x/f2806x/wdog.h" -+ #include "sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.h" -+ -+ -+ #ifdef QEP -+ #include "sw/drivers/qep/src/32b/f28x/f2806x/qep.h" -+ #endif -+ -+ // modules -+ #include "sw/modules/offset/src/32b/offset.h" -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/usDelay/src/32b/usDelay.h" -+ -+ -+ // platforms -+ #include "user.h" -+ -+ -+ //! -+ //! -+ //! \defgroup HAL_OBJ HAL_OBJ -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ //! \brief Defines the ADC data -+ //! \details This data structure contains the voltage and current values that are used when -+ //! performing a HAL_AdcRead and then this structure is passed to the CTRL controller -+ //! and the FAST estimator. -+ //! -+ typedef struct _HAL_AdcData_t_ -+ { -+ MATH_vec3 I; //!< the current values -+ -+ MATH_vec3 V; //!< the voltage values -+ -+ _iq dcBus; //!< the dcBus value -+ -+ } HAL_AdcData_t; -+ -+ -+ //! \brief Defines the DAC data -+ //! \details This data structure contains the pwm values that are used for the DAC output -+ //! on a lot of the hardware kits for debugging. -+ //! -+ typedef struct _HAL_DacData_t_ -+ { -+ _iq value[4]; //!< the DAC data -+ -+ } HAL_DacData_t; -+ -+ -+ //! \brief Defines the PWM data -+ //! \details This structure contains the pwm voltage values for the three phases. A -+ //! HAL_PwmData_t variable is filled with values from, for example, a space -+ //! vector modulator and then sent to functions like HAL_writePwmData() to -+ //! write to the PWM peripheral. -+ //! -+ typedef struct _HAL_PwmData_t_ -+ { -+ MATH_vec3 Tabc; //!< the PWM time-durations for each motor phase -+ -+ } HAL_PwmData_t; -+ -+ -+ //! \brief Defines the hardware abstraction layer (HAL) data -+ //! \details The HAL object contains all handles to peripherals. When accessing a -+ //! peripheral on a processor, use a HAL function along with the HAL handle -+ //! for that processor to access its peripherals. -+ //! -+ typedef struct _HAL_Obj_ -+ { -+ ADC_Handle adcHandle; //!< the ADC handle -+ -+ CLK_Handle clkHandle; //!< the clock handle -+ -+ CPU_Handle cpuHandle; //!< the CPU handle -+ -+ FLASH_Handle flashHandle; //!< the flash handle -+ -+ GPIO_Handle gpioHandle; //!< the GPIO handle -+ -+ // OFFSET_Handle offsetHandle_I[3]; //!< the handles for the current offset estimators -+ // OFFSET_Obj offset_I[3]; //!< the current offset objects -+ // -+ // OFFSET_Handle offsetHandle_V[3]; //!< the handles for the voltage offset estimators -+ // OFFSET_Obj offset_V[3]; //!< the voltage offset objects -+ -+ OSC_Handle oscHandle; //!< the oscillator handlefs -+ -+ PIE_Handle pieHandle; //numCurrentSensors;cnt++) -+ // { -+ // OFFSET_run(obj->offsetHandle_I[cnt],pAdcData->I.value[cnt]); -+ // } -+ -+ -+ // // estimate the voltage offsets -+ // for(cnt=0;cntnumVoltageSensors;cnt++) -+ // { -+ // OFFSET_run(obj->offsetHandle_V[cnt],pAdcData->V.value[cnt]); -+ // } -+ -+ // return; -+ //} // end of HAL_runOffsetEst() function -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _HAL_OBJ_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.c -*** motorware/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.c 2017-07-21 11:00:31.105535500 +0200 -*************** -*** 0 **** ---- 1,136 ---- -+ #include "spiCTRL.h" -+ -+ // McBsp Buffer -+ uint16_t rx_buffer[BUFFER_SIZE]; -+ uint16_t tx_buffer[BUFFER_SIZE]; -+ -+ #pragma DATA_SECTION(rx_buffer, "DMARAML8") -+ #pragma DATA_SECTION(tx_buffer, "DMARAML8") -+ -+ // CRC table for McBsp -+ static uint16_t crc_table[256]; -+ -+ #define POLY ((uint16_t)0x1021) -+ #define START ((uint16_t)0xFFFF) -+ -+ void GenerateCrcTable(void) -+ { -+ uint16_t i, j; -+ uint16_t crc; -+ -+ for (i = 0; i < 256; i++) -+ { -+ crc = i << 8; -+ for (j = 0; j < 8; j++) -+ { -+ if (crc & 0x8000) -+ crc = (crc << 1) ^ POLY; -+ else -+ crc <<= 1; -+ } -+ crc_table[i] = crc; -+ } -+ } // end of GenerateCrcTable() function -+ -+ uint16_t CalcCrc(uint16_t *data, uint16_t len_words) -+ { -+ uint16_t crc = START; -+ uint16_t i; -+ uint16_t idx; -+ uint16_t octet; -+ -+ for (i = 0; i < len_words; ++i) -+ { -+ octet = data[i] & 0xFF; -+ -+ idx = ((crc >> 8) & 0xff) ^ octet; -+ crc = (crc << 8) ^ crc_table[idx]; -+ -+ octet = (data[i] >> 8) & 0xFF; -+ idx = ((crc >> 8) & 0xff) ^ octet; -+ crc = (crc << 8) ^ crc_table[idx]; -+ -+ } -+ return crc; -+ }// end of CalcCrc() function -+ -+ uint16_t GetNewSetpoints(DMA_Handle DMAhandle, tEspRx *my_esp_rx, tEspTx *my_esp_tx) -+ { -+ static int EspSuccessfullCountdown = REQUIRED_SUCCESSFUL_ESP_TRANSACTIONS; -+ static uint16_t offset_rx; -+ uint16_t CH2_start_idx_write_block_plus_NUM_BUFFER; -+ uint16_t CH1_start_idx_read_block_plus_NUM_BUFFER; -+ uint16_t CH2_start_idx_read_block; -+ uint16_t CH1_start_idx_write_block; -+ uint32_t ch1_addr, ch2_addr; -+ static uint32_t recv_addr_last = (uint32_t)rx_buffer; -+ -+ ch2_addr = DMAhandle->CH2.DST_ADDR_ACTIVE; -+ ch1_addr = DMAhandle->CH1.SRC_ADDR_ACTIVE; -+ -+ // check we're not in mid-transfer and if we are, reload addresses to keep them synchronized -+ if ((ch2_addr != DMAhandle->CH2.DST_ADDR_ACTIVE) || (ch1_addr != DMAhandle->CH1.SRC_ADDR_ACTIVE)) -+ { -+ ch2_addr = DMAhandle->CH2.DST_ADDR_ACTIVE; -+ ch1_addr = DMAhandle->CH1.SRC_ADDR_ACTIVE; -+ } -+ -+ #define OFFSET_RX_TX ((3*DATA_SIZE)-2) -+ -+ CH2_start_idx_write_block_plus_NUM_BUFFER = ((ch2_addr - (uint32_t)rx_buffer + DATA_SIZE*NUM_BUFFER - offset_rx )/DATA_SIZE)*DATA_SIZE + offset_rx; -+ CH2_start_idx_read_block = (CH2_start_idx_write_block_plus_NUM_BUFFER -1 - DATA_SIZE) % (NUM_BUFFER*DATA_SIZE); -+ -+ CH1_start_idx_read_block_plus_NUM_BUFFER = ((ch1_addr - (uint32_t)tx_buffer + DATA_SIZE*NUM_BUFFER - offset_rx - OFFSET_RX_TX)/DATA_SIZE)*DATA_SIZE + offset_rx + OFFSET_RX_TX; -+ CH1_start_idx_write_block = (CH1_start_idx_read_block_plus_NUM_BUFFER - 1 - DATA_SIZE) % (NUM_BUFFER*DATA_SIZE); -+ -+ if (ch2_addr < recv_addr_last) -+ recv_addr_last -= NUM_BUFFER*DATA_SIZE; -+ -+ -+ if ((ch2_addr - recv_addr_last) == DATA_SIZE) // new data received / transmitted -+ { -+ recv_addr_last = ch2_addr; -+ -+ my_esp_tx->CRC = CalcCrc((uint16_t*)my_esp_tx, sizeof(tEspRx)-1); -+ -+ // copy the response user data into the DMA memory fields to be sent -+ uint16_t cp; -+ for(cp = 0; cp < DATA_SIZE; cp++){ -+ tx_buffer[(CH1_start_idx_write_block+cp) % (NUM_BUFFER*DATA_SIZE)] = *( (uint16_t *) my_esp_tx + cp); -+ } -+ -+ // copy the setpoints / parameters from the DMA memory into the struct -+ uint16_t rx; -+ for(rx = 0; rx < DATA_SIZE; rx++){ -+ *((uint16_t *) my_esp_rx + rx) = rx_buffer[(CH2_start_idx_read_block+rx) % (NUM_BUFFER*DATA_SIZE)]; -+ } -+ -+ if (CalcCrc((uint16_t*)my_esp_rx, sizeof(tEspRx)-1) == my_esp_rx->CRC) -+ { -+ if (EspSuccessfullCountdown) -+ { -+ --EspSuccessfullCountdown; -+ return CACTUS_NOT_OK; -+ } -+ else -+ { -+ return CACTUS_NEW_DATA_OK; -+ // use new data -+ } -+ -+ } -+ else// if (esp_valid_idx == 0) -+ { -+ ++offset_rx; -+ if (offset_rx > DATA_SIZE) -+ offset_rx = 0; -+ -+ EspSuccessfullCountdown = REQUIRED_SUCCESSFUL_ESP_TRANSACTIONS; -+ return CACTUS_NOT_OK; -+ } -+ } -+ if (EspSuccessfullCountdown) -+ return CACTUS_NOT_OK; -+ else -+ return CACTUS_NO_RECEIVE; -+ } // end of GetNewSetpoints() function -diff -crwN motorware/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.h -*** motorware/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/modules/spiCTRL/src/32b/spiCTRL.h 2017-07-21 09:51:15.694735500 +0200 -*************** -*** 0 **** ---- 1,80 ---- -+ #ifndef SPICTRL_H_ -+ #define SPICTRL_H_ -+ -+ #include -+ -+ #define CACTUS_NOT_OK 0 -+ #define CACTUS_NO_RECEIVE 1 -+ #define CACTUS_NEW_DATA_OK 2 -+ -+ -+ typedef struct _tEspRx -+ { -+ uint16_t flags; -+ uint16_t i_Motor_numPolePairs; -+ float f_Motor_ratedCurrent; -+ float f_Motor_RoverLestFrequencyHz; -+ float f_Motor_fluxEstFrequency; -+ float f_CTRL_setpoint_speed; -+ float f_CTRL_setpoint_accel; -+ float f_resFloat0; -+ float f_resFloat1; -+ float f_resFloat2; -+ float f_resFloat3; -+ float f_resFloat4; -+ float f_resFloat5; -+ float f_resFloat6; -+ float f_resFloat7; -+ float f_resFloat8; -+ float f_resFloat9; -+ float f_resFloat10; -+ uint16_t u_STATUS_DOUT; -+ uint16_t reserved2; -+ uint16_t reserved3; -+ uint16_t CRC; -+ } tEspRx; -+ -+ typedef struct _tEspTx -+ { -+ uint16_t flags; -+ uint16_t u_STATUS_statusErr; -+ float f_STATUS_UdcBus; -+ float f_STATUS_IdcBus; -+ float f_STATUS_boardTemp; -+ float f_STATUS_currSpeed; -+ uint16_t u_CTRL_state; -+ uint16_t u_EST_state; -+ float f_IDENT_motorRs; -+ float f_IDENT_motorRr; -+ float f_IDENT_motorLsd; -+ float f_IDENT_motorLsq; -+ float f_EST_ratedFlux; -+ float f_ANALOG_IN_0; -+ float f_ANALOG_IN_1; -+ float f_ANALOG_IN_2; -+ float f_ANALOG_IN_3; -+ float f_ANALOG_IN_4; -+ float f_ANALOG_IN_5; -+ uint16_t u_STATUS_DIN; -+ uint16_t spiStatus; -+ uint16_t reserved2; -+ uint16_t CRC; -+ } tEspTx; -+ -+ #define DATA_SIZE (sizeof(struct _tEspRx) / sizeof(uint16_t)) -+ -+ #define NUM_BUFFER 3 // Not to be modified -+ #define BUFFER_SIZE (DATA_SIZE*NUM_BUFFER) // Not to be modified -+ -+ #define REQUIRED_SUCCESSFUL_ESP_TRANSACTIONS 5 -+ -+ -+ extern uint16_t rx_buffer[BUFFER_SIZE]; -+ extern uint16_t tx_buffer[BUFFER_SIZE]; -+ -+ -+ void GenerateCrcTable(void); -+ uint16_t CalcCrc(uint16_t *data, uint16_t len_words); -+ uint16_t GetNewSetpoints(DMA_Handle DMAhandle, tEspRx *my_esp_rx, tEspTx *my_esp_tx); -+ -+ #endif /* SPICTRL_H_ */ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.ccsproject 2017-06-08 10:42:10.462548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.cproject 2017-07-21 15:49:02.155735500 +0200 -*************** -*** 0 **** ---- 1,188 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab01/.project 2017-07-21 15:20:32.069735500 +0200 -*************** -*** 0 **** ---- 1,231 ---- -+ -+ -+ proj_lab01 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab01.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab01.c -+ -+ -+ proj_lab01.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab01.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.ccsproject 2017-06-08 10:41:34.114548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.cproject 2017-07-21 16:09:27.226735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02a/.project 2017-07-21 15:21:01.279735500 +0200 -*************** -*** 0 **** ---- 1,236 ---- -+ -+ -+ proj_lab02a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab02a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02a.c -+ -+ -+ proj_lab02a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.ccsproject 2017-06-08 10:42:10.493748300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.cproject 2017-07-21 16:10:04.306735500 +0200 -*************** -*** 0 **** ---- 1,191 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02b/.project 2017-07-21 15:21:48.899735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab02b -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab02b.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02b.c -+ -+ -+ proj_lab02b.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02b.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.ccsproject 2017-06-08 10:42:10.961748300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.cproject 2017-07-21 16:10:27.656735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02c/.project 2017-07-21 15:22:16.459735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab02c -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab02c.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02c.c -+ -+ -+ proj_lab02c.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02c.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.ccsproject 2017-06-08 10:42:10.992948300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.cproject 2017-07-21 16:10:48.946735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab02d/.project 2017-07-21 15:22:44.009735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab02d -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab02d.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02d.c -+ -+ -+ proj_lab02d.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab02d.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.ccsproject 2017-06-08 10:41:35.050548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.cproject 2017-07-21 16:11:13.366735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03a/.project 2017-07-21 15:23:03.589735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab03a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab03a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab03a.c -+ -+ -+ proj_lab03a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab03a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.ccsproject 2017-06-08 10:42:11.008548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.cproject 2017-07-21 16:11:35.926735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03b/.project 2017-07-21 15:23:21.899735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab03b -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ cpu_usage.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/cpu_usage/src/32b/cpu_usage.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ fem.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fem/src/32b/fem.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab03b.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab03b.c -+ -+ -+ proj_lab03b.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab03b.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.ccsproject 2017-06-08 10:42:11.024148300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.cproject 2017-07-21 16:12:01.996735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab03c/.project 2017-07-21 15:23:39.449735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab03c -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab03c.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab03c.c -+ -+ -+ proj_lab03c.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab03c.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.ccsproject 2017-06-08 10:42:11.039748300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.cproject 2017-07-21 16:12:26.866735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04/.project 2017-07-21 15:24:00.749735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab04 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab04.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab04.c -+ -+ -+ proj_lab04.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab04.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.ccsproject 2017-06-08 10:42:11.070948300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.cproject 2017-07-21 16:13:02.596735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab04a/.project 2017-07-21 15:24:20.639735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab04a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab04a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab04a.c -+ -+ -+ proj_lab04a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab04a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.ccsproject 2017-06-08 10:41:35.331348300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.cproject 2017-07-21 16:13:21.276735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05a/.project 2017-07-21 15:24:37.099735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab05a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab05a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab05a.c -+ -+ -+ proj_lab05a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab05a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.ccsproject 2017-06-08 10:41:35.346948300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.cproject 2017-07-21 16:13:45.126735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05b/.project 2017-07-21 15:27:03.689735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab05b -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab05b.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab05b.c -+ -+ -+ proj_lab05b.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab05b.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.ccsproject 2017-06-08 10:42:11.086548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.cproject 2017-07-21 16:14:11.866735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab05g/.project 2017-07-21 15:27:37.759735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab05g -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab05g.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab05g.c -+ -+ -+ proj_lab05g.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab05g.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.ccsproject 2017-06-08 10:42:11.086548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.cproject 2017-07-21 16:14:34.396735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07/.project 2017-07-21 15:27:55.749735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab07 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ cpu_usage.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/cpu_usage/src/32b/cpu_usage.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ fem.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fem/src/32b/fem.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab07.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab07.c -+ -+ -+ proj_lab07.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab07.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.ccsproject 2017-06-08 10:42:11.117748300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.cproject 2017-07-21 16:14:54.686735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab07a/.project 2017-07-21 15:28:13.379735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ proj_lab07a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab07a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab07a.c -+ -+ -+ proj_lab07a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab07a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.ccsproject 2017-06-08 10:42:11.133348300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.cproject 2017-07-21 16:15:17.516735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09/.project 2017-07-21 15:28:27.469735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab09 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fw.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fw/src/32b/fw.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab09.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab09.c -+ -+ -+ proj_lab09.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab09.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ svgen_current.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen_current.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.ccsproject 2017-06-08 10:42:11.148948300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.cproject 2017-07-21 16:15:37.786735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab09a/.project 2017-07-21 15:28:40.399735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab09a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fw.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fw/src/32b/fw.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab09a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab09a.c -+ -+ -+ proj_lab09a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab09a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ svgen_current.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen_current.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.ccsproject 2017-06-08 10:42:11.164548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.cproject 2017-07-21 16:15:58.526735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10a/.project 2017-07-21 15:28:55.529735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab10a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fw.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fw/src/32b/fw.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab10a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab10a.c -+ -+ -+ proj_lab10a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab10a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ svgen_current.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen_current.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.ccsproject 2017-06-08 10:42:11.180148300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.cproject 2017-07-21 16:16:24.266735500 +0200 -*************** -*** 0 **** ---- 1,194 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab10c/.project 2017-07-21 15:29:14.089735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab10c -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols_fpu32.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath_fpu32.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/float/IQmath_fpu32.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fw.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fw/src/32b/fw.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab10c.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab10c.c -+ -+ -+ proj_lab10c.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab10c.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ svgen_current.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen_current.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.ccsproject 2017-06-08 10:42:11.195748300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.cproject 2017-07-21 16:16:51.616735500 +0200 -*************** -*** 0 **** ---- 1,192 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11/.project 2017-07-21 15:29:31.079735500 +0200 -*************** -*** 0 **** ---- 1,261 ---- -+ -+ -+ proj_lab11 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ EST_getIdq_pu.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/EST_getIdq_pu.lib -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab11.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab11.c -+ -+ -+ proj_lab11.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab11.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.ccsproject 2017-06-08 10:42:11.211348300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.cproject 2017-07-21 16:17:13.396735500 +0200 -*************** -*** 0 **** ---- 1,192 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11a/.project 2017-07-21 15:29:46.889735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab11a -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ EST_getIdq_pu.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/EST_getIdq_pu.lib -+ -+ -+ EST_runPowerWarp.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/EST_runPowerWarp.lib -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ cpu_usage.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/cpu_usage/src/32b/cpu_usage.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fw.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fw/src/32b/fw.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab11a.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab11a.c -+ -+ -+ proj_lab11a.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab11a.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ svgen_current.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen_current.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.ccsproject 2017-06-08 10:42:11.226948300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.cproject 2017-07-21 16:17:34.616735500 +0200 -*************** -*** 0 **** ---- 1,192 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab11b/.project 2017-07-21 15:30:03.839735500 +0200 -*************** -*** 0 **** ---- 1,296 ---- -+ -+ -+ proj_lab11b -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ EST_getIdq_pu.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/EST_getIdq_pu.lib -+ -+ -+ EST_runPowerWarp.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/EST_runPowerWarp.lib -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ cpu_usage.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/cpu_usage/src/32b/cpu_usage.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fw.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/fw/src/32b/fw.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab11b.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab11b.c -+ -+ -+ proj_lab11b.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab11b.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ svgen_current.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen_current.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ vib_comp.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/vib_comp/lib/32b/vib_comp.lib -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.ccsproject 2017-06-08 10:42:11.242548300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.cproject 2017-07-21 16:17:56.936735500 +0200 -*************** -*** 0 **** ---- 1,221 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab20/.project 2017-07-21 15:30:19.499735500 +0200 -*************** -*** 0 **** ---- 1,276 ---- -+ -+ -+ proj_lab20 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ f28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/f28069F_ram_lnk.cmd -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab20.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab20.c -+ -+ -+ proj_lab20.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab20.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.ccsproject 2017-06-08 10:42:11.258148300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.cproject 2017-07-21 16:18:19.916735500 +0200 -*************** -*** 0 **** ---- 1,222 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/proj_lab21/.project 2017-07-21 15:30:32.979735500 +0200 -*************** -*** 0 **** ---- 1,291 ---- -+ -+ -+ proj_lab21 -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ afsel.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/afsel/lib/32b/f28x/afsel.lib -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ f28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/f28069F_ram_lnk.cmd -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ fstart.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fstart/lib/32b/f28x/fstart.lib -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ ipd_hfi.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipd/lib/32b/f28x/ipd_hfi.lib -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ proj_lab21.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab21.c -+ -+ -+ proj_lab21.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/proj_lab21.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.ccsproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.ccsproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.ccsproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.ccsproject 2017-06-08 10:42:10.961748300 +0200 -*************** -*** 0 **** ---- 1,6 ---- -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.cproject motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.cproject -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.cproject 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.cproject 2017-07-21 16:18:37.916735500 +0200 -*************** -*** 0 **** ---- 1,193 ---- -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.project motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.project -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.project 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/projects/ccs5/TAPAS_quick_start/.project 2017-07-21 15:30:55.039735500 +0200 -*************** -*** 0 **** ---- 1,281 ---- -+ -+ -+ TAPAS_quick_start -+ -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.genmakebuilder -+ -+ -+ ?name? -+ -+ -+ -+ org.eclipse.cdt.make.core.append_environment -+ true -+ -+ -+ org.eclipse.cdt.make.core.autoBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.buildArguments -+ -k -+ -+ -+ org.eclipse.cdt.make.core.buildCommand -+ ${CCS_UTILS_DIR}/bin/gmake -+ -+ -+ org.eclipse.cdt.make.core.buildLocation -+ ${BuildDirectory} -+ -+ -+ org.eclipse.cdt.make.core.cleanBuildTarget -+ clean -+ -+ -+ org.eclipse.cdt.make.core.contents -+ org.eclipse.cdt.make.core.activeConfigSettings -+ -+ -+ org.eclipse.cdt.make.core.enableAutoBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableCleanBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.enableFullBuild -+ true -+ -+ -+ org.eclipse.cdt.make.core.fullBuildTarget -+ all -+ -+ -+ org.eclipse.cdt.make.core.stopOnError -+ false -+ -+ -+ org.eclipse.cdt.make.core.useDefaultBuildCmd -+ true -+ -+ -+ -+ -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder -+ full,incremental, -+ -+ -+ -+ -+ -+ com.ti.ccstudio.core.ccsNature -+ org.eclipse.cdt.core.cnature -+ org.eclipse.cdt.managedbuilder.core.managedBuildNature -+ org.eclipse.cdt.core.ccnature -+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature -+ -+ -+ -+ 2806xRevB_FastSpinROMSymbols.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/fast/lib/32b/f28x/f2806x/2806xRevB_FastSpinROMSymbols.lib -+ -+ -+ CodeStartBranch.asm -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/CodeStartBranch.asm -+ -+ -+ F28069F.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F.cmd -+ -+ -+ F28069F_ram_lnk.cmd -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/cmd/f2806x/F28069F_ram_lnk.cmd -+ -+ -+ IQmath.lib -+ 1 -+ MW_INSTALL_DIR/sw/modules/iqmath/lib/f28x/32b/IQmath.lib -+ -+ -+ SPImcBSP.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/mcbsp/SPImcBSP.c -+ -+ -+ TMS320F28069_xds100v2.ccxml -+ 1 -+ MW_INSTALL_DIR/sw/ide/ccs/ccs5/targetConfigs/TMS320F28069_xds100v2.ccxml -+ -+ -+ adc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/adc/src/32b/f28x/f2806x/adc.c -+ -+ -+ clarke.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/clarke/src/32b/clarke.c -+ -+ -+ clk.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/clk/src/32b/f28x/f2806x/clk.c -+ -+ -+ cpu.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/cpu/src/32b/f28x/f2806x/cpu.c -+ -+ -+ ctrl.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ctrl/src/32b/ctrl.c -+ -+ -+ dma.c -+ 1 -+ PARENT-9-PROJECT_LOC/drivers/dma/dma.c -+ -+ -+ drv8301.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/drvic/drv8301/src/32b/f28x/f2806x/drv8301.c -+ -+ -+ filter_fo.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/filter/src/32b/filter_fo.c -+ -+ -+ flash.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/flash/src/32b/f28x/f2806x/flash.c -+ -+ -+ gpio.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/gpio/src/32b/f28x/f2806x/gpio.c -+ -+ -+ hal.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/hal/boards/TAPAS_V1.0/f28x/f2806x/src/hal.c -+ -+ -+ ipark.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/ipark/src/32b/ipark.c -+ -+ -+ memCopy.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/memCopy/src/memCopy.c -+ -+ -+ offset.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/offset/src/32b/offset.c -+ -+ -+ osc.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/osc/src/32b/f28x/f2806x/osc.c -+ -+ -+ park.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/park/src/32b/park.c -+ -+ -+ pid.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/pid/src/32b/pid.c -+ -+ -+ pie.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pie/src/32b/f28x/f2806x/pie.c -+ -+ -+ pll.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pll/src/32b/f28x/f2806x/pll.c -+ -+ -+ TAPAS_quick_start.c -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/TAPAS_quick_start.c -+ -+ -+ TAPAS_quick_start.js -+ 1 -+ MW_INSTALL_DIR/sw/solutions/instaspin_foc/src/TAPAS_quick_start.js -+ -+ -+ pwm.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwm/src/32b/f28x/f2806x/pwm.c -+ -+ -+ pwr.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/pwr/src/32b/f28x/f2806x/pwr.c -+ -+ -+ spi.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/spi/src/32b/f28x/f2806x/spi.c -+ -+ -+ spiCTRL.c -+ 1 -+ PARENT-9-PROJECT_LOC/modules/spiCTRL/src/32b/spiCTRL.c -+ -+ -+ svgen.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/svgen/src/32b/svgen.c -+ -+ -+ timer.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/timer/src/32b/f28x/f2806x/timer.c -+ -+ -+ traj.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/traj/src/32b/traj.c -+ -+ -+ usDelay.asm -+ 1 -+ MW_INSTALL_DIR/sw/modules/usDelay/src/32b/f28x/usDelay.asm -+ -+ -+ user.c -+ 1 -+ MW_INSTALL_DIR/sw/modules/user/src/32b/user.c -+ -+ -+ wdog.c -+ 1 -+ MW_INSTALL_DIR/sw/drivers/wdog/src/32b/f28x/f2806x/wdog.c -+ -+ -+ -+ -+ MW_INSTALL_DIR -+ $%7BPARENT-10-PROJECT_LOC%7D -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user.h -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user.h 2017-07-21 11:30:09.895935500 +0200 -*************** -*** 0 **** ---- 1,654 ---- -+ #ifndef _USER_H_ -+ #define _USER_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806xF/src/user.h -+ //! \brief Contains the public interface for user initialization data for the CTRL, HAL, and EST modules -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // modules -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/motor/src/32b/motor.h" -+ #include "sw/modules/est/src/32b/est.h" -+ #include "sw/modules/est/src/est_states.h" -+ #include "sw/modules/est/src/est_Flux_states.h" -+ #include "sw/modules/est/src/est_Ls_states.h" -+ #include "sw/modules/est/src/est_Rs_states.h" -+ #include "sw/modules/ctrl/src/32b/ctrl_obj.h" -+ -+ // platforms -+ #include "sw/modules/fast/src/32b/userParams.h" -+ -+ //! -+ //! -+ //! \defgroup USER USER -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ -+ //! \brief CURRENTS AND VOLTAGES -+ // ************************************************************************** -+ //! \brief Defines the voltage scale factor for the system -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_VOLTAGE_SF ((float_t)((USER_ADC_FULL_SCALE_VOLTAGE_V)/(USER_IQ_FULL_SCALE_VOLTAGE_V))) -+ -+ //! \brief Defines the voltage scale factor for the 6 external analog inputs -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_ANALOGIN_VOLTAGE_SF ((float_t)((USER_ADC_ANALOGIN_FULL_SCALE_VOLTAGE_V)/(USER_IQ_FULL_SCALE_VOLTAGE_V))) -+ -+ //! \brief Defines the current scale factor for the system -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_CURRENT_SF ((float_t)((USER_ADC_FULL_SCALE_CURRENT_A)/(USER_IQ_FULL_SCALE_CURRENT_A))) -+ -+ //! \brief Defines the full scale frequency for IQ variable, Hz -+ //! \brief All frequencies are converted into (pu) based on the ratio to this value -+ //! \brief this value MUST be larger than the maximum speed that you are expecting from the motor -+ #define USER_IQ_FULL_SCALE_FREQ_Hz (800.0) // 800 Example with buffer for 8-pole 6 KRPM motor to be run to 10 KRPM with field weakening; Hz =(RPM * Poles) / 120 -+ -+ //! \brief Defines full scale value for the IQ30 variable of Voltage inside the system -+ //! \brief All voltages are converted into (pu) based on the ratio to this value -+ //! \brief WARNING: this value MUST meet the following condition: USER_IQ_FULL_SCALE_VOLTAGE_V > 0.5 * USER_MOTOR_MAX_CURRENT * USER_MOTOR_Ls_d * USER_VOLTAGE_FILTER_POLE_rps, -+ //! \brief WARNING: otherwise the value can saturate and roll-over, causing an inaccurate value -+ //! \brief WARNING: this value is OFTEN greater than the maximum measured ADC value, especially with high Bemf motors operating at higher than rated speeds -+ //! \brief WARNING: if you know the value of your Bemf constant, and you know you are operating at a multiple speed due to field weakening, be sure to set this value higher than the expected Bemf voltage -+ //! \brief It is recommended to start with a value ~3x greater than the USER_ADC_FULL_SCALE_VOLTAGE_V and increase to 4-5x if scenarios where a Bemf calculation may exceed these limits -+ //! \brief This value is also used to calculate the minimum flux value: USER_IQ_FULL_SCALE_VOLTAGE_V/USER_EST_FREQ_Hz/0.7 -+ #define USER_IQ_FULL_SCALE_VOLTAGE_V (100.0) // 24.0 Example for boostxldrv8301_revB typical usage and the Anaheim motor -+ -+ //! \brief Defines the maximum voltage at the input to the AD converter -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the voltage sensing and scaling to the ADC input -+ #define USER_ADC_FULL_SCALE_VOLTAGE_V (67.925) // 26.314 boostxldrv8301_revB voltage scaling -+ -+ //! \brief Defines the maximum voltage at the analog inputs to drive 3.3V to the ADC-Input -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the voltage sensing and scaling to the ADC input -+ #define USER_ADC_ANALOGIN_FULL_SCALE_VOLTAGE_V (26.4702) -+ -+ //! \brief Defines the full scale current for the IQ variables, A -+ //! \brief All currents are converted into (pu) based on the ratio to this value -+ //! \brief WARNING: this value MUST be larger than the maximum current readings that you are expecting from the motor or the reading will roll over to 0, creating a control issue -+ #define USER_IQ_FULL_SCALE_CURRENT_A (70.0) // 20.0 Example for boostxldrv8301_revB typical usage -+ -+ //! \brief Defines the maximum current at the AD converter -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the current sensing and scaling to the ADC input -+ #define USER_ADC_FULL_SCALE_CURRENT_A (46.0) // 33.0 boostxldrv8301_revB current scaling -+ -+ //! \brief Defines the number of current sensors used -+ //! \brief Defined by the hardware capability present -+ //! \brief May be (2) or (3) -+ #define USER_NUM_CURRENT_SENSORS (3) // 3 Preferred setting for best performance across full speed range, allows for 100% duty cycle -+ -+ //! \brief Defines the number of voltage (phase) sensors -+ //! \brief Must be (3) -+ #define USER_NUM_VOLTAGE_SENSORS (3) // 3 Required -+ -+ //! \brief ADC current offsets for A, B, and C phases -+ //! \brief One-time hardware dependent, though the calibration can be done at run-time as well -+ //! \brief After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller -+ #define I_A_offset (0.4811285138) -+ #define I_B_offset (0.4643591642) -+ #define I_C_offset (0.4632356763) -+ -+ //! \brief ADC voltage offsets for A, B, and C phases -+ //! \brief One-time hardware dependent, though the calibration can be done at run-time as well -+ //! \brief After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller -+ #define V_A_offset (0.1605404019) -+ #define V_B_offset (0.1603416204) -+ #define V_C_offset (0.1619312167) -+ -+ //! \brief ADC voltage offset for I_DC_Bus -+ //! \until now, this has to be measured by hand and set manually... -+ //#define I_DC_Bus_offset (23.9750000000) -+ //#define USER_NUM_DCBUS_OFFSET_SAMPLES (10) -+ -+ //! \brief CLOCKS & TIMERS -+ // ************************************************************************** -+ //! \brief Defines the system clock frequency, MHz -+ #define USER_SYSTEM_FREQ_MHz (90.0) -+ -+ //! \brief Defines the address of controller handle -+ //! -+ #define USER_CTRL_HANDLE_ADDRESS (0x13C40) -+ #define USER_CTRL_HANDLE_ADDRESS_1 (0x13D36) -+ -+ //! \brief Defines the address of estimator handle -+ //! -+ #define USER_EST_HANDLE_ADDRESS (0x13840) -+ #define USER_EST_HANDLE_ADDRESS_1 (0x13A3E) -+ -+ //! \brief Defines the direct voltage (Vd) scale factor -+ //! -+ #define USER_VD_SF (0.95) -+ -+ //! \brief Defines the Pulse Width Modulation (PWM) period, usec -+ //! \brief Compile time calculation -+ #define USER_PWM_PERIOD_usec (1000.0/USER_PWM_FREQ_kHz) -+ -+ //! \brief Defines the Interrupt Service Routine (ISR) frequency, Hz -+ //! -+ #define USER_ISR_FREQ_Hz ((float_t)USER_PWM_FREQ_kHz * 1000.0 / (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK) -+ -+ //! \brief Defines the Interrupt Service Routine (ISR) period, usec -+ //! -+ #define USER_ISR_PERIOD_usec (USER_PWM_PERIOD_usec * (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK) -+ -+ //! \brief Defines the Pulse Width Modulation (PWM) frequency, kHz -+ //! \brief PWM frequency can be set directly here up to 30 KHz safely (60 KHz MAX in some cases) -+ //! \brief For higher PWM frequencies (60 KHz+ typical for low inductance, high current ripple motors) it is recommended to use the ePWM hardware -+ //! \brief and adjustable ADC SOC to decimate the ADC conversion done interrupt to the control system, or to use the software Que example. -+ //! \brief Otherwise you risk missing interrupts and disrupting the timing of the control state machine -+ #define USER_PWM_FREQ_kHz (90.0) //30.0 Example, 8.0 - 30.0 KHz typical; 45-80 KHz may be required for very low inductance, high speed motors -+ -+ //! \brief Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the -+ //! \brief Id and Iq PI current controllers. The Id and Iq current controller outputs are Vd and Vq. -+ //! \brief The relationship between Vs, Vd, and Vq is: Vs = sqrt(Vd^2 + Vq^2). In this FOC controller, the -+ //! \brief Vd value is set equal to USER_MAX_VS_MAG*USER_VD_MAG_FACTOR. Vq = sqrt(USER_MAX_VS_MAG^2 - Vd^2). -+ //! \brief Set USER_MAX_VS_MAG = 0.5 for a pure sinewave with a peak at SQRT(3)/2 = 86.6% duty cycle. No current reconstruction is needed for this scenario. -+ //! \brief Set USER_MAX_VS_MAG = 1/SQRT(3) = 0.5774 for a pure sinewave with a peak at 100% duty cycle. Current reconstruction will be needed for this scenario (Lab10a-x). -+ //! \brief Set USER_MAX_VS_MAG = 2/3 = 0.6666 to create a trapezoidal voltage waveform. Current reconstruction will be needed for this scenario (Lab10a-x). -+ //! \brief For space vector over-modulation, see lab 10 for details on system requirements that will allow the SVM generator to go all the way to trapezoidal. -+ #define USER_MAX_VS_MAG_PU (0.5) // Set to 0.5 if a current reconstruction technique is not used. Look at the module svgen_current in lab10a-x for more info. -+ -+ -+ //! \brief DECIMATION -+ // ************************************************************************** -+ //! \brief Defines the controller frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_CTRL_FREQ_Hz (uint_least32_t)(USER_ISR_FREQ_Hz/USER_NUM_ISR_TICKS_PER_CTRL_TICK) -+ -+ //! \brief Defines the estimator frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_EST_FREQ_Hz (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_EST_TICK) -+ -+ //! \brief Defines the trajectory frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_TRAJ_FREQ_Hz (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_TRAJ_TICK) -+ -+ //! \brief Defines the controller execution period, usec -+ //! \brief Compile time calculation -+ #define USER_CTRL_PERIOD_usec (USER_ISR_PERIOD_usec * USER_NUM_ISR_TICKS_PER_CTRL_TICK) -+ -+ //! \brief Defines the controller execution period, sec -+ //! \brief Compile time calculation -+ #define USER_CTRL_PERIOD_sec ((float_t)USER_CTRL_PERIOD_usec/(float_t)1000000.0) -+ -+ //! \brief Defines the number of pwm clock ticks per isr clock tick -+ //! Note: Valid values are 1, 2 or 3 only -+ #define USER_NUM_PWM_TICKS_PER_ISR_TICK (3) -+ -+ //! \brief Defines the number of isr ticks (hardware) per controller clock tick (software) -+ //! \brief Controller clock tick (CTRL) is the main clock used for all timing in the software -+ //! \brief Typically the PWM Frequency triggers (can be decimated by the ePWM hardware for less overhead) an ADC SOC -+ //! \brief ADC SOC triggers an ADC Conversion Done -+ //! \brief ADC Conversion Done triggers ISR -+ //! \brief This relates the hardware ISR rate to the software controller rate -+ //! \brief Typcially want to consider some form of decimation (ePWM hardware, CURRENT or EST) over 16KHz ISR to insure interrupt completes and leaves time for background tasks -+ #define USER_NUM_ISR_TICKS_PER_CTRL_TICK (2) // 2 Example, controller clock rate (CTRL) runs at PWM / 2; ex 30 KHz PWM, 15 KHz control -+ -+ //! \brief Defines the number of controller clock ticks per current controller clock tick -+ //! \brief Relationship of controller clock rate to current controller (FOC) rate -+ #define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK (1) // 1 Typical, Forward FOC current controller (Iq/Id/IPARK/SVPWM) runs at same rate as CTRL. -+ -+ //! \brief Defines the number of controller clock ticks per estimator clock tick -+ //! \brief Relationship of controller clock rate to estimator (FAST) rate -+ //! \brief Depends on needed dynamic performance, FAST provides very good results as low as 1 KHz while more dynamic or high speed applications may require up to 15 KHz -+ #define USER_NUM_CTRL_TICKS_PER_EST_TICK (1) // 1 Typical, FAST estimator runs at same rate as CTRL; -+ -+ //! \brief Defines the number of controller clock ticks per speed controller clock tick -+ //! \brief Relationship of controller clock rate to speed loop rate -+ #define USER_NUM_CTRL_TICKS_PER_SPEED_TICK (20) // 15 Typical to match PWM, ex: 15KHz PWM, controller, and current loop, 1KHz speed loop -+ -+ //! \brief Defines the number of controller clock ticks per trajectory clock tick -+ //! \brief Relationship of controller clock rate to trajectory loop rate -+ //! \brief Typically the same as the speed rate -+ #define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK (20) // 15 Typical to match PWM, ex: 10KHz controller & current loop, 1KHz speed loop, 1 KHz Trajectory -+ -+ //! \brief LIMITS -+ // ************************************************************************** -+ //! \brief Defines the maximum current slope for Id trajectory during PowerWarp -+ //! \brief For Induction motors only, controls how fast Id input can change under PowerWarp control -+ #define USER_MAX_CURRENT_SLOPE_POWERWARP (0.3*USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz) // 0.3*RES_EST_CURRENT / IQ_FULL_SCALE_CURRENT / TRAJ_FREQ Typical to produce 1-sec rampup/down -+ -+ //! \brief Defines the starting maximum acceleration AND deceleration for the speed profiles, Hz/s -+ //! \brief Updated in run-time through user functions -+ //! \brief Inverter, motor, inertia, and load will limit actual acceleration capability -+ #define USER_MAX_ACCEL_Hzps (9.0) // 20.0 Default -+ -+ //! \brief Defines maximum acceleration for the estimation speed profiles, Hz/s -+ //! \brief Only used during Motor ID (commission) -+ #define USER_MAX_ACCEL_EST_Hzps (5.0) // 5.0 Default, don't change -+ -+ //! \brief Defines the maximum current slope for Id trajectory during estimation -+ #define USER_MAX_CURRENT_SLOPE (USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz) // USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz Default, don't change -+ -+ //! \brief Defines the fraction of IdRated to use during rated flux estimation -+ //! -+ #define USER_IDRATED_FRACTION_FOR_RATED_FLUX (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the fraction of IdRated to use during inductance estimation -+ //! -+ #define USER_IDRATED_FRACTION_FOR_L_IDENT (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the IdRated delta to use during estimation -+ //! -+ #define USER_IDRATED_DELTA (0.00002) -+ -+ //! \brief Defines the fraction of SpeedMax to use during inductance estimation -+ //! -+ #define USER_SPEEDMAX_FRACTION_FOR_L_IDENT (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines flux fraction to use during inductance identification -+ //! -+ #define USER_FLUX_FRACTION (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the PowerWarp gain for computing Id reference -+ //! \brief Induction motors only -+ #define USER_POWERWARP_GAIN (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the maximum negative current to be applied in Id reference -+ //! \brief Used in field weakening only, this is a safety setting (e.g. to protect against demagnetization) -+ //! \brief User must also be aware that overall current magnitude [sqrt(Id^2 + Iq^2)] should be kept below any machine design specifications -+ #define USER_MAX_NEGATIVE_ID_REF_CURRENT_A (-0.5 * USER_MOTOR_MAX_CURRENT) // -0.5 * USER_MOTOR_MAX_CURRENT Example, adjust to meet safety needs of your motor -+ -+ //! \brief Defines the R/L estimation frequency, Hz -+ //! \brief User higher values for low inductance motors and lower values for higher inductance -+ //! \brief motors. The values can range from 100 to 300 Hz. -+ #define USER_R_OVER_L_EST_FREQ_Hz (200) // 300 Default -+ -+ //! \brief Defines the low speed limit for the flux integrator, pu -+ //! \brief This is the speed range (CW/CCW) at which the ForceAngle object is active, but only if Enabled -+ //! \brief Outside of this speed - or if Disabled - the ForcAngle will NEVER be active and the angle is provided by FAST only -+ #define USER_ZEROSPEEDLIMIT (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz) // 0.002 pu, 1-5 Hz typical; Hz = USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz -+ -+ //! \brief Defines the force angle frequency, Hz -+ //! \brief Frequency of stator vector rotation used by the ForceAngle object -+ //! \brief Can be positive or negative -+ #define USER_FORCE_ANGLE_FREQ_Hz (2.0 * USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz) // 1.0 Typical force angle start-up speed -+ -+ //! \brief POLES -+ // ************************************************************************** -+ //! \brief Defines the analog voltage filter pole location, rad/s -+ //! \brief Compile time calculation from Hz to rad/s -+ #define USER_VOLTAGE_FILTER_POLE_rps (2.0 * MATH_PI * USER_VOLTAGE_FILTER_POLE_Hz) -+ -+ //! \brief Defines the software pole location for the voltage and current offset estimation, rad/s -+ //! \brief Should not be changed from default of (20.0) -+ #define USER_OFFSET_POLE_rps (20.0) // 20.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the flux estimation, rad/s -+ //! \brief Should not be changed from default of (100.0) -+ #define USER_FLUX_POLE_rps (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the direction filter, rad/s -+ #define USER_DIRECTION_POLE_rps (6.0) // 6.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the speed control filter, rad/s -+ #define USER_SPEED_POLE_rps (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the DC bus filter, rad/s -+ #define USER_DCBUS_POLE_rps (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the convergence factor for the estimator -+ //! \brief Do not change from default for FAST -+ #define USER_EST_KAPPAQ (1.5) // 1.5 Default, do not change -+ -+ //! \brief Defines the analog voltage filter pole location, Hz -+ //! \brief Must match the hardware filter for Vph -+ #define USER_VOLTAGE_FILTER_POLE_Hz (697.015) // 364.682, value for boostxldrv8301_revB hardware -+ -+ // ************************************************************************** -+ // end the defines -+ -+ -+ //! \brief USER MOTOR & ID SETTINGS -+ // ************************************************************************** -+ -+ //! \brief Define each motor with a unique name and ID number -+ // BLDC & SMPM motors -+ #define Teknic_M2310PLN04K 104 -+ #define HackerImpeller 105 -+ #define RotoMaxx50CC 106 -+ #define DummyMotor 107 -+ -+ //! \brief Uncomment the motor which should be included at compile -+ //! \brief These motor ID settings and motor parameters are then available to be used by the control system -+ //! \brief Once your ideal settings and parameters are identified update the motor section here so it is available in the binary code -+ -+ //#define USER_MOTOR Teknic_M2310PLN04K -+ //#define USER_MOTOR HackerImpeller -+ //#define USER_MOTOR RotoMaxx50CC -+ #define USER_MOTOR DummyMotor -+ -+ #if (USER_MOTOR == Teknic_M2310PLN04K) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.47) -+ #define USER_MOTOR_Ls_d (0.00023495) -+ #define USER_MOTOR_Ls_q (0.00023495) -+ #define USER_MOTOR_RATED_FLUX (0.03955824) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_MAX_CURRENT (7.0) -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0)*USER_MOTOR_RES_EST_CURRENT -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (50.0) -+ -+ #define USER_MOTOR_ENCODER_LINES (4000.0) -+ #define USER_SYSTEM_INERTIA (0.02084666491) -+ #define USER_SYSTEM_FRICTION (0.1093267202) -+ -+ // CAUTION: -+ // IPD and AFSEL settings below are not necessarily valid for this motor -+ // Added so that proj_lab21 compiles without errors with default user.h settings -+ #define IPD_HFI_EXC_FREQ_HZ (750.0) // excitation frequency, Hz -+ #define IPD_HFI_LP_SPD_FILT_HZ (35.0) // lowpass filter cutoff frequency, Hz -+ #define IPD_HFI_HP_IQ_FILT_HZ (100.0) // highpass filter cutoff frequency, Hz -+ #define IPD_HFI_KSPD (60.0) // the speed gain value -+ #define IPD_HFI_EXC_MAG_COARSE_PU (0.25) // coarse IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_MAG_FINE_PU (0.2) // fine IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_TIME_COARSE_S (0.5) // coarse wait time, sec max 0.64 -+ #define IPD_HFI_EXC_TIME_FINE_S (0.5) // fine wait time, sec max 0.4 -+ #define AFSEL_FREQ_HIGH_PU (_IQ(20.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_FREQ_LOW_PU (_IQ(10.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_IQ_SLOPE_EST (_IQ((float)(1.0/0.1/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_HFI (_IQ((float)(1.0/10.0/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_THROTTLE_DWN (_IQ((float)(1.0/0.05/USER_ISR_FREQ_Hz))) -+ #define AFSEL_MAX_IQ_REF_EST (_IQ(0.4)) -+ #define AFSEL_MAX_IQ_REF_HFI (_IQ(0.4)) -+ -+ // identified using lab2c) and DRV8301revB on a F28069M Launchpad -+ // f_PWM = 45kHz -+ // PWMvsISR = 2 -+ // ISRvsCTRL = 1 -+ #elif (USER_MOTOR == HackerImpeller) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.03657501) -+ #define USER_MOTOR_Ls_d (0.00000129875) -+ #define USER_MOTOR_Ls_q (0.00000129875) -+ #define USER_MOTOR_RATED_FLUX (0.007515696) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (5.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-5.0) -+ #define USER_MOTOR_MAX_CURRENT (20.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (200.0) -+ -+ // CAUTION: -+ // IPD and AFSEL settings below are not necessarily valid for this motor -+ // Added so that proj_lab21 compiles without errors with default user.h settings -+ #define IPD_HFI_EXC_FREQ_HZ (750.0) // excitation frequency, Hz -+ #define IPD_HFI_LP_SPD_FILT_HZ (35.0) // lowpass filter cutoff frequency, Hz -+ #define IPD_HFI_HP_IQ_FILT_HZ (100.0) // highpass filter cutoff frequency, Hz -+ #define IPD_HFI_KSPD (60.0) // the speed gain value -+ #define IPD_HFI_EXC_MAG_COARSE_PU (0.25) // coarse IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_MAG_FINE_PU (0.2) // fine IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_TIME_COARSE_S (0.5) // coarse wait time, sec max 0.64 -+ #define IPD_HFI_EXC_TIME_FINE_S (0.5) // fine wait time, sec max 0.4 -+ #define AFSEL_FREQ_HIGH_PU (_IQ(20.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_FREQ_LOW_PU (_IQ(10.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_IQ_SLOPE_EST (_IQ((float)(1.0/0.1/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_HFI (_IQ((float)(1.0/10.0/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_THROTTLE_DWN (_IQ((float)(1.0/0.05/USER_ISR_FREQ_Hz))) -+ #define AFSEL_MAX_IQ_REF_EST (_IQ(0.4)) -+ #define AFSEL_MAX_IQ_REF_HFI (_IQ(0.4)) -+ -+ // identified using lab2c) and DRV8301revB on a F28069M Launchpad -+ // f_PWM = 45kHz -+ // PWMvsISR = 2 -+ // ISRvsCTRL = 1 -+ #elif (USER_MOTOR == RotoMaxx50CC) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (12) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.02940753) -+ #define USER_MOTOR_Ls_d (0.000006735248) -+ #define USER_MOTOR_Ls_q (0.000006735248) -+ #define USER_MOTOR_RATED_FLUX (0.01375589) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (5.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-5.0) -+ #define USER_MOTOR_MAX_CURRENT (20.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (200.0) -+ -+ // CAUTION: -+ // IPD and AFSEL settings below are not necessarily valid for this motor -+ // Added so that proj_lab21 compiles without errors with default user.h settings -+ #define IPD_HFI_EXC_FREQ_HZ (750.0) // excitation frequency, Hz -+ #define IPD_HFI_LP_SPD_FILT_HZ (35.0) // lowpass filter cutoff frequency, Hz -+ #define IPD_HFI_HP_IQ_FILT_HZ (100.0) // highpass filter cutoff frequency, Hz -+ #define IPD_HFI_KSPD (60.0) // the speed gain value -+ #define IPD_HFI_EXC_MAG_COARSE_PU (0.25) // coarse IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_MAG_FINE_PU (0.2) // fine IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_TIME_COARSE_S (0.5) // coarse wait time, sec max 0.64 -+ #define IPD_HFI_EXC_TIME_FINE_S (0.5) // fine wait time, sec max 0.4 -+ #define AFSEL_FREQ_HIGH_PU (_IQ(20.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_FREQ_LOW_PU (_IQ(10.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_IQ_SLOPE_EST (_IQ((float)(1.0/0.1/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_HFI (_IQ((float)(1.0/10.0/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_THROTTLE_DWN (_IQ((float)(1.0/0.05/USER_ISR_FREQ_Hz))) -+ #define AFSEL_MAX_IQ_REF_EST (_IQ(0.4)) -+ #define AFSEL_MAX_IQ_REF_HFI (_IQ(0.4)) -+ -+ #elif (USER_MOTOR == DummyMotor) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (NULL) -+ #define USER_MOTOR_Ls_d (0.0001) -+ #define USER_MOTOR_Ls_q (0.0001) -+ #define USER_MOTOR_RATED_FLUX (0.01) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_MAX_CURRENT (1.0) -+ #define USER_MOTOR_RES_EST_CURRENT (0.15)*USER_MOTOR_MAX_CURRENT -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0)*USER_MOTOR_RES_EST_CURRENT -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (50.0) -+ -+ // CAUTION: -+ // IPD and AFSEL settings below are not necessarily valid for this motor -+ // Added so that proj_lab21 compiles without errors with default user.h settings -+ #define IPD_HFI_EXC_FREQ_HZ (750.0) // excitation frequency, Hz -+ #define IPD_HFI_LP_SPD_FILT_HZ (35.0) // lowpass filter cutoff frequency, Hz -+ #define IPD_HFI_HP_IQ_FILT_HZ (100.0) // highpass filter cutoff frequency, Hz -+ #define IPD_HFI_KSPD (60.0) // the speed gain value -+ #define IPD_HFI_EXC_MAG_COARSE_PU (0.25) // coarse IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_MAG_FINE_PU (0.2) // fine IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_TIME_COARSE_S (0.5) // coarse wait time, sec max 0.64 -+ #define IPD_HFI_EXC_TIME_FINE_S (0.5) // fine wait time, sec max 0.4 -+ #define AFSEL_FREQ_HIGH_PU (_IQ(20.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_FREQ_LOW_PU (_IQ(10.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_IQ_SLOPE_EST (_IQ((float)(1.0/0.1/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_HFI (_IQ((float)(1.0/10.0/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_THROTTLE_DWN (_IQ((float)(1.0/0.05/USER_ISR_FREQ_Hz))) -+ #define AFSEL_MAX_IQ_REF_EST (_IQ(0.4)) -+ #define AFSEL_MAX_IQ_REF_HFI (_IQ(0.4)) -+ -+ #else -+ #error No motor type specified -+ #endif -+ -+ -+ #ifndef USER_MOTOR -+ #error Motor is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_TYPE -+ #error The motor type is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_NUM_POLE_PAIRS -+ #error Number of motor pole pairs is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Rr -+ #error The rotor resistance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Rs -+ #error The stator resistance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Ls_d -+ #error The direct stator inductance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Ls_q -+ #error The quadrature stator inductance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_RATED_FLUX -+ #error The rated flux of motor is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_MAGNETIZING_CURRENT -+ #error The magnetizing current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_RES_EST_CURRENT -+ #error The resistance estimation current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_IND_EST_CURRENT -+ #error The inductance estimation current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_MAX_CURRENT -+ #error The maximum current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_FLUX_EST_FREQ_Hz -+ #error The flux estimation frequency is not defined in user.h -+ #endif -+ -+ -+ // ************************************************************************** -+ // the functions -+ -+ -+ //! \brief Sets the user parameter values -+ //! \param[in] pUserParams The pointer to the user param structure -+ extern void USER_setParams(USER_Params *pUserParams); -+ -+ -+ //! \brief Checks for errors in the user parameter values -+ //! \param[in] pUserParams The pointer to the user param structure -+ extern void USER_checkForErrors(USER_Params *pUserParams); -+ -+ -+ //! \brief Gets the error code in the user parameters -+ //! \param[in] pUserParams The pointer to the user param structure -+ //! \return The error code -+ extern USER_ErrorCode_e USER_getErrorCode(USER_Params *pUserParams); -+ -+ -+ //! \brief Sets the error code in the user parameters -+ //! \param[in] pUserParams The pointer to the user param structure -+ //! \param[in] errorCode The error code -+ extern void USER_setErrorCode(USER_Params *pUserParams,const USER_ErrorCode_e errorCode); -+ -+ -+ //! \brief Recalculates Inductances with the correct Q Format -+ //! \param[in] handle The controller (CTRL) handle -+ extern void USER_softwareUpdate1p6(CTRL_Handle handle); -+ -+ -+ //! \brief Updates Id and Iq PI gains -+ //! \param[in] handle The controller (CTRL) handle -+ extern void USER_calcPIgains(CTRL_Handle handle); -+ -+ -+ //! \brief Computes the scale factor needed to convert from torque created by Ld, Lq, Id and Iq, from per unit to Nm -+ //! \return The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to Nm, in IQ24 format -+ extern _iq USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(void); -+ -+ -+ //! \brief Computes the scale factor needed to convert from torque created by flux and Iq, from per unit to Nm -+ //! \return The scale factor to convert torque from Flux * Iq from per unit to Nm, in IQ24 format -+ extern _iq USER_computeTorque_Flux_Iq_pu_to_Nm_sf(void); -+ -+ -+ //! \brief Computes the scale factor needed to convert from per unit to Wb -+ //! \return The scale factor to convert from flux per unit to flux in Wb, in IQ24 format -+ extern _iq USER_computeFlux_pu_to_Wb_sf(void); -+ -+ -+ //! \brief Computes the scale factor needed to convert from per unit to V/Hz -+ //! \return The scale factor to convert from flux per unit to flux in V/Hz, in IQ24 format -+ extern _iq USER_computeFlux_pu_to_VpHz_sf(void); -+ -+ -+ //! \brief Computes Flux in Wb or V/Hz depending on the scale factor sent as parameter -+ //! \param[in] handle The controller (CTRL) handle -+ //! \param[in] sf The scale factor to convert flux from per unit to Wb or V/Hz -+ //! \return The flux in Wb or V/Hz depending on the scale factor sent as parameter, in IQ24 format -+ extern _iq USER_computeFlux(CTRL_Handle handle, const _iq sf); -+ -+ -+ //! \brief Computes Torque in Nm -+ //! \param[in] handle The controller (CTRL) handle -+ //! \param[in] torque_Flux_sf The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to Nm -+ //! \param[in] torque_Ls_sf The scale factor to convert torque from Flux * Iq from per unit to Nm -+ //! \return The torque in Nm, in IQ24 format -+ extern _iq USER_computeTorque_Nm(CTRL_Handle handle, const _iq torque_Flux_sf, const _iq torque_Ls_sf); -+ -+ -+ //! \brief Computes Torque in lbin -+ //! \param[in] handle The controller (CTRL) handle -+ //! \param[in] torque_Flux_sf The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to lbin -+ //! \param[in] torque_Ls_sf The scale factor to convert torque from Flux * Iq from per unit to lbin -+ //! \return The torque in lbin, in IQ24 format -+ extern _iq USER_computeTorque_lbin(CTRL_Handle handle, const _iq torque_Flux_sf, const _iq torque_Ls_sf); -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _USER_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j1.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j1.h -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j1.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j1.h 2017-06-08 10:42:07.638948300 +0200 -*************** -*** 0 **** ---- 1,336 ---- -+ #ifndef _USER_J1_H_ -+ #define _USER_J1_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806xF/src/user_j1.h -+ //! \brief Contains the public interface for user initialization data for the CTRL, HAL, and EST modules -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ //! -+ //! -+ //! \defgroup USER USER -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ //! \brief CURRENTS AND VOLTAGES -+ // ************************************************************************** -+ //! \brief Defines the full scale frequency for IQ variable, Hz -+ //! \brief All frequencies are converted into (pu) based on the ratio to this value -+ //! \brief this value MUST be larger than the maximum speed that you are expecting from the motor -+ #define USER_IQ_FULL_SCALE_FREQ_Hz (800.0) // 800 Example with buffer for 8-pole 6 KRPM motor to be run to 10 KRPM with field weakening; Hz =(RPM * Poles) / 120 -+ -+ //! \brief Defines full scale value for the IQ30 variable of Voltage inside the system -+ //! \brief All voltages are converted into (pu) based on the ratio to this value -+ //! \brief WARNING: this value MUST meet the following condition: USER_IQ_FULL_SCALE_VOLTAGE_V > 0.5 * USER_MOTOR_MAX_CURRENT * USER_MOTOR_Ls_d * USER_VOLTAGE_FILTER_POLE_rps, -+ //! \brief WARNING: otherwise the value can saturate and roll-over, causing an inaccurate value -+ //! \brief WARNING: this value is OFTEN greater than the maximum measured ADC value, especially with high Bemf motors operating at higher than rated speeds -+ //! \brief WARNING: if you know the value of your Bemf constant, and you know you are operating at a multiple speed due to field weakening, be sure to set this value higher than the expected Bemf voltage -+ //! \brief It is recommended to start with a value ~3x greater than the USER_ADC_FULL_SCALE_VOLTAGE_V and increase to 4-5x if scenarios where a Bemf calculation may exceed these limits -+ //! \brief This value is also used to calculate the minimum flux value: USER_IQ_FULL_SCALE_VOLTAGE_V/USER_EST_FREQ_Hz/0.7 -+ #define USER_IQ_FULL_SCALE_VOLTAGE_V (24.0) // 24.0 Example for boostxldrv8301_revB typical usage and the Anaheim motor -+ -+ //! \brief Defines the maximum voltage at the input to the AD converter -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the voltage sensing and scaling to the ADC input -+ #define USER_ADC_FULL_SCALE_VOLTAGE_V (26.314) // 26.314 boostxldrv8301_revB voltage scaling -+ -+ //! \brief Defines the full scale current for the IQ variables, A -+ //! \brief All currents are converted into (pu) based on the ratio to this value -+ //! \brief WARNING: this value MUST be larger than the maximum current readings that you are expecting from the motor or the reading will roll over to 0, creating a control issue -+ #define USER_IQ_FULL_SCALE_CURRENT_A (20.0) // 20.0 Example for boostxldrv8301_revB typical usage -+ -+ //! \brief Defines the maximum current at the AD converter -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the current sensing and scaling to the ADC input -+ #define USER_ADC_FULL_SCALE_CURRENT_A (33.0) // 33.0 boostxldrv8301_revB current scaling -+ -+ //! \brief Defines the number of current sensors used -+ //! \brief Defined by the hardware capability present -+ //! \brief May be (2) or (3) -+ #define USER_NUM_CURRENT_SENSORS (3) // 3 Preferred setting for best performance across full speed range, allows for 100% duty cycle -+ -+ //! \brief Defines the number of voltage (phase) sensors -+ //! \brief Must be (3) -+ #define USER_NUM_VOLTAGE_SENSORS (3) // 3 Required -+ -+ //! \brief ADC current offsets for A, B, and C phases -+ //! \brief One-time hardware dependent, though the calibration can be done at run-time as well -+ //! \brief After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller -+ #define I_A_offset (0.8325241804) -+ #define I_B_offset (0.8290548921) -+ #define I_C_offset (0.8284353018) -+ -+ //! \brief ADC voltage offsets for A, B, and C phases -+ //! \brief One-time hardware dependent, though the calibration can be done at run-time as well -+ //! \brief After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller -+ #define V_A_offset (0.4963588715) -+ #define V_B_offset (0.4934324026) -+ #define V_C_offset (0.4930265546) -+ -+ -+ //! \brief CLOCKS & TIMERS -+ // ************************************************************************** -+ //! \brief Defines the Pulse Width Modulation (PWM) frequency, kHz -+ //! \brief PWM frequency can be set directly here up to 30 KHz safely (60 KHz MAX in some cases) -+ //! \brief For higher PWM frequencies (60 KHz+ typical for low inductance, high current ripple motors) it is recommended to use the ePWM hardware -+ //! \brief and adjustable ADC SOC to decimate the ADC conversion done interrupt to the control system, or to use the software Que example. -+ //! \brief Otherwise you risk missing interrupts and disrupting the timing of the control state machine -+ #define USER_PWM_FREQ_kHz (15.0) //30.0 Example, 8.0 - 30.0 KHz typical; 45-80 KHz may be required for very low inductance, high speed motors -+ -+ //! \brief Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the -+ //! \brief Id and Iq PI current controllers. The Id and Iq current controller outputs are Vd and Vq. -+ //! \brief The relationship between Vs, Vd, and Vq is: Vs = sqrt(Vd^2 + Vq^2). In this FOC controller, the -+ //! \brief Vd value is set equal to USER_MAX_VS_MAG*USER_VD_MAG_FACTOR. Vq = sqrt(USER_MAX_VS_MAG^2 - Vd^2). -+ //! \brief Set USER_MAX_VS_MAG = 0.5 for a pure sinewave with a peak at SQRT(3)/2 = 86.6% duty cycle. No current reconstruction is needed for this scenario. -+ //! \brief Set USER_MAX_VS_MAG = 1/SQRT(3) = 0.5774 for a pure sinewave with a peak at 100% duty cycle. Current reconstruction will be needed for this scenario (Lab10a-x). -+ //! \brief Set USER_MAX_VS_MAG = 2/3 = 0.6666 to create a trapezoidal voltage waveform. Current reconstruction will be needed for this scenario (Lab10a-x). -+ //! \brief For space vector over-modulation, see lab 10 for details on system requirements that will allow the SVM generator to go all the way to trapezoidal. -+ #define USER_MAX_VS_MAG_PU (0.5) // Set to 0.5 if a current reconstruction technique is not used. Look at the module svgen_current in lab10a-x for more info. -+ -+ -+ //! \brief DECIMATION -+ // ************************************************************************** -+ //! \brief Defines the number of pwm clock ticks per isr clock tick -+ //! Note: Valid values are 1, 2 or 3 only -+ #define USER_NUM_PWM_TICKS_PER_ISR_TICK (2) -+ -+ //! \brief Defines the number of isr ticks (hardware) per controller clock tick (software) -+ //! \brief Controller clock tick (CTRL) is the main clock used for all timing in the software -+ //! \brief Typically the PWM Frequency triggers (can be decimated by the ePWM hardware for less overhead) an ADC SOC -+ //! \brief ADC SOC triggers an ADC Conversion Done -+ //! \brief ADC Conversion Done triggers ISR -+ //! \brief This relates the hardware ISR rate to the software controller rate -+ //! \brief Typcially want to consider some form of decimation (ePWM hardware, CURRENT or EST) over 16KHz ISR to insure interrupt completes and leaves time for background tasks -+ #define USER_NUM_ISR_TICKS_PER_CTRL_TICK (1) // 2 Example, controller clock rate (CTRL) runs at PWM / 2; ex 30 KHz PWM, 15 KHz control -+ -+ //! \brief Defines the number of controller clock ticks per current controller clock tick -+ //! \brief Relationship of controller clock rate to current controller (FOC) rate -+ #define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK (1) // 1 Typical, Forward FOC current controller (Iq/Id/IPARK/SVPWM) runs at same rate as CTRL. -+ -+ //! \brief Defines the number of controller clock ticks per estimator clock tick -+ //! \brief Relationship of controller clock rate to estimator (FAST) rate -+ //! \brief Depends on needed dynamic performance, FAST provides very good results as low as 1 KHz while more dynamic or high speed applications may require up to 15 KHz -+ #define USER_NUM_CTRL_TICKS_PER_EST_TICK (1) // 1 Typical, FAST estimator runs at same rate as CTRL; -+ -+ //! \brief Defines the number of controller clock ticks per speed controller clock tick -+ //! \brief Relationship of controller clock rate to speed loop rate -+ #define USER_NUM_CTRL_TICKS_PER_SPEED_TICK (15) // 15 Typical to match PWM, ex: 15KHz PWM, controller, and current loop, 1KHz speed loop -+ -+ //! \brief Defines the number of controller clock ticks per trajectory clock tick -+ //! \brief Relationship of controller clock rate to trajectory loop rate -+ //! \brief Typically the same as the speed rate -+ #define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK (15) // 15 Typical to match PWM, ex: 10KHz controller & current loop, 1KHz speed loop, 1 KHz Trajectory -+ -+ -+ //! \brief LIMITS -+ // ************************************************************************** -+ //! \brief Defines the maximum negative current to be applied in Id reference -+ //! \brief Used in field weakening only, this is a safety setting (e.g. to protect against demagnetization) -+ //! \brief User must also be aware that overall current magnitude [sqrt(Id^2 + Iq^2)] should be kept below any machine design specifications -+ #define USER_MAX_NEGATIVE_ID_REF_CURRENT_A (-0.5 * USER_MOTOR_MAX_CURRENT) // -0.5 * USER_MOTOR_MAX_CURRENT Example, adjust to meet safety needs of your motor -+ -+ //! \brief Defines the R/L estimation frequency, Hz -+ //! \brief User higher values for low inductance motors and lower values for higher inductance -+ //! \brief motors. The values can range from 100 to 300 Hz. -+ #define USER_R_OVER_L_EST_FREQ_Hz (300) // 300 Default -+ -+ //! \brief Defines the low speed limit for the flux integrator, pu -+ //! \brief This is the speed range (CW/CCW) at which the ForceAngle object is active, but only if Enabled -+ //! \brief Outside of this speed - or if Disabled - the ForcAngle will NEVER be active and the angle is provided by FAST only -+ #define USER_ZEROSPEEDLIMIT (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz) // 0.002 pu, 1-5 Hz typical; Hz = USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz -+ -+ //! \brief Defines the force angle frequency, Hz -+ //! \brief Frequency of stator vector rotation used by the ForceAngle object -+ //! \brief Can be positive or negative -+ #define USER_FORCE_ANGLE_FREQ_Hz (2.0 * USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz) // 1.0 Typical force angle start-up speed -+ -+ -+ //! \brief POLES -+ // ************************************************************************** -+ //! \brief Defines the analog voltage filter pole location, Hz -+ //! \brief Must match the hardware filter for Vph -+ #define USER_VOLTAGE_FILTER_POLE_Hz (364.682) // 364.682, value for boostxldrv8301_revB hardware -+ -+ -+ //! \brief USER MOTOR & ID SETTINGS -+ // ************************************************************************** -+ -+ //! \brief Define each motor with a unique name and ID number -+ // BLDC & SMPM motors -+ #define Estun_EMJ_04APB22 101 -+ #define Anaheim_BLY172S 102 -+ #define Teknic_M2310PLN04K 104 -+ -+ // IPM motors -+ // If user provides separate Ls-d, Ls-q -+ // else treat as SPM with user or identified average Ls -+ #define Belt_Drive_Washer_IPM 201 -+ #define Anaheim_Salient 202 -+ -+ // ACIM motors -+ #define Marathon_5K33GN2A 301 -+ -+ //! \brief Uncomment the motor which should be included at compile -+ //! \brief These motor ID settings and motor parameters are then available to be used by the control system -+ //! \brief Once your ideal settings and parameters are identified update the motor section here so it is available in the binary code -+ //#define USER_MOTOR Estun_EMJ_04APB22 -+ //#define USER_MOTOR Anaheim_BLY172S -+ #define USER_MOTOR Teknic_M2310PLN04K -+ //#define USER_MOTOR Belt_Drive_Washer_IPM -+ //#define USER_MOTOR Marathon_5K33GN2A -+ //#define USER_MOTOR Anaheim_Salient -+ -+ -+ #if (USER_MOTOR == Estun_EMJ_04APB22) // Name must match the motor #define -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm // Motor_Type_Pm (All Synchronous: BLDC, PMSM, SMPM, IPM) or Motor_Type_Induction (Asynchronous ACI) -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) // PAIRS, not total poles. Used to calculate user RPM from rotor Hz only -+ #define USER_MOTOR_Rr (NULL) // Induction motors only, else NULL -+ #define USER_MOTOR_Rs (2.303403) // Identified phase to neutral resistance in a Y equivalent circuit (Ohms, float) -+ #define USER_MOTOR_Ls_d (0.008464367) // For PM, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_Ls_q (0.008464367) // For PM, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_RATED_FLUX (0.38) // Identified TOTAL flux linkage between the rotor and the stator (V/Hz) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) // Induction motors only, else NULL -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) // During Motor ID, maximum current (Amperes, float) used for Rs estimation, 10-20% rated current -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0) // During Motor ID, maximum current (negative Amperes, float) used for Ls estimation, use just enough to enable rotation -+ #define USER_MOTOR_MAX_CURRENT (3.82) // CRITICAL: Used during ID and run-time, sets a limit on the maximum current command output of the provided Speed PI Controller to the Iq controller -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) // During Motor ID, maximum commanded speed (Hz, float), ~10% rated -+ -+ #elif (USER_MOTOR == Anaheim_BLY172S) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.4110007) -+ #define USER_MOTOR_Ls_d (0.0007092811) -+ #define USER_MOTOR_Ls_q (0.0007092811) -+ #define USER_MOTOR_RATED_FLUX (0.03279636) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0) -+ #define USER_MOTOR_MAX_CURRENT (5.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) -+ -+ #elif (USER_MOTOR == Anaheim_Salient) // When using IPD_HFI, set decimation to 1 and PWM to 15.0 KHz -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.1215855) -+ #define USER_MOTOR_Ls_d (0.0002298828) -+ #define USER_MOTOR_Ls_q (0.0002298828) -+ #define USER_MOTOR_RATED_FLUX (0.04821308) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (2.0) // Enter amperes(float) -+ #define USER_MOTOR_IND_EST_CURRENT (-0.5) // Enter negative amperes(float) -+ #define USER_MOTOR_MAX_CURRENT (10.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) -+ #define IPD_HFI_EXC_FREQ_HZ (750.0) // excitation frequency, Hz -+ #define IPD_HFI_LP_SPD_FILT_HZ (35.0) // lowpass filter cutoff frequency, Hz -+ #define IPD_HFI_HP_IQ_FILT_HZ (100.0) // highpass filter cutoff frequency, Hz -+ #define IPD_HFI_KSPD (15.0) // the speed gain value -+ #define IPD_HFI_EXC_MAG_COARSE_PU (0.13) // coarse IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_MAG_FINE_PU (0.12) // fine IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_TIME_COARSE_S (0.5) // coarse wait time, sec max 0.64 -+ #define IPD_HFI_EXC_TIME_FINE_S (0.5) // fine wait time, sec max 0.4 -+ #define AFSEL_FREQ_HIGH_PU (_IQ(15.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_FREQ_LOW_PU (_IQ(10.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_IQ_SLOPE_EST (_IQ((float)(1.0/0.1/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_HFI (_IQ((float)(1.0/10.0/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_THROTTLE_DWN (_IQ((float)(1.0/0.05/USER_ISR_FREQ_Hz))) -+ #define AFSEL_MAX_IQ_REF_EST (_IQ(0.6)) -+ #define AFSEL_MAX_IQ_REF_HFI (_IQ(0.6)) -+ -+ #elif (USER_MOTOR == Teknic_M2310PLN04K) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.3918252) -+ #define USER_MOTOR_Ls_d (0.00023495) -+ #define USER_MOTOR_Ls_q (0.00023495) -+ #define USER_MOTOR_RATED_FLUX (0.03955824) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-0.5) -+ #define USER_MOTOR_MAX_CURRENT (7.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) -+ -+ #elif (USER_MOTOR == Belt_Drive_Washer_IPM) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (2.832002) -+ #define USER_MOTOR_Ls_d (0.0115) -+ #define USER_MOTOR_Ls_q (0.0135) -+ #define USER_MOTOR_RATED_FLUX (0.5022156) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0) -+ #define USER_MOTOR_MAX_CURRENT (4.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) -+ -+ #elif (USER_MOTOR == Marathon_5K33GN2A) // Name must match the motor #define -+ #define USER_MOTOR_TYPE MOTOR_Type_Induction // Motor_Type_Pm (All Synchronous: BLDC, PMSM, SMPM, IPM) or Motor_Type_Induction (Asynchronous ACI) -+ #define USER_MOTOR_NUM_POLE_PAIRS (2) // PAIRS, not total poles. Used to calculate user RPM from rotor Hz only -+ #define USER_MOTOR_Rr (5.508003) // Identified phase to neutral in a Y equivalent circuit (Ohms, float) -+ #define USER_MOTOR_Rs (10.71121) // Identified phase to neutral in a Y equivalent circuit (Ohms, float) -+ #define USER_MOTOR_Ls_d (0.05296588) // For Induction, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_Ls_q (0.05296588) // For Induction, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_RATED_FLUX (0.8165*220.0/60.0) // sqrt(2/3)* Rated V (line-line) / Rated Freq (Hz) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (1.378) // Identified magnetizing current for induction motors, else NULL -+ #define USER_MOTOR_RES_EST_CURRENT (0.5) // During Motor ID, maximum current (Amperes, float) used for Rs estimation, 10-20% rated current -+ #define USER_MOTOR_IND_EST_CURRENT (NULL) // not used for induction -+ #define USER_MOTOR_MAX_CURRENT (2.0) // CRITICAL: Used during ID and run-time, sets a limit on the maximum current command output of the provided Speed PI Controller to the Iq controller -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (5.0) // During Motor ID, maximum commanded speed (Hz, float). Should always use 5 Hz for Induction. -+ -+ #else -+ #error No motor type specified -+ #endif -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _USER_J1_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j5.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j5.h -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j5.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user_mtr_on_j5.h 2017-06-08 10:42:07.638948300 +0200 -*************** -*** 0 **** ---- 1,336 ---- -+ #ifndef _USER_J5_H_ -+ #define _USER_J5_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806xF/src/user_j5.h -+ //! \brief Contains the public interface for user initialization data for the CTRL, HAL, and EST modules -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ //! -+ //! -+ //! \defgroup USER USER -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ //! \brief CURRENTS AND VOLTAGES -+ // ************************************************************************** -+ //! \brief Defines the full scale frequency for IQ variable, Hz -+ //! \brief All frequencies are converted into (pu) based on the ratio to this value -+ //! \brief this value MUST be larger than the maximum speed that you are expecting from the motor -+ #define USER_IQ_FULL_SCALE_FREQ_Hz_2 (800.0) // 800 Example with buffer for 8-pole 6 KRPM motor to be run to 10 KRPM with field weakening; Hz =(RPM * Poles) / 120 -+ -+ //! \brief Defines full scale value for the IQ30 variable of Voltage inside the system -+ //! \brief All voltages are converted into (pu) based on the ratio to this value -+ //! \brief WARNING: this value MUST meet the following condition: USER_IQ_FULL_SCALE_VOLTAGE_V > 0.5 * USER_MOTOR_MAX_CURRENT * USER_MOTOR_Ls_d * USER_VOLTAGE_FILTER_POLE_rps, -+ //! \brief WARNING: otherwise the value can saturate and roll-over, causing an inaccurate value -+ //! \brief WARNING: this value is OFTEN greater than the maximum measured ADC value, especially with high Bemf motors operating at higher than rated speeds -+ //! \brief WARNING: if you know the value of your Bemf constant, and you know you are operating at a multiple speed due to field weakening, be sure to set this value higher than the expected Bemf voltage -+ //! \brief It is recommended to start with a value ~3x greater than the USER_ADC_FULL_SCALE_VOLTAGE_V and increase to 4-5x if scenarios where a Bemf calculation may exceed these limits -+ //! \brief This value is also used to calculate the minimum flux value: USER_IQ_FULL_SCALE_VOLTAGE_V/USER_EST_FREQ_Hz/0.7 -+ #define USER_IQ_FULL_SCALE_VOLTAGE_V_2 (24.0) // 24.0 Example for boostxldrv8301_revB typical usage and the Anaheim motor -+ -+ //! \brief Defines the maximum voltage at the input to the AD converter -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the voltage sensing and scaling to the ADC input -+ #define USER_ADC_FULL_SCALE_VOLTAGE_V_2 (26.314) // 26.314 boostxldrv8301_revB voltage scaling -+ -+ //! \brief Defines the full scale current for the IQ variables, A -+ //! \brief All currents are converted into (pu) based on the ratio to this value -+ //! \brief WARNING: this value MUST be larger than the maximum current readings that you are expecting from the motor or the reading will roll over to 0, creating a control issue -+ #define USER_IQ_FULL_SCALE_CURRENT_A_2 (20.0) // 20.0 Example for boostxldrv8301_revB typical usage -+ -+ //! \brief Defines the maximum current at the AD converter -+ //! \brief The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) -+ //! \brief Hardware dependent, this should be based on the current sensing and scaling to the ADC input -+ #define USER_ADC_FULL_SCALE_CURRENT_A_2 (33.0) // 33.0 boostxldrv8301_revB current scaling -+ -+ //! \brief Defines the number of current sensors used -+ //! \brief Defined by the hardware capability present -+ //! \brief May be (2) or (3) -+ #define USER_NUM_CURRENT_SENSORS_2 (3) // 3 Preferred setting for best performance across full speed range, allows for 100% duty cycle -+ -+ //! \brief Defines the number of voltage (phase) sensors -+ //! \brief Must be (3) -+ #define USER_NUM_VOLTAGE_SENSORS_2 (3) // 3 Required -+ -+ //! \brief ADC current offsets for A, B, and C phases -+ //! \brief One-time hardware dependent, though the calibration can be done at run-time as well -+ //! \brief After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller -+ #define I_A_offset_2 (0.8302742839) -+ #define I_B_offset_2 (0.8323637843) -+ #define I_C_offset_2 (0.8154913783) -+ -+ //! \brief ADC voltage offsets for A, B, and C phases -+ //! \brief One-time hardware dependent, though the calibration can be done at run-time as well -+ //! \brief After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller -+ #define V_A_offset_2 (0.5052267909) -+ #define V_B_offset_2 (0.5082066059) -+ #define V_C_offset_2 (0.5019959807) -+ -+ -+ //! \brief CLOCKS & TIMERS -+ // ************************************************************************** -+ //! \brief Defines the Pulse Width Modulation (PWM) frequency, kHz -+ //! \brief PWM frequency can be set directly here up to 30 KHz safely (60 KHz MAX in some cases) -+ //! \brief For higher PWM frequencies (60 KHz+ typical for low inductance, high current ripple motors) it is recommended to use the ePWM hardware -+ //! \brief and adjustable ADC SOC to decimate the ADC conversion done interrupt to the control system, or to use the software Que example. -+ //! \brief Otherwise you risk missing interrupts and disrupting the timing of the control state machine -+ #define USER_PWM_FREQ_kHz_2 (18.0) //30.0 Example, 8.0 - 30.0 KHz typical; 45-80 KHz may be required for very low inductance, high speed motors -+ -+ //! \brief Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the -+ //! \brief Id and Iq PI current controllers. The Id and Iq current controller outputs are Vd and Vq. -+ //! \brief The relationship between Vs, Vd, and Vq is: Vs = sqrt(Vd^2 + Vq^2). In this FOC controller, the -+ //! \brief Vd value is set equal to USER_MAX_VS_MAG*USER_VD_MAG_FACTOR. Vq = sqrt(USER_MAX_VS_MAG^2 - Vd^2). -+ //! \brief Set USER_MAX_VS_MAG = 0.5 for a pure sinewave with a peak at SQRT(3)/2 = 86.6% duty cycle. No current reconstruction is needed for this scenario. -+ //! \brief Set USER_MAX_VS_MAG = 1/SQRT(3) = 0.5774 for a pure sinewave with a peak at 100% duty cycle. Current reconstruction will be needed for this scenario (Lab10a-x). -+ //! \brief Set USER_MAX_VS_MAG = 2/3 = 0.6666 to create a trapezoidal voltage waveform. Current reconstruction will be needed for this scenario (Lab10a-x). -+ //! \brief For space vector over-modulation, see lab 10 for details on system requirements that will allow the SVM generator to go all the way to trapezoidal. -+ #define USER_MAX_VS_MAG_PU_2 (0.5) // Set to 0.5 if a current reconstruction technique is not used. Look at the module svgen_current in lab10a-x for more info. -+ -+ -+ //! \brief DECIMATION -+ // ************************************************************************** -+ //! \brief Defines the number of pwm clock ticks per isr clock tick -+ //! Note: Valid values are 1, 2 or 3 only -+ #define USER_NUM_PWM_TICKS_PER_ISR_TICK_2 (2) -+ -+ //! \brief Defines the number of isr ticks (hardware) per controller clock tick (software) -+ //! \brief Controller clock tick (CTRL) is the main clock used for all timing in the software -+ //! \brief Typically the PWM Frequency triggers (can be decimated by the ePWM hardware for less overhead) an ADC SOC -+ //! \brief ADC SOC triggers an ADC Conversion Done -+ //! \brief ADC Conversion Done triggers ISR -+ //! \brief This relates the hardware ISR rate to the software controller rate -+ //! \brief Typcially want to consider some form of decimation (ePWM hardware, CURRENT or EST) over 16KHz ISR to insure interrupt completes and leaves time for background tasks -+ #define USER_NUM_ISR_TICKS_PER_CTRL_TICK_2 (1) // 2 Example, controller clock rate (CTRL) runs at PWM / 2; ex 30 KHz PWM, 15 KHz control -+ -+ //! \brief Defines the number of controller clock ticks per current controller clock tick -+ //! \brief Relationship of controller clock rate to current controller (FOC) rate -+ #define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK_2 (1) // 1 Typical, Forward FOC current controller (Iq/Id/IPARK/SVPWM) runs at same rate as CTRL. -+ -+ //! \brief Defines the number of controller clock ticks per estimator clock tick -+ //! \brief Relationship of controller clock rate to estimator (FAST) rate -+ //! \brief Depends on needed dynamic performance, FAST provides very good results as low as 1 KHz while more dynamic or high speed applications may require up to 15 KHz -+ #define USER_NUM_CTRL_TICKS_PER_EST_TICK_2 (1) // 1 Typical, FAST estimator runs at same rate as CTRL; -+ -+ //! \brief Defines the number of controller clock ticks per speed controller clock tick -+ //! \brief Relationship of controller clock rate to speed loop rate -+ #define USER_NUM_CTRL_TICKS_PER_SPEED_TICK_2 (15) // 15 Typical to match PWM, ex: 15KHz PWM, controller, and current loop, 1KHz speed loop -+ -+ //! \brief Defines the number of controller clock ticks per trajectory clock tick -+ //! \brief Relationship of controller clock rate to trajectory loop rate -+ //! \brief Typically the same as the speed rate -+ #define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK_2 (15) // 15 Typical to match PWM, ex: 10KHz controller & current loop, 1KHz speed loop, 1 KHz Trajectory -+ -+ -+ //! \brief LIMITS -+ // ************************************************************************** -+ //! \brief Defines the maximum negative current to be applied in Id reference -+ //! \brief Used in field weakening only, this is a safety setting (e.g. to protect against demagnetization) -+ //! \brief User must also be aware that overall current magnitude [sqrt(Id^2 + Iq^2)] should be kept below any machine design specifications -+ #define USER_MAX_NEGATIVE_ID_REF_CURRENT_A_2 (-0.5 * USER_MOTOR_MAX_CURRENT) // -0.5 * USER_MOTOR_MAX_CURRENT Example, adjust to meet safety needs of your motor -+ -+ //! \brief Defines the R/L estimation frequency, Hz -+ //! \brief User higher values for low inductance motors and lower values for higher inductance -+ //! \brief motors. The values can range from 100 to 300 Hz. -+ #define USER_R_OVER_L_EST_FREQ_Hz_2 (300) // 300 Default -+ -+ //! \brief Defines the low speed limit for the flux integrator, pu -+ //! \brief This is the speed range (CW/CCW) at which the ForceAngle object is active, but only if Enabled -+ //! \brief Outside of this speed - or if Disabled - the ForcAngle will NEVER be active and the angle is provided by FAST only -+ #define USER_ZEROSPEEDLIMIT_2 (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz_2) // 0.002 pu, 1-5 Hz typical; Hz = USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz -+ -+ //! \brief Defines the force angle frequency, Hz -+ //! \brief Frequency of stator vector rotation used by the ForceAngle object -+ //! \brief Can be positive or negative -+ #define USER_FORCE_ANGLE_FREQ_Hz_2 (2.0 * USER_ZEROSPEEDLIMIT_2 * USER_IQ_FULL_SCALE_FREQ_Hz_2) // 1.0 Typical force angle start-up speed -+ -+ -+ //! \brief POLES -+ // ************************************************************************** -+ //! \brief Defines the analog voltage filter pole location, Hz -+ //! \brief Must match the hardware filter for Vph -+ #define USER_VOLTAGE_FILTER_POLE_Hz_2 (364.682) // 364.682, value for boostxldrv8301_revB hardware -+ -+ -+ //! \brief USER MOTOR & ID SETTINGS -+ // ************************************************************************** -+ -+ //! \brief Define each motor with a unique name and ID number -+ // BLDC & SMPM motors -+ #define Estun_EMJ_04APB22_2 101 -+ #define Anaheim_BLY172S_2 102 -+ #define Teknic_M2310PLN04K_2 104 -+ -+ // IPM motors -+ // If user provides separate Ls-d, Ls-q -+ // else treat as SPM with user or identified average Ls -+ #define Belt_Drive_Washer_IPM_2 201 -+ #define Anaheim_Salient_2 202 -+ -+ // ACIM motors -+ #define Marathon_5K33GN2A_2 301 -+ -+ //! \brief Uncomment the motor which should be included at compile -+ //! \brief These motor ID settings and motor parameters are then available to be used by the control system -+ //! \brief Once your ideal settings and parameters are identified update the motor section here so it is available in the binary code -+ //#define USER_MOTOR_2 Estun_EMJ_04APB22_2 -+ //#define USER_MOTOR_2 Anaheim_BLY172S_2 -+ #define USER_MOTOR_2 Teknic_M2310PLN04K_2 -+ //#define USER_MOTOR_2 Belt_Drive_Washer_IPM_2 -+ //#define USER_MOTOR_2 Marathon_5K33GN2A_2 -+ //#define USER_MOTOR_2 Anaheim_Salient_2 -+ -+ -+ #if (USER_MOTOR == Estun_EMJ_04APB22_2) // Name must match the motor #define -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm // Motor_Type_Pm (All Synchronous: BLDC, PMSM, SMPM, IPM) or Motor_Type_Induction (Asynchronous ACI) -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) // PAIRS, not total poles. Used to calculate user RPM from rotor Hz only -+ #define USER_MOTOR_Rr (NULL) // Induction motors only, else NULL -+ #define USER_MOTOR_Rs (2.303403) // Identified phase to neutral resistance in a Y equivalent circuit (Ohms, float) -+ #define USER_MOTOR_Ls_d (0.008464367) // For PM, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_Ls_q (0.008464367) // For PM, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_RATED_FLUX (0.38) // Identified TOTAL flux linkage between the rotor and the stator (V/Hz) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) // Induction motors only, else NULL -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) // During Motor ID, maximum current (Amperes, float) used for Rs estimation, 10-20% rated current -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0) // During Motor ID, maximum current (negative Amperes, float) used for Ls estimation, use just enough to enable rotation -+ #define USER_MOTOR_MAX_CURRENT (3.82) // CRITICAL: Used during ID and run-time, sets a limit on the maximum current command output of the provided Speed PI Controller to the Iq controller -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) // During Motor ID, maximum commanded speed (Hz, float), ~10% rated -+ -+ #elif (USER_MOTOR == Anaheim_BLY172S_2) -+ #define USER_MOTOR_TYPE_2 MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS_2 (4) -+ #define USER_MOTOR_Rr_2 (NULL) -+ #define USER_MOTOR_Rs_2 (0.4110007) -+ #define USER_MOTOR_Ls_d_2 (0.0007092811) -+ #define USER_MOTOR_Ls_q_2 (0.0007092811) -+ #define USER_MOTOR_RATED_FLUX_2 (0.03279636) -+ #define USER_MOTOR_MAGNETIZING_CURRENT_2 (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT_2 (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT_2 (-1.0) -+ #define USER_MOTOR_MAX_CURRENT_2 (5.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz_2 (20.0) -+ -+ #elif (USER_MOTOR == Anaheim_Salient_2) // When using IPD_HFI, set decimation to 1 and PWM to 15.0 KHz -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (0.1215855) -+ #define USER_MOTOR_Ls_d (0.0002298828) -+ #define USER_MOTOR_Ls_q (0.0002298828) -+ #define USER_MOTOR_RATED_FLUX (0.04821308) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (2.0) // Enter amperes(float) -+ #define USER_MOTOR_IND_EST_CURRENT (-0.5) // Enter negative amperes(float) -+ #define USER_MOTOR_MAX_CURRENT (10.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) -+ #define IPD_HFI_EXC_FREQ_HZ (750.0) // excitation frequency, Hz -+ #define IPD_HFI_LP_SPD_FILT_HZ (35.0) // lowpass filter cutoff frequency, Hz -+ #define IPD_HFI_HP_IQ_FILT_HZ (100.0) // highpass filter cutoff frequency, Hz -+ #define IPD_HFI_KSPD (15.0) // the speed gain value -+ #define IPD_HFI_EXC_MAG_COARSE_PU (0.13) // coarse IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_MAG_FINE_PU (0.12) // fine IPD excitation magnitude, pu -+ #define IPD_HFI_EXC_TIME_COARSE_S (0.5) // coarse wait time, sec max 0.64 -+ #define IPD_HFI_EXC_TIME_FINE_S (0.5) // fine wait time, sec max 0.4 -+ #define AFSEL_FREQ_HIGH_PU (_IQ(15.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_FREQ_LOW_PU (_IQ(10.0 / USER_IQ_FULL_SCALE_FREQ_Hz)) -+ #define AFSEL_IQ_SLOPE_EST (_IQ((float)(1.0/0.1/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_HFI (_IQ((float)(1.0/10.0/USER_ISR_FREQ_Hz))) -+ #define AFSEL_IQ_SLOPE_THROTTLE_DWN (_IQ((float)(1.0/0.05/USER_ISR_FREQ_Hz))) -+ #define AFSEL_MAX_IQ_REF_EST (_IQ(0.6)) -+ #define AFSEL_MAX_IQ_REF_HFI (_IQ(0.6)) -+ -+ #elif (USER_MOTOR == Teknic_M2310PLN04K_2) -+ #define USER_MOTOR_TYPE_2 MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS_2 (4) -+ #define USER_MOTOR_Rr_2 (NULL) -+ #define USER_MOTOR_Rs_2 (0.3918252) -+ #define USER_MOTOR_Ls_d_2 (0.00023495) -+ #define USER_MOTOR_Ls_q_2 (0.00023495) -+ #define USER_MOTOR_RATED_FLUX_2 (0.03955824) -+ #define USER_MOTOR_MAGNETIZING_CURRENT_2 (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT_2 (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT_2 (-0.5) -+ #define USER_MOTOR_MAX_CURRENT_2 (7.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz_2 (20.0) -+ -+ #elif (USER_MOTOR == Belt_Drive_Washer_IPM_2) -+ #define USER_MOTOR_TYPE MOTOR_Type_Pm -+ #define USER_MOTOR_NUM_POLE_PAIRS (4) -+ #define USER_MOTOR_Rr (NULL) -+ #define USER_MOTOR_Rs (2.832002) -+ #define USER_MOTOR_Ls_d (0.0115) -+ #define USER_MOTOR_Ls_q (0.0135) -+ #define USER_MOTOR_RATED_FLUX (0.5022156) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (NULL) -+ #define USER_MOTOR_RES_EST_CURRENT (1.0) -+ #define USER_MOTOR_IND_EST_CURRENT (-1.0) -+ #define USER_MOTOR_MAX_CURRENT (4.0) -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (20.0) -+ -+ #elif (USER_MOTOR == Marathon_5K33GN2A_2) // Name must match the motor #define -+ #define USER_MOTOR_TYPE MOTOR_Type_Induction // Motor_Type_Pm (All Synchronous: BLDC, PMSM, SMPM, IPM) or Motor_Type_Induction (Asynchronous ACI) -+ #define USER_MOTOR_NUM_POLE_PAIRS (2) // PAIRS, not total poles. Used to calculate user RPM from rotor Hz only -+ #define USER_MOTOR_Rr (5.508003) // Identified phase to neutral in a Y equivalent circuit (Ohms, float) -+ #define USER_MOTOR_Rs (10.71121) // Identified phase to neutral in a Y equivalent circuit (Ohms, float) -+ #define USER_MOTOR_Ls_d (0.05296588) // For Induction, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_Ls_q (0.05296588) // For Induction, Identified average stator inductance (Henry, float) -+ #define USER_MOTOR_RATED_FLUX (0.8165*220.0/60.0) // sqrt(2/3)* Rated V (line-line) / Rated Freq (Hz) -+ #define USER_MOTOR_MAGNETIZING_CURRENT (1.378) // Identified magnetizing current for induction motors, else NULL -+ #define USER_MOTOR_RES_EST_CURRENT (0.5) // During Motor ID, maximum current (Amperes, float) used for Rs estimation, 10-20% rated current -+ #define USER_MOTOR_IND_EST_CURRENT (NULL) // not used for induction -+ #define USER_MOTOR_MAX_CURRENT (2.0) // CRITICAL: Used during ID and run-time, sets a limit on the maximum current command output of the provided Speed PI Controller to the Iq controller -+ #define USER_MOTOR_FLUX_EST_FREQ_Hz (5.0) // During Motor ID, maximum commanded speed (Hz, float). Should always use 5 Hz for Induction. -+ -+ #else -+ #error No motor type specified -+ #endif -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _USER_J5_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user1.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user1.h -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user1.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user1.h 2017-06-08 10:42:07.623348300 +0200 -*************** -*** 0 **** ---- 1,329 ---- -+ #ifndef _USER_MTR1_H_ -+ #define _USER_MTR1_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806xF/src/user.h -+ //! \brief Contains the public interface for user initialization data for the CTRL, HAL, and EST modules -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // modules -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/motor/src/32b/motor.h" -+ #include "sw/modules/est/src/32b/est.h" -+ #include "sw/modules/est/src/est_states.h" -+ #include "sw/modules/est/src/est_Flux_states.h" -+ #include "sw/modules/est/src/est_Ls_states.h" -+ #include "sw/modules/est/src/est_Rs_states.h" -+ -+ -+ // platforms -+ #include "sw/modules/fast/src/32b/userParams_eou.h" -+ #include "user_mtr_on_j1.h" -+ -+ //! -+ //! -+ //! \defgroup USER USER -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ -+ //! \brief CURRENTS AND VOLTAGES -+ // ************************************************************************** -+ //! \brief Defines the voltage scale factor for the system -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_VOLTAGE_SF ((float_t)((USER_ADC_FULL_SCALE_VOLTAGE_V)/(USER_IQ_FULL_SCALE_VOLTAGE_V))) -+ -+ //! \brief Defines the current scale factor for the system -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_CURRENT_SF ((float_t)((USER_ADC_FULL_SCALE_CURRENT_A)/(USER_IQ_FULL_SCALE_CURRENT_A))) -+ -+ -+ //! \brief CLOCKS & TIMERS -+ // ************************************************************************** -+ //! \brief Defines the system clock frequency, MHz -+ #define USER_SYSTEM_FREQ_MHz (90.0) -+ -+ //! \brief Defines the address of controller handle 0 and 1 -+ //! -+ #define USER_CTRL_HANDLE_ADDRESS (0x13C40) -+ #define USER_CTRL_HANDLE_ADDRESS_1 (0x13D36) -+ -+ //! \brief Defines the address of estimator handle 0 and 1 -+ //! -+ #define USER_EST_HANDLE_ADDRESS (0x13840) -+ #define USER_EST_HANDLE_ADDRESS_1 (0x13A3E) -+ -+ //! \brief Defines the direct voltage (Vd) scale factor -+ //! -+ #define USER_VD_SF (0.95) -+ -+ //! \brief Defines the Pulse Width Modulation (PWM) period, usec -+ //! \brief Compile time calculation -+ #define USER_PWM_PERIOD_usec (1000.0/USER_PWM_FREQ_kHz) -+ -+ //! \brief Defines the Interrupt Service Routine (ISR) frequency, Hz -+ //! -+ #define USER_ISR_FREQ_Hz ((float_t)USER_PWM_FREQ_kHz * 1000.0 / (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK) -+ -+ //! \brief Defines the Interrupt Service Routine (ISR) period, usec -+ //! -+ #define USER_ISR_PERIOD_usec (USER_PWM_PERIOD_usec * (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK) -+ -+ -+ //! \brief DECIMATION -+ // ************************************************************************** -+ //! \brief Defines the controller frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_CTRL_FREQ_Hz (uint_least32_t)(USER_ISR_FREQ_Hz/USER_NUM_ISR_TICKS_PER_CTRL_TICK) -+ -+ //! \brief Defines the estimator frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_EST_FREQ_Hz (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_EST_TICK) -+ -+ //! \brief Defines the trajectory frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_TRAJ_FREQ_Hz (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_TRAJ_TICK) -+ -+ //! \brief Defines the controller execution period, usec -+ //! \brief Compile time calculation -+ #define USER_CTRL_PERIOD_usec (USER_ISR_PERIOD_usec * USER_NUM_ISR_TICKS_PER_CTRL_TICK) -+ -+ //! \brief Defines the controller execution period, sec -+ //! \brief Compile time calculation -+ #define USER_CTRL_PERIOD_sec ((float_t)USER_CTRL_PERIOD_usec/(float_t)1000000.0) -+ -+ -+ //! \brief LIMITS -+ // ************************************************************************** -+ //! \brief Defines the maximum current slope for Id trajectory during PowerWarp -+ //! \brief For Induction motors only, controls how fast Id input can change under PowerWarp control -+ #define USER_MAX_CURRENT_SLOPE_POWERWARP (0.3*USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz) // 0.3*RES_EST_CURRENT / IQ_FULL_SCALE_CURRENT / TRAJ_FREQ Typical to produce 1-sec rampup/down -+ -+ //! \brief Defines the starting maximum acceleration AND deceleration for the speed profiles, Hz/s -+ //! \brief Updated in run-time through user functions -+ //! \brief Inverter, motor, inertia, and load will limit actual acceleration capability -+ #define USER_MAX_ACCEL_Hzps (20.0) // 20.0 Default -+ -+ //! \brief Defines maximum acceleration for the estimation speed profiles, Hz/s -+ //! \brief Only used during Motor ID (commission) -+ #define USER_MAX_ACCEL_EST_Hzps (5.0) // 5.0 Default, don't change -+ -+ //! \brief Defines the maximum current slope for Id trajectory during estimation -+ #define USER_MAX_CURRENT_SLOPE (USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz) // USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz Default, don't change -+ -+ //! \brief Defines the fraction of IdRated to use during rated flux estimation -+ //! -+ #define USER_IDRATED_FRACTION_FOR_RATED_FLUX (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the fraction of IdRated to use during inductance estimation -+ //! -+ #define USER_IDRATED_FRACTION_FOR_L_IDENT (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the IdRated delta to use during estimation -+ //! -+ #define USER_IDRATED_DELTA (0.00002) -+ -+ //! \brief Defines the fraction of SpeedMax to use during inductance estimation -+ //! -+ #define USER_SPEEDMAX_FRACTION_FOR_L_IDENT (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines flux fraction to use during inductance identification -+ //! -+ #define USER_FLUX_FRACTION (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the PowerWarp gain for computing Id reference -+ //! \brief Induction motors only -+ #define USER_POWERWARP_GAIN (1.0) // 1.0 Default, don't change -+ -+ -+ //! \brief POLES -+ // ************************************************************************** -+ //! \brief Defines the analog voltage filter pole location, rad/s -+ //! \brief Compile time calculation from Hz to rad/s -+ #define USER_VOLTAGE_FILTER_POLE_rps (2.0 * MATH_PI * USER_VOLTAGE_FILTER_POLE_Hz) -+ -+ //! \brief Defines the software pole location for the voltage and current offset estimation, rad/s -+ //! \brief Should not be changed from default of (20.0) -+ #define USER_OFFSET_POLE_rps (20.0) // 20.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the flux estimation, rad/s -+ //! \brief Should not be changed from default of (100.0) -+ #define USER_FLUX_POLE_rps (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the direction filter, rad/s -+ #define USER_DIRECTION_POLE_rps (6.0) // 6.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the speed control filter, rad/s -+ #define USER_SPEED_POLE_rps (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the DC bus filter, rad/s -+ #define USER_DCBUS_POLE_rps (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the convergence factor for the estimator -+ //! \brief Do not change from default for FAST -+ #define USER_EST_KAPPAQ (1.5) // 1.5 Default, do not change -+ -+ // ************************************************************************** -+ // end the defines -+ -+ -+ //! \brief USER MOTOR & ID SETTINGS -+ // ************************************************************************** -+ // this section defined in user_j1.h or user_j5.h -+ -+ #ifndef USER_MOTOR -+ #error Motor is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_TYPE -+ #error The motor type is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_NUM_POLE_PAIRS -+ #error Number of motor pole pairs is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Rr -+ #error The rotor resistance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Rs -+ #error The stator resistance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Ls_d -+ #error The direct stator inductance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Ls_q -+ #error The quadrature stator inductance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_RATED_FLUX -+ #error The rated flux of motor is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_MAGNETIZING_CURRENT -+ #error The magnetizing current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_RES_EST_CURRENT -+ #error The resistance estimation current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_IND_EST_CURRENT -+ #error The inductance estimation current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_MAX_CURRENT -+ #error The maximum current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_FLUX_EST_FREQ_Hz -+ #error The flux estimation frequency is not defined in user.h -+ #endif -+ -+ -+ // ************************************************************************** -+ // the functions -+ -+ -+ //! \brief Sets the user parameter values -+ //! \param[in] pUserParams The pointer to the user param structure -+ extern void USER_setParamsMtr1(USER_Params *pUserParams); -+ -+ -+ //! \brief Computes the scale factor needed to convert from torque created by Ld, Lq, Id and Iq, from per unit to Nm -+ //! \return The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to Nm, in IQ24 format -+ extern _iq USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(USER_Params *pUserParams); -+ -+ -+ //! \brief Computes the scale factor needed to convert from torque created by flux and Iq, from per unit to Nm -+ //! \return The scale factor to convert torque from Flux * Iq from per unit to Nm, in IQ24 format -+ extern _iq USER_computeTorque_Flux_Iq_pu_to_Nm_sf(USER_Params *pUserParams); -+ -+ -+ //! \brief Computes the scale factor needed to convert from per unit to Wb -+ //! \param[in] pUserParams The pointer to the user param structure -+ //! \return The scale factor to convert from flux per unit to flux in Wb, in IQ24 format -+ extern _iq USER_computeFlux_pu_to_Wb_sf(USER_Params *pUserParams); -+ -+ -+ //! \brief Computes the scale factor needed to convert from per unit to V/Hz -+ //! \return The scale factor to convert from flux per unit to flux in V/Hz, in IQ24 format -+ extern _iq USER_computeFlux_pu_to_VpHz_sf(USER_Params *pUserParams); -+ -+ -+ ////! \brief Computes Flux in Wb or V/Hz depending on the scale factor sent as parameter -+ ////! \param[in] handle The controller (CTRL) handle -+ ////! \param[in] sf The scale factor to convert flux from per unit to Wb or V/Hz -+ ////! \return The flux in Wb or V/Hz depending on the scale factor sent as parameter, in IQ24 format -+ //extern _iq USER_computeFlux(CTRL_Handle handle, const _iq sf); -+ // -+ // -+ ////! \brief Computes Torque in Nm -+ ////! \param[in] handle The controller (CTRL) handle -+ ////! \param[in] torque_Flux_sf The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to Nm -+ ////! \param[in] torque_Ls_sf The scale factor to convert torque from Flux * Iq from per unit to Nm -+ ////! \return The torque in Nm, in IQ24 format -+ //extern _iq USER_computeTorque_Nm(CTRL_Handle handle, const _iq torque_Flux_sf, const _iq torque_Ls_sf); -+ // -+ // -+ ////! \brief Computes Torque in lbin -+ ////! \param[in] handle The controller (CTRL) handle -+ ////! \param[in] torque_Flux_sf The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to lbin -+ ////! \param[in] torque_Ls_sf The scale factor to convert torque from Flux * Iq from per unit to lbin -+ ////! \return The torque in lbin, in IQ24 format -+ //extern _iq USER_computeTorque_lbin(CTRL_Handle handle, const _iq torque_Flux_sf, const _iq torque_Ls_sf); -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _USER_MTR1_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user2.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user2.h -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user2.h 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/boards/TAPAS__V1_0/f28x/f2806xF/src/user2.h 2017-06-08 10:42:07.638948300 +0200 -*************** -*** 0 **** ---- 1,275 ---- -+ #ifndef _USER_MTR2_H_ -+ #define _USER_MTR2_H_ -+ /* --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/boards/boostxldrv8301_revB/f28x/f2806xF/src/user.h -+ //! \brief Contains the public interface for user initialization data for the CTRL, HAL, and EST modules -+ //! -+ //! (C) Copyright 2012, Texas Instruments, Inc. -+ -+ -+ // ************************************************************************** -+ // the includes -+ -+ // modules -+ #include "sw/modules/types/src/types.h" -+ #include "sw/modules/motor/src/32b/motor.h" -+ #include "sw/modules/est/src/32b/est.h" -+ #include "sw/modules/est/src/est_states.h" -+ #include "sw/modules/est/src/est_Flux_states.h" -+ #include "sw/modules/est/src/est_Ls_states.h" -+ #include "sw/modules/est/src/est_Rs_states.h" -+ -+ -+ // platforms -+ #include "sw/modules/fast/src/32b/userParams_eou.h" -+ #include "user_mtr_on_j5.h" -+ -+ //! -+ //! -+ //! \defgroup USER USER -+ //! -+ //@{ -+ -+ -+ #ifdef __cplusplus -+ extern "C" { -+ #endif -+ -+ // ************************************************************************** -+ // the defines -+ -+ -+ //! \brief CURRENTS AND VOLTAGES -+ // ************************************************************************** -+ //! \brief Defines the voltage scale factor for the system -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_VOLTAGE_SF_2 ((float_t)((USER_ADC_FULL_SCALE_VOLTAGE_V_2)/(USER_IQ_FULL_SCALE_VOLTAGE_V_2))) -+ -+ //! \brief Defines the current scale factor for the system -+ //! \brief Compile time calculation for scale factor (ratio) used throughout the system -+ #define USER_CURRENT_SF_2 ((float_t)((USER_ADC_FULL_SCALE_CURRENT_A_2)/(USER_IQ_FULL_SCALE_CURRENT_A_2))) -+ -+ -+ //! \brief CLOCKS & TIMERS -+ // ************************************************************************** -+ //! \brief Defines the system clock frequency, MHz -+ #define USER_SYSTEM_FREQ_MHz_2 (90.0) -+ -+ //! \brief Defines the direct voltage (Vd) scale factor -+ //! -+ #define USER_VD_SF_2 (0.95) -+ -+ //! \brief Defines the Pulse Width Modulation (PWM) period, usec -+ //! \brief Compile time calculation -+ #define USER_PWM_PERIOD_usec_2 (1000.0/USER_PWM_FREQ_kHz_2) -+ -+ //! \brief Defines the Interrupt Service Routine (ISR) frequency, Hz -+ //! -+ #define USER_ISR_FREQ_Hz_2 ((float_t)USER_PWM_FREQ_kHz_2 * 1000.0 / (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK_2) -+ -+ //! \brief Defines the Interrupt Service Routine (ISR) period, usec -+ //! -+ #define USER_ISR_PERIOD_usec_2 (USER_PWM_PERIOD_usec_2 * (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK_2) -+ -+ -+ //! \brief DECIMATION -+ // ************************************************************************** -+ //! \brief Defines the controller frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_CTRL_FREQ_Hz_2 (uint_least32_t)(USER_ISR_FREQ_Hz_2/USER_NUM_ISR_TICKS_PER_CTRL_TICK_2) -+ -+ //! \brief Defines the estimator frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_EST_FREQ_Hz_2 (uint_least32_t)(USER_CTRL_FREQ_Hz_2/USER_NUM_CTRL_TICKS_PER_EST_TICK_2) -+ -+ //! \brief Defines the trajectory frequency, Hz -+ //! \brief Compile time calculation -+ #define USER_TRAJ_FREQ_Hz_2 (uint_least32_t)(USER_CTRL_FREQ_Hz_2/USER_NUM_CTRL_TICKS_PER_TRAJ_TICK_2) -+ -+ //! \brief Defines the controller execution period, usec -+ //! \brief Compile time calculation -+ #define USER_CTRL_PERIOD_usec_2 (USER_ISR_PERIOD_usec_2 * USER_NUM_ISR_TICKS_PER_CTRL_TICK_2) -+ -+ //! \brief Defines the controller execution period, sec -+ //! \brief Compile time calculation -+ #define USER_CTRL_PERIOD_sec_2 ((float_t)USER_CTRL_PERIOD_usec_2/(float_t)1000000.0) -+ -+ -+ //! \brief LIMITS -+ // ************************************************************************** -+ //! \brief Defines the maximum current slope for Id trajectory during PowerWarp -+ //! \brief For Induction motors only, controls how fast Id input can change under PowerWarp control -+ #define USER_MAX_CURRENT_SLOPE_POWERWARP_2 (0.3*USER_MOTOR_RES_EST_CURRENT_2/USER_IQ_FULL_SCALE_CURRENT_A_2/USER_TRAJ_FREQ_Hz_2) // 0.3*RES_EST_CURRENT / IQ_FULL_SCALE_CURRENT / TRAJ_FREQ Typical to produce 1-sec rampup/down -+ -+ //! \brief Defines the starting maximum acceleration AND deceleration for the speed profiles, Hz/s -+ //! \brief Updated in run-time through user functions -+ //! \brief Inverter, motor, inertia, and load will limit actual acceleration capability -+ #define USER_MAX_ACCEL_Hzps_2 (20.0) // 20.0 Default -+ -+ //! \brief Defines maximum acceleration for the estimation speed profiles, Hz/s -+ //! \brief Only used during Motor ID (commission) -+ #define USER_MAX_ACCEL_EST_Hzps_2 (5.0) // 5.0 Default, don't change -+ -+ //! \brief Defines the maximum current slope for Id trajectory during estimation -+ #define USER_MAX_CURRENT_SLOPE_2 (USER_MOTOR_RES_EST_CURRENT_2/USER_IQ_FULL_SCALE_CURRENT_A_2/USER_TRAJ_FREQ_Hz_2) // USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz Default, don't change -+ -+ //! \brief Defines the fraction of IdRated to use during rated flux estimation -+ //! -+ #define USER_IDRATED_FRACTION_FOR_RATED_FLUX_2 (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the fraction of IdRated to use during inductance estimation -+ //! -+ #define USER_IDRATED_FRACTION_FOR_L_IDENT_2 (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the IdRated delta to use during estimation -+ //! -+ #define USER_IDRATED_DELTA_2 (0.00002) -+ -+ //! \brief Defines the fraction of SpeedMax to use during inductance estimation -+ //! -+ #define USER_SPEEDMAX_FRACTION_FOR_L_IDENT_2 (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines flux fraction to use during inductance identification -+ //! -+ #define USER_FLUX_FRACTION_2 (1.0) // 1.0 Default, don't change -+ -+ //! \brief Defines the PowerWarp gain for computing Id reference -+ //! \brief Induction motors only -+ #define USER_POWERWARP_GAIN_2 (1.0) // 1.0 Default, don't change -+ -+ -+ //! \brief POLES -+ // ************************************************************************** -+ //! \brief Defines the analog voltage filter pole location, rad/s -+ //! \brief Compile time calculation from Hz to rad/s -+ #define USER_VOLTAGE_FILTER_POLE_rps_2 (2.0 * MATH_PI * USER_VOLTAGE_FILTER_POLE_Hz_2) -+ -+ //! \brief Defines the software pole location for the voltage and current offset estimation, rad/s -+ //! \brief Should not be changed from default of (20.0) -+ #define USER_OFFSET_POLE_rps_2 (20.0) // 20.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the flux estimation, rad/s -+ //! \brief Should not be changed from default of (100.0) -+ #define USER_FLUX_POLE_rps_2 (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the direction filter, rad/s -+ #define USER_DIRECTION_POLE_rps_2 (6.0) // 6.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the speed control filter, rad/s -+ #define USER_SPEED_POLE_rps_2 (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the software pole location for the DC bus filter, rad/s -+ #define USER_DCBUS_POLE_rps_2 (100.0) // 100.0 Default, do not change -+ -+ //! \brief Defines the convergence factor for the estimator -+ //! \brief Do not change from default for FAST -+ #define USER_EST_KAPPAQ_2 (1.5) // 1.5 Default, do not change -+ -+ // ************************************************************************** -+ // end the defines -+ -+ -+ //! \brief USER MOTOR & ID SETTINGS -+ // ************************************************************************** -+ // this section defined in user_j1.h or user_j5.h -+ -+ #ifndef USER_MOTOR_2 -+ #error Motor is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_TYPE_2 -+ #error The motor type is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_NUM_POLE_PAIRS_2 -+ #error Number of motor pole pairs is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Rr_2 -+ #error The rotor resistance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Rs_2 -+ #error The stator resistance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Ls_d_2 -+ #error The direct stator inductance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_Ls_q_2 -+ #error The quadrature stator inductance is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_RATED_FLUX_2 -+ #error The rated flux of motor is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_MAGNETIZING_CURRENT_2 -+ #error The magnetizing current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_RES_EST_CURRENT_2 -+ #error The resistance estimation current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_IND_EST_CURRENT_2 -+ #error The inductance estimation current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_MAX_CURRENT_2 -+ #error The maximum current is not defined in user.h -+ #endif -+ -+ #ifndef USER_MOTOR_FLUX_EST_FREQ_Hz_2 -+ #error The flux estimation frequency is not defined in user.h -+ #endif -+ -+ -+ // ************************************************************************** -+ // the functions -+ -+ -+ //! \brief Sets the user parameter values -+ //! \param[in] pUserParams The pointer to the user param structure -+ extern void USER_setParamsMtr2(USER_Params *pUserParams); -+ -+ -+ #ifdef __cplusplus -+ } -+ #endif // extern "C" -+ -+ //@} // ingroup -+ #endif // end of _USER_MTR2_H_ definition -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/main.h motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/main.h -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/main.h 2016-01-05 13:52:34.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/main.h 2017-06-19 12:54:24.894015800 +0200 -*************** -*** 48,54 **** - #include "sw/modules/fw/src/32b/fw.h" - #include "sw/modules/fem/src/32b/fem.h" - #include "sw/modules/cpu_usage/src/32b/cpu_usage.h" -! - - // drivers - ---- 48,54 ---- - #include "sw/modules/fw/src/32b/fw.h" - #include "sw/modules/fem/src/32b/fem.h" - #include "sw/modules/cpu_usage/src/32b/cpu_usage.h" -! #include "sw/modules/spiCTRL/src/32b/spiCTRL.h" - - // drivers - -*************** -*** 125,131 **** - _IQ(0.0), \ - _IQ(0.0), \ - {0,0,0}, \ -! {0,0,0}} - - - // ************************************************************************** ---- 125,136 ---- - _IQ(0.0), \ - _IQ(0.0), \ - {0,0,0}, \ -! {0,0,0}, \ -! _IQ(0.0), \ -! _IQ(0.0), \ -! {0,0,0,0,0,0},\ -! {false, false, false, false}, \ -! {false, false, false, false, false, false, false}} - - - // ************************************************************************** -*************** -*** 198,203 **** ---- 203,219 ---- - MATH_vec3 I_bias; - MATH_vec3 V_bias; - -+ /* extra Elements for FIKAT */ -+ _iq IdcBus_A; -+ -+ _iq TempSenDegCelsius; -+ -+ _iq AnalogInpVals_kV[6]; -+ -+ bool DigitalIn[4]; -+ -+ bool DigitalOut[7]; -+ - }MOTOR_Vars_t; - - -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.c motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.c -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.c 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.c 2017-07-21 09:13:49.341413300 +0200 -*************** -*** 0 **** ---- 1,900 ---- -+ /* --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_lab02c.c -+ //! \brief All control from user code, only FAST™ feedback from ROM -+ //! \brief Special variable scaling for improved motor ID, especially with low inductance motors -+ //! (C) Copyright 2011, Texas Instruments, Inc. -+ -+ //! \defgroup PROJ_LAB02c PROJ_LAB02c -+ //@{ -+ -+ //! \defgroup PROJ_LAB02c_OVERVIEW Project Overview -+ //! -+ //! Run InstaSPIN™-FOC from user memory (RAM/FLASH), only FAST™ in ROM -+ //! Special variable scaling for improved motor ID, especially with low inductance motors -+ -+ // ************************************************************************** -+ // 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 -+ -+ #define LED_BLINK_FREQ_Hz 5 -+ -+ -+ // ************************************************************************** -+ // the globals -+ -+ #define TAPAS_NORMAL_OP 0 -+ #define TAPAS_UPPER_TEMP_LIMIT 80.0 // [°C] -+ #define TAPAS_PROTECT_OVERTEMP 1 -+ #define TAPAS_UPPER_CURRENT_LIMIT 6.0 // [A] -+ #define TAPAS_PROTECT_OVERCURRENT 2 -+ uint16_t TAPASProtect = 0; -+ -+ uint_least16_t gCounter_updateGlobals = 0; -+ -+ bool Flag_Latch_softwareUpdate = true; -+ -+ CTRL_Handle ctrlHandle; -+ -+ #ifdef F2802xF -+ #pragma DATA_SECTION(halHandle,"rom_accessed_data"); -+ #endif -+ HAL_Handle halHandle; -+ -+ #ifdef F2802xF -+ #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; -+ -+ _iq gMaxCurrentSlope = _IQ(0.0); -+ -+ #ifdef FAST_ROM_V1p6 -+ CTRL_Obj *controller_obj; -+ #else -+ #ifdef F2802xF -+ #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 F2802xF -+ extern uint16_t *econst_start, *econst_end, *econst_ram_load; -+ extern uint16_t *switch_start, *switch_end, *switch_ram_load; -+ #endif -+ -+ #endif -+ -+ _iq gLs_pu = _IQ30(0.0); -+ uint_least8_t gLs_qFmt = 0; -+ uint_least8_t gMax_Ls_qFmt = 0; -+ -+ #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 -+ -+ // Communication to Raspberry Pi via SPI -+ struct _tEspRx masterCmd; // received commands from the Raspberry -+ struct _tEspTx slaveResp; // sent response from TAPAS -+ volatile uint16_t spiStatus; -+ -+ // for DC-Bus-Current calculation -+ // (simple running average) -+ #define g_dcBusCurrentSamples 50 -+ uint32_t g_dcBusCurrentIndex = 0; -+ _iq g_dcBusCurrent[g_dcBusCurrentSamples]; -+ float DCBusC[g_dcBusCurrentSamples]; -+ float mean; -+ -+ -+ // ************************************************************************** -+ // the functions -+ -+ void main(void) -+ { -+ // initialize the CRC-table before doing anything else -+ GenerateCrcTable(); -+ -+ // initialize the data structures for the communication with the raspberry-PI -+ memset((void *) &masterCmd, 0, sizeof(masterCmd)); -+ memset((void *) &slaveResp, 0, sizeof(slaveResp)); -+ -+ 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); -+ -+ #ifdef F2802xF -+ //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); -+ -+ -+ // 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); -+ -+ -+ #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); -+ -+ for(;;) -+ { -+ // Waiting for enable system flag to be set -+ while(!(gMotorVars.Flag_enableSys)){ -+ -+ /* RESETTING THE ERROR FLAG IS ONLY POSSIBLE, IF DEVICE GETS DISABLED FROM MASTER */ -+ // do the overtemperature check -+ if (_IQtoF(gMotorVars.TempSenDegCelsius) > TAPAS_UPPER_TEMP_LIMIT) { -+ TAPASProtect = TAPAS_PROTECT_OVERTEMP; -+ slaveResp.u_STATUS_statusErr = TAPAS_PROTECT_OVERTEMP; -+ }else{ -+ TAPASProtect = TAPAS_NORMAL_OP; -+ slaveResp.u_STATUS_statusErr = TAPAS_NORMAL_OP; -+ } -+ // do the overcurrent check -+ if( (_IQtoF(gMotorVars.IdcBus_A) > TAPAS_UPPER_CURRENT_LIMIT) -+ && (HAL_getDCbusCurrentOffsetCalibrationDone()) ){ -+ TAPASProtect = TAPAS_PROTECT_OVERCURRENT; -+ slaveResp.u_STATUS_statusErr = TAPAS_PROTECT_OVERCURRENT; -+ }else{ -+ TAPASProtect = TAPAS_NORMAL_OP; -+ slaveResp.u_STATUS_statusErr = TAPAS_NORMAL_OP; -+ } -+ -+ spiStatus = GetNewSetpoints(halHandle->DMAhandle, -+ &masterCmd, -+ &slaveResp); -+ if(spiStatus != 0){ -+ slaveResp.spiStatus = 0xABCD; -+ }else{ -+ slaveResp.spiStatus = 0xBAD; -+ } -+ -+ HAL_calculateOffsetDCBusCurrent(halHandle, &gAdcData); -+ -+ if(spiStatus != 0){ -+ // overwrite the userparams needed for identification -+ gUserParams.motor_type = MOTOR_Type_Pm; -+ gUserParams.motor_numPolePairs = masterCmd.i_Motor_numPolePairs; -+ gUserParams.powerWarpGain = USER_POWERWARP_GAIN; -+ gUserParams.maxCurrent_resEst = (0.15) * masterCmd.f_Motor_ratedCurrent; -+ gUserParams.maxCurrent_indEst = (-1.0) * gUserParams.maxCurrent_resEst; -+ gUserParams.maxCurrent = masterCmd.f_Motor_ratedCurrent; -+ gUserParams.fluxEstFreq_Hz = masterCmd.f_Motor_fluxEstFrequency; -+ gUserParams.RoverL_estFreq_Hz = masterCmd.f_Motor_RoverLestFrequencyHz; -+ -+ // 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){ -+ gMotorVars.Flag_enableSys = false; -+ }else{ -+ // get the speed and acceleration-setpoints -+ gMotorVars.SpeedRef_krpm = masterCmd.f_CTRL_setpoint_speed; -+ gMotorVars.MaxAccel_krpmps = masterCmd.f_CTRL_setpoint_accel; -+ -+ // get the enable-flag -+ -+ -+ if(masterCmd.flags & 0x0001){ -+ gMotorVars.Flag_enableSys = true; -+ }else{ -+ gMotorVars.Flag_enableSys = false; -+ } -+ } -+ CTRL_setParams(ctrlHandle,&gUserParams); -+ } -+ } -+ -+ // loop while the enable system flag is true -+ while(gMotorVars.Flag_enableSys) -+ { -+ spiStatus = GetNewSetpoints(halHandle->DMAhandle, -+ &masterCmd, -+ &slaveResp); -+ -+ if(spiStatus != 0){ -+ // get the value for the run_identify - flag -+ -+ if(masterCmd.flags & 0x0001){ -+ gMotorVars.Flag_enableSys = true; -+ }else{ -+ gMotorVars.Flag_enableSys = false; -+ } -+ -+ if(masterCmd.flags & 0x0002){ -+ gMotorVars.Flag_Run_Identify = true; -+ }else{ -+ gMotorVars.Flag_Run_Identify = false; -+ } -+ -+ // get the maximum allowed current, used for protection purposes -+ gUserParams.maxCurrent = masterCmd.f_Motor_ratedCurrent; -+ // get the speed and acceleration-setpoints -+ gMotorVars.SpeedRef_krpm = _IQ(masterCmd.f_CTRL_setpoint_speed); -+ gMotorVars.MaxAccel_krpmps = _IQ(masterCmd.f_CTRL_setpoint_accel); -+ }else if (spiStatus == 0){ -+ gMotorVars.Flag_Run_Identify = false; -+ gMotorVars.Flag_enableSys = false; -+ } -+ -+ // do the overtemperature check -+ if (_IQtoF(gMotorVars.TempSenDegCelsius) > 60.0){ -+ gMotorVars.Flag_Run_Identify = false; -+ TAPASProtect = TAPAS_PROTECT_OVERTEMP; -+ slaveResp.u_STATUS_statusErr = TAPAS_PROTECT_OVERTEMP; -+ } -+ // do the overcurrent check -+ if( (_IQtoF(gMotorVars.IdcBus_A) > 2.0) -+ && (HAL_getDCbusCurrentOffsetCalibrationDone()) ){ -+ gMotorVars.Flag_Run_Identify = false; -+ TAPASProtect = TAPAS_PROTECT_OVERCURRENT; -+ slaveResp.u_STATUS_statusErr = TAPAS_PROTECT_OVERCURRENT; -+ } -+ -+ CTRL_Obj *obj = (CTRL_Obj *)ctrlHandle; -+ -+ // increment counters -+ gCounter_updateGlobals++; -+ -+ -+ 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); -+ EST_State_e estState = EST_getState(obj->estHandle); -+ -+ if(ctrlState == CTRL_State_OffLine) -+ { -+ // enable the PWM -+ HAL_enablePwm(halHandle); -+ } -+ else if(ctrlState == CTRL_State_OnLine) -+ { -+ if((estState < EST_State_LockRotor) || (estState > EST_State_MotorIdentified)) -+ { -+ // update the ADC bias values -+ HAL_updateAdcBias(halHandle); -+ } -+ -+ // 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; -+ // clear the bit in the masterCmd - structure -+ masterCmd.flags &= ~(1 << 1); -+ } -+ -+ 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)); -+ -+ if(Flag_Latch_softwareUpdate) -+ { -+ Flag_Latch_softwareUpdate = false; -+ -+ USER_calcPIgains(ctrlHandle); -+ } -+ if(EST_getState(obj->estHandle) == EST_State_Idle){ -+ // update the slave response -+ slaveResp.flags |= (1<<5); -+ } -+ } -+ else -+ { -+ Flag_Latch_softwareUpdate = true; -+ -+ // the estimator sets the maximum current slope during identification -+ gMaxCurrentSlope = EST_getMaxCurrentSlope_pu(obj->estHandle); -+ slaveResp.flags &= ~(1<<5); -+ } -+ -+ -+ // 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); -+ } -+ -+ if(CTRL_getMotorType(ctrlHandle) == MOTOR_Type_Induction) -+ { -+ // recalculate Kp and Ki gains to fix the R/L limitation of 2000.0, and Kp limit to 0.11 -+ recalcKpKi(ctrlHandle); -+ -+ // set electrical frequency limit to zero while identifying an induction motor -+ setFeLimitZero(ctrlHandle); -+ -+ // calculate Dir_qFmt for acim motors -+ acim_Dir_qFmtCalc(ctrlHandle); -+ } -+ else -+ { -+ // recalculate Kp and Ki gains to fix the R/L limitation of 2000.0, and Kp limit to 0.11 -+ // as well as recalculates gains based on estimator state to allow low inductance pmsm to id -+ recalcKpKiPmsm(ctrlHandle); -+ -+ // calculate an Ls qFmt that allows ten times smaller inductance compared to Lhf -+ CTRL_calcMax_Ls_qFmt(ctrlHandle, &gMax_Ls_qFmt); -+ -+ gLs_pu = EST_getLs_d_pu(obj->estHandle); -+ gLs_qFmt = EST_getLs_qFmt(obj->estHandle); -+ } -+ -+ // 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; -+ // clear the bit in the masterCmd - structure -+ masterCmd.flags &= ~(1<<1); -+ -+ } // end of for(;;) loop -+ -+ } // end of main() function -+ -+ -+ interrupt void mainISR(void) -+ { -+ // 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); -+ -+ -+ // setup the controller -+ CTRL_setup(ctrlHandle); -+ -+ -+ if(CTRL_getMotorType(ctrlHandle) == MOTOR_Type_Pm) -+ { -+ // reset Ls Q format to a higher value when Ls identification starts -+ CTRL_resetLs_qFmt(ctrlHandle, gMax_Ls_qFmt); -+ } -+ -+ return; -+ } // end of mainISR() function -+ -+ -+ void updateGlobalVariables_motor(CTRL_Handle handle) -+ { -+ // do the exchange of SPI-messages -+ //spiStatus = GetNewSetpoints(halHandle->DMAhandle, -+ // &masterCmd, -+ // &slaveResp); -+ -+ 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 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 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 Values from the Analog inputs -+ gMotorVars.AnalogInpVals_kV[0] = _IQmpy(gAdcData.AnalogIn[0],_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); -+ -+ gMotorVars.AnalogInpVals_kV[1] = _IQmpy(gAdcData.AnalogIn[1],_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); -+ -+ gMotorVars.AnalogInpVals_kV[2] = _IQmpy(gAdcData.AnalogIn[2],_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); -+ -+ gMotorVars.AnalogInpVals_kV[3] = _IQmpy(gAdcData.AnalogIn[3],_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); -+ -+ gMotorVars.AnalogInpVals_kV[4] = _IQmpy(gAdcData.AnalogIn[4],_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); -+ -+ gMotorVars.AnalogInpVals_kV[5] = _IQmpy(gAdcData.AnalogIn[5],_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0)); -+ -+ // Get the Board's Temperature -+ gMotorVars.TempSenDegCelsius = gAdcData.TempSensor; -+ -+ /* Extra Functions for FIKAT */ -+ // Get the DC bus current -+ if(g_dcBusCurrentIndex < g_dcBusCurrentSamples){ -+ g_dcBusCurrent[g_dcBusCurrentIndex] = _IQmpy(gAdcData.I_dcBus,_IQ(USER_IQ_FULL_SCALE_CURRENT_A)) - _IQ(HAL_getDCbusCurrentOffset());//- _IQ(I_DC_Bus_offset); -+ DCBusC[g_dcBusCurrentIndex] = _IQtoF(g_dcBusCurrent[g_dcBusCurrentIndex]); -+ g_dcBusCurrentIndex++; -+ }else{ -+ g_dcBusCurrentIndex = 0; -+ g_dcBusCurrent[g_dcBusCurrentIndex] = _IQmpy(gAdcData.I_dcBus,_IQ(USER_IQ_FULL_SCALE_CURRENT_A))- _IQ(HAL_getDCbusCurrentOffset());// - _IQ(I_DC_Bus_offset); -+ DCBusC[g_dcBusCurrentIndex] = _IQtoF(g_dcBusCurrent[g_dcBusCurrentIndex]); -+ } -+ int i = 0; -+ for(i = 0; i < g_dcBusCurrentSamples; i++){ -+ mean = mean + (DCBusC[i]); -+ -+ } -+ -+ mean = mean / (float)(g_dcBusCurrentSamples); -+ -+ gMotorVars.IdcBus_A = _IQ(mean); -+ -+ -+ // write Values of interest to our response-structure -+ slaveResp.f_STATUS_UdcBus = _IQtoF(gMotorVars.VdcBus_kV); -+ slaveResp.f_STATUS_IdcBus = _IQtoF(gMotorVars.IdcBus_A); -+ slaveResp.f_STATUS_boardTemp = _IQtoF(gMotorVars.TempSenDegCelsius); -+ slaveResp.f_STATUS_currSpeed = _IQtoF(gMotorVars.Speed_krpm); -+ slaveResp.u_CTRL_state = gMotorVars.CtrlState; -+ slaveResp.u_EST_state = gMotorVars.EstState; -+ slaveResp.f_IDENT_motorRs = gMotorVars.Rs_Ohm; -+ slaveResp.f_IDENT_motorRr = gMotorVars.Rr_Ohm; -+ slaveResp.f_IDENT_motorLsd = gMotorVars.Lsd_H; -+ slaveResp.f_IDENT_motorLsq = gMotorVars.Lsq_H; -+ slaveResp.f_EST_ratedFlux = gMotorVars.Flux_VpHz; -+ slaveResp.f_ANALOG_IN_0 = _IQtoF(gMotorVars.AnalogInpVals_kV[0]); -+ slaveResp.f_ANALOG_IN_1 = _IQtoF(gMotorVars.AnalogInpVals_kV[1]); -+ slaveResp.f_ANALOG_IN_2 = _IQtoF(gMotorVars.AnalogInpVals_kV[2]); -+ slaveResp.f_ANALOG_IN_3 = _IQtoF(gMotorVars.AnalogInpVals_kV[3]); -+ slaveResp.f_ANALOG_IN_4 = _IQtoF(gMotorVars.AnalogInpVals_kV[4]); -+ slaveResp.f_ANALOG_IN_5 = _IQtoF(gMotorVars.AnalogInpVals_kV[5]); -+ slaveResp.u_STATUS_DIN = (uint16_t)(gMotorVars.DigitalIn[0] << 0)||(uint16_t)(gMotorVars.DigitalIn[1] << 1)|| -+ (uint16_t)(gMotorVars.DigitalIn[2] << 2)||(uint16_t)(gMotorVars.DigitalIn[0] << 3); -+ return; -+ } // end of updateGlobalVariables_motor() function -+ -+ -+ void CTRL_resetLs_qFmt(CTRL_Handle handle, const uint_least8_t Ls_qFmt) -+ { -+ CTRL_Obj *obj = (CTRL_Obj *)handle; -+ static bool LsResetLatch = false; -+ -+ // reset Ls Q format to a higher value when Ls identification starts -+ if(EST_getState(obj->estHandle) == EST_State_Ls) -+ { -+ if((EST_getLs_d_pu(obj->estHandle) != _IQ30(0.0)) && (LsResetLatch == false)) -+ { -+ EST_setLs_qFmt(obj->estHandle, Ls_qFmt); -+ LsResetLatch = true; -+ } -+ } -+ else -+ { -+ LsResetLatch = false; -+ } -+ -+ return; -+ } // end of CTRL_resetLs_qFmt() function -+ -+ -+ void recalcKpKiPmsm(CTRL_Handle handle) -+ { -+ CTRL_Obj *obj = (CTRL_Obj *)handle; -+ EST_State_e EstState = EST_getState(obj->estHandle); -+ -+ if((EST_isMotorIdentified(obj->estHandle) == false) && (EstState == EST_State_Rs)) -+ { -+ float_t Lhf = CTRL_getLhf(handle); -+ float_t Rhf = CTRL_getRhf(handle); -+ float_t RhfoverLhf = Rhf/Lhf; -+ _iq Kp = _IQ(0.05*Lhf*USER_IQ_FULL_SCALE_CURRENT_A/(USER_CTRL_PERIOD_sec*USER_IQ_FULL_SCALE_VOLTAGE_V)); -+ _iq Ki = _IQ(RhfoverLhf*USER_CTRL_PERIOD_sec); -+ _iq Kp_spd = _IQ(0.005*USER_IQ_FULL_SCALE_FREQ_Hz*USER_MOTOR_MAX_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A); -+ -+ // set Rhf/Lhf -+ CTRL_setRoverL(handle,RhfoverLhf); -+ -+ // set the controller proportional gains -+ CTRL_setKp(handle,CTRL_Type_PID_Id,Kp); -+ CTRL_setKp(handle,CTRL_Type_PID_Iq,Kp); -+ -+ // set the Id controller gains -+ CTRL_setKi(handle,CTRL_Type_PID_Id,Ki); -+ PID_setKi(obj->pidHandle_Id,Ki); -+ -+ // set the Iq controller gains -+ CTRL_setKi(handle,CTRL_Type_PID_Iq,Ki); -+ PID_setKi(obj->pidHandle_Iq,Ki); -+ -+ // set speed gains -+ PID_setKp(obj->pidHandle_spd,Kp_spd); -+ } -+ else if(EstState == EST_State_RatedFlux) -+ { -+ _iq Ki_spd = _IQ(0.5*USER_IQ_FULL_SCALE_FREQ_Hz*USER_CTRL_PERIOD_sec*USER_MOTOR_MAX_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A); -+ -+ // Set Ki on closing the feedback loop -+ PID_setKi(obj->pidHandle_spd,Ki_spd); -+ } -+ else if(EstState == EST_State_RampDown) -+ { -+ _iq Kp_spd = _IQ(0.02*USER_IQ_FULL_SCALE_FREQ_Hz*USER_MOTOR_MAX_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A); -+ _iq Ki_spd = _IQ(2.0*USER_IQ_FULL_SCALE_FREQ_Hz*USER_CTRL_PERIOD_sec*USER_MOTOR_MAX_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A); -+ -+ // Set Kp and Ki of the speed controller -+ PID_setKp(obj->pidHandle_spd,Kp_spd); -+ PID_setKi(obj->pidHandle_spd,Ki_spd); -+ -+ TRAJ_setTargetValue(obj->trajHandle_spdMax,_IQ(USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A)); -+ } -+ -+ return; -+ } // end of recalcKpKiPmsm() function -+ -+ -+ void CTRL_calcMax_Ls_qFmt(CTRL_Handle handle, uint_least8_t *pLs_qFmt) -+ { -+ CTRL_Obj *obj = (CTRL_Obj *)handle; -+ -+ if((EST_isMotorIdentified(obj->estHandle) == false) && (EST_getState(obj->estHandle) == EST_State_Rs)) -+ { -+ float_t Lhf = CTRL_getLhf(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(obj->estHandle)); -+ int_least8_t lShift = ceil(log((Lhf/20.0)/(Ls_coarse_max*fullScaleInductance))/log(2.0)); -+ -+ *pLs_qFmt = 30 - lShift; -+ } -+ -+ return; -+ } // end of CTRL_calcMax_Ls_qFmt() function -+ -+ -+ void recalcKpKi(CTRL_Handle handle) -+ { -+ CTRL_Obj *obj = (CTRL_Obj *)handle; -+ EST_State_e EstState = EST_getState(obj->estHandle); -+ -+ if((EST_isMotorIdentified(obj->estHandle) == false) && (EstState == EST_State_Rs)) -+ { -+ float_t Lhf = CTRL_getLhf(handle); -+ float_t Rhf = CTRL_getRhf(handle); -+ float_t RhfoverLhf = Rhf/Lhf; -+ _iq Kp = _IQ(0.25*Lhf*USER_IQ_FULL_SCALE_CURRENT_A/(USER_CTRL_PERIOD_sec*USER_IQ_FULL_SCALE_VOLTAGE_V)); -+ _iq Ki = _IQ(RhfoverLhf*USER_CTRL_PERIOD_sec); -+ -+ // set Rhf/Lhf -+ CTRL_setRoverL(handle,RhfoverLhf); -+ -+ // set the controller proportional gains -+ CTRL_setKp(handle,CTRL_Type_PID_Id,Kp); -+ CTRL_setKp(handle,CTRL_Type_PID_Iq,Kp); -+ -+ // set the Id controller gains -+ CTRL_setKi(handle,CTRL_Type_PID_Id,Ki); -+ PID_setKi(obj->pidHandle_Id,Ki); -+ -+ // set the Iq controller gains -+ CTRL_setKi(handle,CTRL_Type_PID_Iq,Ki); -+ PID_setKi(obj->pidHandle_Iq,Ki); -+ } -+ -+ return; -+ } // end of recalcKpKi() function -+ -+ -+ void setFeLimitZero(CTRL_Handle handle) -+ { -+ CTRL_Obj *obj = (CTRL_Obj *)handle; -+ EST_State_e EstState = EST_getState(obj->estHandle); -+ -+ _iq fe_neg_max_pu; -+ _iq fe_pos_min_pu; -+ -+ if((EST_isMotorIdentified(obj->estHandle) == false) && (CTRL_getMotorType(handle) == MOTOR_Type_Induction)) -+ { -+ fe_neg_max_pu = _IQ30(0.0); -+ -+ fe_pos_min_pu = _IQ30(0.0); -+ } -+ else -+ { -+ fe_neg_max_pu = _IQ30(-USER_ZEROSPEEDLIMIT); -+ -+ fe_pos_min_pu = _IQ30(USER_ZEROSPEEDLIMIT); -+ } -+ -+ EST_setFe_neg_max_pu(obj->estHandle, fe_neg_max_pu); -+ -+ EST_setFe_pos_min_pu(obj->estHandle, fe_pos_min_pu); -+ -+ return; -+ } // end of setFeLimitZero() function -+ -+ -+ void acim_Dir_qFmtCalc(CTRL_Handle handle) -+ { -+ CTRL_Obj *obj = (CTRL_Obj *)handle; -+ EST_State_e EstState = EST_getState(obj->estHandle); -+ -+ if(EstState == EST_State_IdRated) -+ { -+ EST_setDir_qFmt(obj->estHandle, EST_computeDirection_qFmt(obj->estHandle, 0.7)); -+ } -+ -+ return; -+ } // end of acim_Dir_qFmtCalc() function -+ -+ -+ //@} //defgroup -+ // end of file -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.js motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.js -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.js 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_foc/src/TAPAS_quick_start.js 2017-06-08 10:42:11.382948300 +0200 -*************** -*** 0 **** ---- 1,30 ---- -+ expRemoveAll(); -+ expAdd ("gMotorVars"); -+ expAdd ("gMotorVars.UserErrorCode"); -+ expAdd ("gMotorVars.CtrlVersion"); -+ expAdd ("gMotorVars.Flag_enableSys", getDecimal()); -+ expAdd ("gMotorVars.Flag_Run_Identify", getDecimal()); -+ expAdd ("gMotorVars.Flag_enableForceAngle", getDecimal()); -+ expAdd ("gMotorVars.Flag_enablePowerWarp", getDecimal()); -+ -+ expAdd ("gMotorVars.CtrlState"); -+ expAdd ("gMotorVars.EstState"); -+ -+ expAdd ("gMotorVars.SpeedRef_krpm", getQValue(24)); -+ expAdd ("gMotorVars.MaxAccel_krpmps", getQValue(24)); -+ expAdd ("gMotorVars.Speed_krpm", getQValue(24)); -+ -+ expAdd ("gMotorVars.MagnCurr_A"); -+ expAdd ("gMotorVars.Rr_Ohm"); -+ expAdd ("gMotorVars.Rs_Ohm"); -+ expAdd ("gMotorVars.Lsd_H"); -+ expAdd ("gMotorVars.Lsq_H"); -+ expAdd ("gMotorVars.Flux_VpHz"); -+ -+ expAdd ("gMotorVars.I_bias", getQValue(24)); -+ expAdd ("gMotorVars.V_bias", getQValue(24)); -+ -+ expAdd ("gMotorVars.VdcBus_kV", getQValue(24)); -+ -+ expAdd ("gDrvSpi8301Vars"); -+ expAdd ("gDrvSpi8305Vars"); -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/annotated.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/annotated.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/annotated.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/annotated.html 2017-06-08 10:42:11.554548300 +0200 -*************** -*** 0 **** ---- 1,310 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Data Structures -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
Data Structures
-+
-+
-+
Here are the data structures with brief descriptions:
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
 C_ADC_Obj_ [external]
 C_ANGLE_Obj_ [external]
 C_CAL_Obj_ [external]
 C_CAP_Obj_ [external]
 C_CLARKE_Obj_ [external]
 C_CLK_Obj_ [external]
 C_COMP_Obj_ [external]
 C_cplx_int16_t_ [external]
 C_cplx_int32_t [external]
 C_cplx_int_least32_t_ [external]
 C_cplx_int_least8_t [external]
 C_cplx_least16_t [external]
 C_cplx_uint16_t_ [external]
 C_cplx_uint32_t [external]
 C_cplx_uint_least32_t_ [external]
 C_cplx_uint_least8_t [external]
 C_cplx_uleast16_t [external]
 C_CPU_Obj_ [external]
 C_CPU_USAGE_Obj_ [external]
 C_CTRL_Obj_ [external]
 C_CTRL_Version_ [external]
 C_DLOG_4CH_ [external]
 C_DRV8301_Obj_ [external]
 C_DRV_SPI_8301_CTRL1_t_ [external]
 C_DRV_SPI_8301_CTRL2_t_ [external]
 C_DRV_SPI_8301_Stat1_t_ [external]
 C_DRV_SPI_8301_Stat2_t_ [external]
 C_DRV_SPI_8301_Vars_t_ [external]
 C_ENC_Obj_ [external]
 C_EST_InputData_ [external]
 C_EST_OutputData_ [external]
 C_EVENT_ArgList_ [external]
 C_EVENT_Obj_ [external]
 C_FEM_Obj_ [external]
 C_FILTER_FO_ [external]
 C_FILTER_FO_Obj_ [external]
 C_FILTER_SO_ [external]
 C_FILTER_SO_Obj_ [external]
 C_FLASH_Obj_ [external]
 C_FW_Obj_ [external]
 C_GPIO_Obj_ [external]
 C_HAL_AdcData_t_ [external]
 C_HAL_DacData_t_ [external]
 C_HAL_Obj_ [external]
 C_HAL_PwmData_t_ [external]
 C_IPARK_Obj_ [external]
 C_MATH_vec2_ [external]
 C_MATH_vec3_ [external]
 C_MOTOR_Params_ [external]
 C_MOTOR_Vars_t_
 C_OFFSET_ [external]
 C_OSC_Obj_ [external]
 C_PARK_Obj_ [external]
 C_PI_Obj_ [external]
 C_PID_Obj_ [external]
 C_PIE_IERIFR_t [external]
 C_PIE_Obj_ [external]
 C_PLL_Obj_ [external]
 C_POS_Params_tDefines the position components of SpinTAC (ST)
 C_PWM_Obj_ [external]
 C_PWR_Obj_ [external]
 C_QEP_Obj_ [external]
 C_QUEUE_Obj_ [external]
 C_SCI_Obj_ [external]
 C_SLIP_Obj_ [external]
 C_SPI_Obj_ [external]
 C_ST_ObjDefines the SpinTAC (ST) object
 C_ST_Vars_tDefines the SpinTAC (ST) global variables
 C_SVGEN_Obj_ [external]
 C_SVGENCURRENT_Obj_ [external]
 C_TIMER_Obj_ [external]
 C_TRAJ_Obj_ [external]
 C_USER_Params_ [external]
 C_VEL_Params_tDefines the velocity components of SpinTAC (ST)
 C_WDOG_Obj_ [external]
 CBRSR_BITS [external]
 CBRSR_REG [external]
 CCANAA_BITS [external]
 CCANAA_REG [external]
 CCANBTC_BITS [external]
 CCANBTC_REG [external]
 CCANES_BITS [external]
 CCANES_REG [external]
 CCANGAM_BITS [external]
 CCANGAM_REG [external]
 CCANGIF0_BITS [external]
 CCANGIF0_REG [external]
 CCANGIF1_BITS [external]
 CCANGIF1_REG [external]
 CCANGIM_BITS [external]
 CCANGIM_REG [external]
 CCANLAM_BITS [external]
 CCANLAM_REG [external]
 CCANMC_BITS [external]
 CCANMC_REG [external]
 CCANMD_BITS [external]
 CCANMD_REG [external]
 CCANMDH_BYTES [external]
 CCANMDH_REG [external]
 CCANMDH_WORDS [external]
 CCANMDL_BYTES [external]
 CCANMDL_REG [external]
 CCANMDL_WORDS [external]
 CCANME_BITS [external]
 CCANME_REG [external]
 CCANMIL_BITS [external]
 CCANMIL_REG [external]
 CCANMIM_BITS [external]
 CCANMIM_REG [external]
 CCANMSGCTRL_BITS [external]
 CCANMSGCTRL_REG [external]
 CCANMSGID_BITS [external]
 CCANMSGID_REG [external]
 CCANOPC_BITS [external]
 CCANOPC_REG [external]
 CCANREC_BITS [external]
 CCANREC_REG [external]
 CCANRFP_BITS [external]
 CCANRFP_REG [external]
 CCANRIOC_BITS [external]
 CCANRIOC_REG [external]
 CCANRML_BITS [external]
 CCANRML_REG [external]
 CCANRMP_BITS [external]
 CCANRMP_REG [external]
 CCANTA_BITS [external]
 CCANTA_REG [external]
 CCANTEC_BITS [external]
 CCANTEC_REG [external]
 CCANTIOC_BITS [external]
 CCANTIOC_REG [external]
 CCANTOC_BITS [external]
 CCANTOC_REG [external]
 CCANTOS_BITS [external]
 CCANTOS_REG [external]
 CCANTRR_BITS [external]
 CCANTRR_REG [external]
 CCANTRS_BITS [external]
 CCANTRS_REG [external]
 CCLA_REGS [external]
 CCLASSID_BITS [external]
 CCLASSID_REG [external]
 CDEV_EMU_REGS [external]
 CDEVICECNF_BITS [external]
 CDEVICECNF_REG [external]
 CECAN_MBOXES [external]
 CECAN_REGS [external]
 CI2C_REGS [external]
 CI2CEMDR_BITS [external]
 CI2CEMDR_REG [external]
 CI2CFFRX_BITS [external]
 CI2CFFRX_REG [external]
 CI2CFFTX_BITS [external]
 CI2CFFTX_REG [external]
 CI2CIER_BITS [external]
 CI2CIER_REG [external]
 CI2CISRC_BITS [external]
 CI2CISRC_REG [external]
 CI2CMDR_BITS [external]
 CI2CMDR_REG [external]
 CI2CPSC_BITS [external]
 CI2CPSC_REG [external]
 CI2CSTR_BITS [external]
 CI2CSTR_REG [external]
 CIODFTCTRL_BITS [external]
 CIODFTCTRL_REG [external]
 CLAM_REGS [external]
 CLIN_REGS [external]
 CLINCOMP_BITS [external]
 CLINCOMP_REG [external]
 CLINID_BITS [external]
 CLINID_REG [external]
 CLINMASK_BITS [external]
 CLINMASK_REG [external]
 CLINRD0_BITS [external]
 CLINRD0_REG [external]
 CLINRD1_BITS [external]
 CLINRD1_REG [external]
 CLINTD0_BITS [external]
 CLINTD0_REG [external]
 CLINTD1_BITS [external]
 CLINTD1_REG [external]
 CMBOX [external]
 CMCTL_BITS [external]
 CMCTL_REG [external]
 CMICLR_REG [external]
 CMICLROVF_REG [external]
 CMIER_REG [external]
 CMIFR_BITS [external]
 CMIFR_REG [external]
 CMIFRC_REG [external]
 CMIOVF_REG [external]
 CMIRUN_REG [external]
 CMMEMCFG_BITS [external]
 CMMEMCFG_REG [external]
 CMOTO_REGS [external]
 CMOTS_REGS [external]
 CMPISRCSEL1_BITS [external]
 CMPISRCSEL1_REG [external]
 CMR_REG [external]
 CMSTF_BITS [external]
 CMSTF_REG [external]
 CPARTID_BITS [external]
 CPARTID_REG [external]
 CPARTID_REGS [external]
 CSCICLEARINT_BITS [external]
 CSCICLEARINT_REG [external]
 CSCICLEARINTLVL_BITS [external]
 CSCICLEARINTLVL_REG [external]
 CSCIFLR_BITS [external]
 CSCIFLR_REG [external]
 CSCIFORMAT_BITS [external]
 CSCIFORMAT_REG [external]
 CSCIGCR0_BITS [external]
 CSCIGCR0_REG [external]
 CSCIGCR1_BITS [external]
 CSCIGCR1_REG [external]
 CSCIGCR2_BITS [external]
 CSCIGCR2_REG [external]
 CSCIINTVECT0_BITS [external]
 CSCIINTVECT0_REG [external]
 CSCIINTVECT1_BITS [external]
 CSCIINTVECT1_REG [external]
 CSCIPIO2_BITS [external]
 CSCIPIO2_REG [external]
 CSCISETINT_BITS [external]
 CSCISETINT_REG [external]
 CSCISETINTLVL_BITS [external]
 CSCISETINTLVL_REG [external]
 CST_PlanError_t [external]
 CST_PosConv_t [external]
 CST_PosConvCfg_t [external]
 CST_PosCtl_t [external]
 CST_PosCtlCfg_t [external]
 CST_PosMove_t [external]
 CST_PosMoveCfg_t [external]
 CST_PosMoveMsg_t [external]
 CST_PosPlan_t [external]
 CST_VelCtl_t [external]
 CST_VelCtlCfg_t [external]
 CST_VelId_t [external]
 CST_VelIdCfg_t [external]
 CST_VelMove_t [external]
 CST_VelMoveCfg_t [external]
 CST_VelMoveMsg_t [external]
 CST_VelPlan_t [external]
 CST_Ver_t [external]
-+
-+
-+ -+ -+ -+ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/arrowdown.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/arrowdown.png differ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/arrowright.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/arrowright.png differ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/bc_s.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/bc_s.png differ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/bdwn.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/bdwn.png differ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/classes.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/classes.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/classes.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/classes.html 2017-06-08 10:42:11.585748300 +0200 -*************** -*** 0 **** ---- 1,68 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Data Structure Index -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
Data Structure Index
-+
-+
-+ -+ -+ -+ -+ -+ -+
  _  
-+
_POS_Params_t   _ST_Vars_t   
_ST_Obj   _VEL_Params_t   
_MOTOR_Vars_t_   
-+ -+
-+ -+ -+ -+ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/closed.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/closed.png differ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_416f27cf7dcbd2a3d3a01ab75aff42c3.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_416f27cf7dcbd2a3d3a01ab75aff42c3.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_416f27cf7dcbd2a3d3a01ab75aff42c3.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_416f27cf7dcbd2a3d3a01ab75aff42c3.html 2017-06-08 10:42:11.585748300 +0200 -*************** -*** 0 **** ---- 1,69 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: src Directory Reference -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
src Directory Reference
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Files

file  user.h [code]
 Contains the public interface for user initialization data for the CTRL, HAL, and EST modules.
 
file  user_j1.h [code]
 Contains the public interface for user initialization data for the CTRL, HAL, and EST modules.
 
file  user_j5.h [code]
 Contains the public interface for user initialization data for the CTRL, HAL, and EST modules.
 
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_8fd94e6534391c4b671292a45a97aeaf.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_8fd94e6534391c4b671292a45a97aeaf.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_8fd94e6534391c4b671292a45a97aeaf.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_8fd94e6534391c4b671292a45a97aeaf.html 2017-06-08 10:42:11.601348300 +0200 -*************** -*** 0 **** ---- 1,121 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: src Directory Reference -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
src Directory Reference
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Files

file  main.h [code]
 Defines the structures, global initialization, and functions used in MAIN.
 
file  main_position.h [code]
 
file  proj_lab05c.c [code]
 InstaSPIN-MOTION Inertia Identification.
 
file  proj_lab05d.c [code]
 InstaSPIN-MOTION SpinTAC Speed Controller.
 
file  proj_lab05e.c [code]
 Tuning the SpinTAC Velocity Controller.
 
file  proj_lab05f.c [code]
 Comparing performance of PI velocity controller & SpinTAC velocity controller.
 
file  proj_lab06a.c [code]
 Designing velocity trajectory changes using the SpinTAC Velocity Profile Generator.
 
file  proj_lab06b.c [code]
 Designing Motion Sequences using SpinTAC Plan.
 
file  proj_lab06c.c [code]
 Motion Sequence Example: Washing Machine.
 
file  proj_lab06d.c [code]
 Design a motion sequence.
 
file  proj_lab10b.c [code]
 Automatic Field Weakening and Space Vector Over-Modulation with SpinTAC.
 
file  proj_lab12a.c [code]
 InstaSPIN-MOTION Inertia Identification using a quadrature encoder for feedback.
 
file  proj_lab12b.c [code]
 SpinTAC Velocity Controller using a quadrature encoder for feedback.
 
file  proj_lab13a.c [code]
 Tuning the InstaSPIN-MOTION Position Controller.
 
file  proj_lab13b.c [code]
 mooth Position Transitions with SpinTAC Move
 
file  proj_lab13c.c [code]
 Motion Sequence Example with SpinTAC Plan.
 
file  proj_lab13d.c [code]
 Motion Sequence Real World Example: Vending Machine.
 
file  proj_lab13e.c [code]
 Smooth Velocity Transitions in Position Control.
 
file  spintac_position.h [code]
 Contains public interface to various functions related to the SpinTAC (ST) object.
 
file  spintac_velocity.h [code]
 Contains public interface to various functions related to the SpinTAC (ST) object.
 
file  user.c [code]
 
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_c4fb4f2e8a625dfea1743f6afd78908b.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_c4fb4f2e8a625dfea1743f6afd78908b.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_c4fb4f2e8a625dfea1743f6afd78908b.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_c4fb4f2e8a625dfea1743f6afd78908b.html 2017-06-08 10:42:11.601348300 +0200 -*************** -*** 0 **** ---- 1,62 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: docs Directory Reference -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
docs Directory Reference
-+
-+
-+ -+ -+ -+ -+

-+ Directories

directory  doxygen
 
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_cebf5d542632d9111d69f66af58d6cb2.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_cebf5d542632d9111d69f66af58d6cb2.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_cebf5d542632d9111d69f66af58d6cb2.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dir_cebf5d542632d9111d69f66af58d6cb2.html 2017-06-08 10:42:11.601348300 +0200 -*************** -*** 0 **** ---- 1,62 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: doxygen Directory Reference -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
doxygen Directory Reference
-+
-+
-+ -+ -+ -+ -+

-+ Files

file  doxygen.h [code]
 
-+
-+ -+ -+ -+ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doc.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doc.png differ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen.css motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen.css -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen.css 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen.css 2017-06-08 10:42:11.616948300 +0200 -*************** -*** 0 **** ---- 1,1449 ---- -+ /* The standard CSS for doxygen 1.8.9.1 */ -+ -+ body, table, div, p, dl { -+ font: 400 14px/22px Roboto,sans-serif; -+ } -+ -+ /* @group Heading Levels */ -+ -+ h1.groupheader { -+ font-size: 150%; -+ } -+ -+ .title { -+ font: 400 14px/28px Roboto,sans-serif; -+ font-size: 150%; -+ font-weight: bold; -+ margin: 10px 2px; -+ } -+ -+ h2.groupheader { -+ border-bottom: 1px solid #879ECB; -+ color: #354C7B; -+ font-size: 150%; -+ font-weight: normal; -+ margin-top: 1.75em; -+ padding-top: 8px; -+ padding-bottom: 4px; -+ width: 100%; -+ } -+ -+ h3.groupheader { -+ font-size: 100%; -+ } -+ -+ h1, h2, h3, h4, h5, h6 { -+ -webkit-transition: text-shadow 0.5s linear; -+ -moz-transition: text-shadow 0.5s linear; -+ -ms-transition: text-shadow 0.5s linear; -+ -o-transition: text-shadow 0.5s linear; -+ transition: text-shadow 0.5s linear; -+ margin-right: 15px; -+ } -+ -+ h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { -+ text-shadow: 0 0 15px cyan; -+ } -+ -+ dt { -+ font-weight: bold; -+ } -+ -+ div.multicol { -+ -moz-column-gap: 1em; -+ -webkit-column-gap: 1em; -+ -moz-column-count: 3; -+ -webkit-column-count: 3; -+ } -+ -+ p.startli, p.startdd { -+ margin-top: 2px; -+ } -+ -+ p.starttd { -+ margin-top: 0px; -+ } -+ -+ p.endli { -+ margin-bottom: 0px; -+ } -+ -+ p.enddd { -+ margin-bottom: 4px; -+ } -+ -+ p.endtd { -+ margin-bottom: 2px; -+ } -+ -+ /* @end */ -+ -+ caption { -+ font-weight: bold; -+ } -+ -+ span.legend { -+ font-size: 70%; -+ text-align: center; -+ } -+ -+ h3.version { -+ font-size: 90%; -+ text-align: center; -+ } -+ -+ div.qindex, div.navtab{ -+ background-color: #EBEFF6; -+ border: 1px solid #A3B4D7; -+ text-align: center; -+ } -+ -+ div.qindex, div.navpath { -+ width: 100%; -+ line-height: 140%; -+ } -+ -+ div.navtab { -+ margin-right: 15px; -+ } -+ -+ /* @group Link Styling */ -+ -+ a { -+ color: #3D578C; -+ font-weight: normal; -+ text-decoration: none; -+ } -+ -+ .contents a:visited { -+ color: #4665A2; -+ } -+ -+ a:hover { -+ text-decoration: underline; -+ } -+ -+ a.qindex { -+ font-weight: bold; -+ } -+ -+ a.qindexHL { -+ font-weight: bold; -+ background-color: #9CAFD4; -+ color: #ffffff; -+ border: 1px double #869DCA; -+ } -+ -+ .contents a.qindexHL:visited { -+ color: #ffffff; -+ } -+ -+ a.el { -+ font-weight: bold; -+ } -+ -+ a.elRef { -+ } -+ -+ a.code, a.code:visited, a.line, a.line:visited { -+ color: #4665A2; -+ } -+ -+ a.codeRef, a.codeRef:visited, a.lineRef, a.lineRef:visited { -+ color: #4665A2; -+ } -+ -+ /* @end */ -+ -+ dl.el { -+ margin-left: -1cm; -+ } -+ -+ pre.fragment { -+ border: 1px solid #C4CFE5; -+ background-color: #FBFCFD; -+ padding: 4px 6px; -+ margin: 4px 8px 4px 2px; -+ overflow: auto; -+ word-wrap: break-word; -+ font-size: 9pt; -+ line-height: 125%; -+ font-family: monospace, fixed; -+ font-size: 105%; -+ } -+ -+ div.fragment { -+ padding: 4px 6px; -+ margin: 4px 8px 4px 2px; -+ background-color: #FBFCFD; -+ border: 1px solid #C4CFE5; -+ } -+ -+ div.line { -+ font-family: monospace, fixed; -+ font-size: 13px; -+ min-height: 13px; -+ line-height: 1.0; -+ text-wrap: unrestricted; -+ white-space: -moz-pre-wrap; /* Moz */ -+ white-space: -pre-wrap; /* Opera 4-6 */ -+ white-space: -o-pre-wrap; /* Opera 7 */ -+ white-space: pre-wrap; /* CSS3 */ -+ word-wrap: break-word; /* IE 5.5+ */ -+ text-indent: -53px; -+ padding-left: 53px; -+ padding-bottom: 0px; -+ margin: 0px; -+ -webkit-transition-property: background-color, box-shadow; -+ -webkit-transition-duration: 0.5s; -+ -moz-transition-property: background-color, box-shadow; -+ -moz-transition-duration: 0.5s; -+ -ms-transition-property: background-color, box-shadow; -+ -ms-transition-duration: 0.5s; -+ -o-transition-property: background-color, box-shadow; -+ -o-transition-duration: 0.5s; -+ transition-property: background-color, box-shadow; -+ transition-duration: 0.5s; -+ } -+ -+ div.line.glow { -+ background-color: cyan; -+ box-shadow: 0 0 10px cyan; -+ } -+ -+ -+ span.lineno { -+ padding-right: 4px; -+ text-align: right; -+ border-right: 2px solid #0F0; -+ background-color: #E8E8E8; -+ white-space: pre; -+ } -+ span.lineno a { -+ background-color: #D8D8D8; -+ } -+ -+ span.lineno a:hover { -+ background-color: #C8C8C8; -+ } -+ -+ div.ah, span.ah { -+ background-color: black; -+ font-weight: bold; -+ color: #ffffff; -+ margin-bottom: 3px; -+ margin-top: 3px; -+ padding: 0.2em; -+ border: solid thin #333; -+ border-radius: 0.5em; -+ -webkit-border-radius: .5em; -+ -moz-border-radius: .5em; -+ box-shadow: 2px 2px 3px #999; -+ -webkit-box-shadow: 2px 2px 3px #999; -+ -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; -+ background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444)); -+ background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000); -+ } -+ -+ div.classindex ul { -+ list-style: none; -+ padding-left: 0; -+ } -+ -+ div.classindex span.ai { -+ display: inline-block; -+ } -+ -+ div.groupHeader { -+ margin-left: 16px; -+ margin-top: 12px; -+ font-weight: bold; -+ } -+ -+ div.groupText { -+ margin-left: 16px; -+ font-style: italic; -+ } -+ -+ body { -+ background-color: white; -+ color: black; -+ margin: 0; -+ } -+ -+ div.contents { -+ margin-top: 10px; -+ margin-left: 12px; -+ margin-right: 8px; -+ } -+ -+ td.indexkey { -+ background-color: #EBEFF6; -+ font-weight: bold; -+ border: 1px solid #C4CFE5; -+ margin: 2px 0px 2px 0; -+ padding: 2px 10px; -+ white-space: nowrap; -+ vertical-align: top; -+ } -+ -+ td.indexvalue { -+ background-color: #EBEFF6; -+ border: 1px solid #C4CFE5; -+ padding: 2px 10px; -+ margin: 2px 0px; -+ } -+ -+ tr.memlist { -+ background-color: #EEF1F7; -+ } -+ -+ p.formulaDsp { -+ text-align: center; -+ } -+ -+ img.formulaDsp { -+ -+ } -+ -+ img.formulaInl { -+ vertical-align: middle; -+ } -+ -+ div.center { -+ text-align: center; -+ margin-top: 0px; -+ margin-bottom: 0px; -+ padding: 0px; -+ } -+ -+ div.center img { -+ border: 0px; -+ } -+ -+ address.footer { -+ text-align: right; -+ padding-right: 12px; -+ } -+ -+ img.footer { -+ border: 0px; -+ vertical-align: middle; -+ } -+ -+ /* @group Code Colorization */ -+ -+ span.keyword { -+ color: #008000 -+ } -+ -+ span.keywordtype { -+ color: #604020 -+ } -+ -+ span.keywordflow { -+ color: #e08000 -+ } -+ -+ span.comment { -+ color: #800000 -+ } -+ -+ span.preprocessor { -+ color: #806020 -+ } -+ -+ span.stringliteral { -+ color: #002080 -+ } -+ -+ span.charliteral { -+ color: #008080 -+ } -+ -+ span.vhdldigit { -+ color: #ff00ff -+ } -+ -+ span.vhdlchar { -+ color: #000000 -+ } -+ -+ span.vhdlkeyword { -+ color: #700070 -+ } -+ -+ span.vhdllogic { -+ color: #ff0000 -+ } -+ -+ blockquote { -+ background-color: #F7F8FB; -+ border-left: 2px solid #9CAFD4; -+ margin: 0 24px 0 4px; -+ padding: 0 12px 0 16px; -+ } -+ -+ /* @end */ -+ -+ /* -+ .search { -+ color: #003399; -+ font-weight: bold; -+ } -+ -+ form.search { -+ margin-bottom: 0px; -+ margin-top: 0px; -+ } -+ -+ input.search { -+ font-size: 75%; -+ color: #000080; -+ font-weight: normal; -+ background-color: #e8eef2; -+ } -+ */ -+ -+ td.tiny { -+ font-size: 75%; -+ } -+ -+ .dirtab { -+ padding: 4px; -+ border-collapse: collapse; -+ border: 1px solid #A3B4D7; -+ } -+ -+ th.dirtab { -+ background: #EBEFF6; -+ font-weight: bold; -+ } -+ -+ hr { -+ height: 0px; -+ border: none; -+ border-top: 1px solid #4A6AAA; -+ } -+ -+ hr.footer { -+ height: 1px; -+ } -+ -+ /* @group Member Descriptions */ -+ -+ table.memberdecls { -+ border-spacing: 0px; -+ padding: 0px; -+ } -+ -+ .memberdecls td, .fieldtable tr { -+ -webkit-transition-property: background-color, box-shadow; -+ -webkit-transition-duration: 0.5s; -+ -moz-transition-property: background-color, box-shadow; -+ -moz-transition-duration: 0.5s; -+ -ms-transition-property: background-color, box-shadow; -+ -ms-transition-duration: 0.5s; -+ -o-transition-property: background-color, box-shadow; -+ -o-transition-duration: 0.5s; -+ transition-property: background-color, box-shadow; -+ transition-duration: 0.5s; -+ } -+ -+ .memberdecls td.glow, .fieldtable tr.glow { -+ background-color: cyan; -+ box-shadow: 0 0 15px cyan; -+ } -+ -+ .mdescLeft, .mdescRight, -+ .memItemLeft, .memItemRight, -+ .memTemplItemLeft, .memTemplItemRight, .memTemplParams { -+ background-color: #F9FAFC; -+ border: none; -+ margin: 4px; -+ padding: 1px 0 0 8px; -+ } -+ -+ .mdescLeft, .mdescRight { -+ padding: 0px 8px 4px 8px; -+ color: #555; -+ } -+ -+ .memSeparator { -+ border-bottom: 1px solid #DEE4F0; -+ line-height: 1px; -+ margin: 0px; -+ padding: 0px; -+ } -+ -+ .memItemLeft, .memTemplItemLeft { -+ white-space: nowrap; -+ } -+ -+ .memItemRight { -+ width: 100%; -+ } -+ -+ .memTemplParams { -+ color: #4665A2; -+ white-space: nowrap; -+ font-size: 80%; -+ } -+ -+ /* @end */ -+ -+ /* @group Member Details */ -+ -+ /* Styles for detailed member documentation */ -+ -+ .memtemplate { -+ font-size: 80%; -+ color: #4665A2; -+ font-weight: normal; -+ margin-left: 9px; -+ } -+ -+ .memnav { -+ background-color: #EBEFF6; -+ border: 1px solid #A3B4D7; -+ text-align: center; -+ margin: 2px; -+ margin-right: 15px; -+ padding: 2px; -+ } -+ -+ .mempage { -+ width: 100%; -+ } -+ -+ .memitem { -+ padding: 0; -+ margin-bottom: 10px; -+ margin-right: 5px; -+ -webkit-transition: box-shadow 0.5s linear; -+ -moz-transition: box-shadow 0.5s linear; -+ -ms-transition: box-shadow 0.5s linear; -+ -o-transition: box-shadow 0.5s linear; -+ transition: box-shadow 0.5s linear; -+ display: table !important; -+ width: 100%; -+ } -+ -+ .memitem.glow { -+ box-shadow: 0 0 15px cyan; -+ } -+ -+ .memname { -+ font-weight: bold; -+ margin-left: 6px; -+ } -+ -+ .memname td { -+ vertical-align: bottom; -+ } -+ -+ .memproto, dl.reflist dt { -+ border-top: 1px solid #A8B8D9; -+ border-left: 1px solid #A8B8D9; -+ border-right: 1px solid #A8B8D9; -+ padding: 6px 0px 6px 0px; -+ color: #253555; -+ font-weight: bold; -+ text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); -+ background-image:url('nav_f.png'); -+ background-repeat:repeat-x; -+ background-color: #E2E8F2; -+ /* opera specific markup */ -+ box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -+ border-top-right-radius: 4px; -+ border-top-left-radius: 4px; -+ /* firefox specific markup */ -+ -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; -+ -moz-border-radius-topright: 4px; -+ -moz-border-radius-topleft: 4px; -+ /* webkit specific markup */ -+ -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -+ -webkit-border-top-right-radius: 4px; -+ -webkit-border-top-left-radius: 4px; -+ -+ } -+ -+ .memdoc, dl.reflist dd { -+ border-bottom: 1px solid #A8B8D9; -+ border-left: 1px solid #A8B8D9; -+ border-right: 1px solid #A8B8D9; -+ padding: 6px 10px 2px 10px; -+ background-color: #FBFCFD; -+ border-top-width: 0; -+ background-image:url('nav_g.png'); -+ background-repeat:repeat-x; -+ background-color: #FFFFFF; -+ /* opera specific markup */ -+ border-bottom-left-radius: 4px; -+ border-bottom-right-radius: 4px; -+ box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -+ /* firefox specific markup */ -+ -moz-border-radius-bottomleft: 4px; -+ -moz-border-radius-bottomright: 4px; -+ -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; -+ /* webkit specific markup */ -+ -webkit-border-bottom-left-radius: 4px; -+ -webkit-border-bottom-right-radius: 4px; -+ -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -+ } -+ -+ dl.reflist dt { -+ padding: 5px; -+ } -+ -+ dl.reflist dd { -+ margin: 0px 0px 10px 0px; -+ padding: 5px; -+ } -+ -+ .paramkey { -+ text-align: right; -+ } -+ -+ .paramtype { -+ white-space: nowrap; -+ } -+ -+ .paramname { -+ color: #602020; -+ white-space: nowrap; -+ } -+ .paramname em { -+ font-style: normal; -+ } -+ .paramname code { -+ line-height: 14px; -+ } -+ -+ .params, .retval, .exception, .tparams { -+ margin-left: 0px; -+ padding-left: 0px; -+ } -+ -+ .params .paramname, .retval .paramname { -+ font-weight: bold; -+ vertical-align: top; -+ } -+ -+ .params .paramtype { -+ font-style: italic; -+ vertical-align: top; -+ } -+ -+ .params .paramdir { -+ font-family: "courier new",courier,monospace; -+ vertical-align: top; -+ } -+ -+ table.mlabels { -+ border-spacing: 0px; -+ } -+ -+ td.mlabels-left { -+ width: 100%; -+ padding: 0px; -+ } -+ -+ td.mlabels-right { -+ vertical-align: bottom; -+ padding: 0px; -+ white-space: nowrap; -+ } -+ -+ span.mlabels { -+ margin-left: 8px; -+ } -+ -+ span.mlabel { -+ background-color: #728DC1; -+ border-top:1px solid #5373B4; -+ border-left:1px solid #5373B4; -+ border-right:1px solid #C4CFE5; -+ border-bottom:1px solid #C4CFE5; -+ text-shadow: none; -+ color: white; -+ margin-right: 4px; -+ padding: 2px 3px; -+ border-radius: 3px; -+ font-size: 7pt; -+ white-space: nowrap; -+ vertical-align: middle; -+ } -+ -+ -+ -+ /* @end */ -+ -+ /* these are for tree view inside a (index) page */ -+ -+ div.directory { -+ margin: 10px 0px; -+ border-top: 1px solid #9CAFD4; -+ border-bottom: 1px solid #9CAFD4; -+ width: 100%; -+ } -+ -+ .directory table { -+ border-collapse:collapse; -+ } -+ -+ .directory td { -+ margin: 0px; -+ padding: 0px; -+ vertical-align: top; -+ } -+ -+ .directory td.entry { -+ white-space: nowrap; -+ padding-right: 6px; -+ padding-top: 3px; -+ } -+ -+ .directory td.entry a { -+ outline:none; -+ } -+ -+ .directory td.entry a img { -+ border: none; -+ } -+ -+ .directory td.desc { -+ width: 100%; -+ padding-left: 6px; -+ padding-right: 6px; -+ padding-top: 3px; -+ border-left: 1px solid rgba(0,0,0,0.05); -+ } -+ -+ .directory tr.even { -+ padding-left: 6px; -+ background-color: #F7F8FB; -+ } -+ -+ .directory img { -+ vertical-align: -30%; -+ } -+ -+ .directory .levels { -+ white-space: nowrap; -+ width: 100%; -+ text-align: right; -+ font-size: 9pt; -+ } -+ -+ .directory .levels span { -+ cursor: pointer; -+ padding-left: 2px; -+ padding-right: 2px; -+ color: #3D578C; -+ } -+ -+ .arrow { -+ color: #9CAFD4; -+ -webkit-user-select: none; -+ -khtml-user-select: none; -+ -moz-user-select: none; -+ -ms-user-select: none; -+ user-select: none; -+ cursor: pointer; -+ font-size: 80%; -+ display: inline-block; -+ width: 16px; -+ height: 22px; -+ } -+ -+ .icon { -+ font-family: Arial, Helvetica; -+ font-weight: bold; -+ font-size: 12px; -+ height: 14px; -+ width: 16px; -+ display: inline-block; -+ background-color: #728DC1; -+ color: white; -+ text-align: center; -+ border-radius: 4px; -+ margin-left: 2px; -+ margin-right: 2px; -+ } -+ -+ .icona { -+ width: 24px; -+ height: 22px; -+ display: inline-block; -+ } -+ -+ .iconfopen { -+ width: 24px; -+ height: 18px; -+ margin-bottom: 4px; -+ background-image:url('folderopen.png'); -+ background-position: 0px -4px; -+ background-repeat: repeat-y; -+ vertical-align:top; -+ display: inline-block; -+ } -+ -+ .iconfclosed { -+ width: 24px; -+ height: 18px; -+ margin-bottom: 4px; -+ background-image:url('folderclosed.png'); -+ background-position: 0px -4px; -+ background-repeat: repeat-y; -+ vertical-align:top; -+ display: inline-block; -+ } -+ -+ .icondoc { -+ width: 24px; -+ height: 18px; -+ margin-bottom: 4px; -+ background-image:url('doc.png'); -+ background-position: 0px -4px; -+ background-repeat: repeat-y; -+ vertical-align:top; -+ display: inline-block; -+ } -+ -+ table.directory { -+ font: 400 14px Roboto,sans-serif; -+ } -+ -+ /* @end */ -+ -+ div.dynheader { -+ margin-top: 8px; -+ -webkit-touch-callout: none; -+ -webkit-user-select: none; -+ -khtml-user-select: none; -+ -moz-user-select: none; -+ -ms-user-select: none; -+ user-select: none; -+ } -+ -+ address { -+ font-style: normal; -+ color: #2A3D61; -+ } -+ -+ table.doxtable { -+ border-collapse:collapse; -+ margin-top: 4px; -+ margin-bottom: 4px; -+ } -+ -+ table.doxtable td, table.doxtable th { -+ border: 1px solid #2D4068; -+ padding: 3px 7px 2px; -+ } -+ -+ table.doxtable th { -+ background-color: #374F7F; -+ color: #FFFFFF; -+ font-size: 110%; -+ padding-bottom: 4px; -+ padding-top: 5px; -+ } -+ -+ table.fieldtable { -+ /*width: 100%;*/ -+ margin-bottom: 10px; -+ border: 1px solid #A8B8D9; -+ border-spacing: 0px; -+ -moz-border-radius: 4px; -+ -webkit-border-radius: 4px; -+ border-radius: 4px; -+ -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; -+ -webkit-box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); -+ box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); -+ } -+ -+ .fieldtable td, .fieldtable th { -+ padding: 3px 7px 2px; -+ } -+ -+ .fieldtable td.fieldtype, .fieldtable td.fieldname { -+ white-space: nowrap; -+ border-right: 1px solid #A8B8D9; -+ border-bottom: 1px solid #A8B8D9; -+ vertical-align: top; -+ } -+ -+ .fieldtable td.fieldname { -+ padding-top: 3px; -+ } -+ -+ .fieldtable td.fielddoc { -+ border-bottom: 1px solid #A8B8D9; -+ /*width: 100%;*/ -+ } -+ -+ .fieldtable td.fielddoc p:first-child { -+ margin-top: 0px; -+ } -+ -+ .fieldtable td.fielddoc p:last-child { -+ margin-bottom: 2px; -+ } -+ -+ .fieldtable tr:last-child td { -+ border-bottom: none; -+ } -+ -+ .fieldtable th { -+ background-image:url('nav_f.png'); -+ background-repeat:repeat-x; -+ background-color: #E2E8F2; -+ font-size: 90%; -+ color: #253555; -+ padding-bottom: 4px; -+ padding-top: 5px; -+ text-align:left; -+ -moz-border-radius-topleft: 4px; -+ -moz-border-radius-topright: 4px; -+ -webkit-border-top-left-radius: 4px; -+ -webkit-border-top-right-radius: 4px; -+ border-top-left-radius: 4px; -+ border-top-right-radius: 4px; -+ border-bottom: 1px solid #A8B8D9; -+ } -+ -+ -+ .tabsearch { -+ top: 0px; -+ left: 10px; -+ height: 36px; -+ background-image: url('tab_b.png'); -+ z-index: 101; -+ overflow: hidden; -+ font-size: 13px; -+ } -+ -+ .navpath ul -+ { -+ font-size: 11px; -+ background-image:url('tab_b.png'); -+ background-repeat:repeat-x; -+ background-position: 0 -5px; -+ height:30px; -+ line-height:30px; -+ color:#8AA0CC; -+ border:solid 1px #C2CDE4; -+ overflow:hidden; -+ margin:0px; -+ padding:0px; -+ } -+ -+ .navpath li -+ { -+ list-style-type:none; -+ float:left; -+ padding-left:10px; -+ padding-right:15px; -+ background-image:url('bc_s.png'); -+ background-repeat:no-repeat; -+ background-position:right; -+ color:#364D7C; -+ } -+ -+ .navpath li.navelem a -+ { -+ height:32px; -+ display:block; -+ text-decoration: none; -+ outline: none; -+ color: #283A5D; -+ font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; -+ text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); -+ text-decoration: none; -+ } -+ -+ .navpath li.navelem a:hover -+ { -+ color:#6884BD; -+ } -+ -+ .navpath li.footer -+ { -+ list-style-type:none; -+ float:right; -+ padding-left:10px; -+ padding-right:15px; -+ background-image:none; -+ background-repeat:no-repeat; -+ background-position:right; -+ color:#364D7C; -+ font-size: 8pt; -+ } -+ -+ -+ div.summary -+ { -+ float: right; -+ font-size: 8pt; -+ padding-right: 5px; -+ width: 50%; -+ text-align: right; -+ } -+ -+ div.summary a -+ { -+ white-space: nowrap; -+ } -+ -+ div.ingroups -+ { -+ font-size: 8pt; -+ width: 50%; -+ text-align: left; -+ } -+ -+ div.ingroups a -+ { -+ white-space: nowrap; -+ } -+ -+ div.header -+ { -+ background-image:url('nav_h.png'); -+ background-repeat:repeat-x; -+ background-color: #F9FAFC; -+ margin: 0px; -+ border-bottom: 1px solid #C4CFE5; -+ } -+ -+ div.headertitle -+ { -+ padding: 5px 5px 5px 10px; -+ } -+ -+ dl -+ { -+ padding: 0 0 0 10px; -+ } -+ -+ /* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug */ -+ dl.section -+ { -+ margin-left: 0px; -+ padding-left: 0px; -+ } -+ -+ dl.note -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #D0C000; -+ } -+ -+ dl.warning, dl.attention -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #FF0000; -+ } -+ -+ dl.pre, dl.post, dl.invariant -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #00D000; -+ } -+ -+ dl.deprecated -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #505050; -+ } -+ -+ dl.todo -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #00C0E0; -+ } -+ -+ dl.test -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #3030E0; -+ } -+ -+ dl.bug -+ { -+ margin-left:-7px; -+ padding-left: 3px; -+ border-left:4px solid; -+ border-color: #C08050; -+ } -+ -+ dl.section dd { -+ margin-bottom: 6px; -+ } -+ -+ -+ #projectlogo -+ { -+ text-align: center; -+ vertical-align: bottom; -+ border-collapse: separate; -+ } -+ -+ #projectlogo img -+ { -+ border: 0px none; -+ } -+ -+ #projectname -+ { -+ font: 300% Tahoma, Arial,sans-serif; -+ margin: 0px; -+ padding: 2px 0px; -+ } -+ -+ #projectbrief -+ { -+ font: 120% Tahoma, Arial,sans-serif; -+ margin: 0px; -+ padding: 0px; -+ } -+ -+ #projectnumber -+ { -+ font: 50% Tahoma, Arial,sans-serif; -+ margin: 0px; -+ padding: 0px; -+ } -+ -+ #titlearea -+ { -+ padding: 0px; -+ margin: 0px; -+ width: 100%; -+ border-bottom: 1px solid #5373B4; -+ } -+ -+ .image -+ { -+ text-align: center; -+ } -+ -+ .dotgraph -+ { -+ text-align: center; -+ } -+ -+ .mscgraph -+ { -+ text-align: center; -+ } -+ -+ .diagraph -+ { -+ text-align: center; -+ } -+ -+ .caption -+ { -+ font-weight: bold; -+ } -+ -+ div.zoom -+ { -+ border: 1px solid #90A5CE; -+ } -+ -+ dl.citelist { -+ margin-bottom:50px; -+ } -+ -+ dl.citelist dt { -+ color:#334975; -+ float:left; -+ font-weight:bold; -+ margin-right:10px; -+ padding:5px; -+ } -+ -+ dl.citelist dd { -+ margin:2px 0; -+ padding:5px 0; -+ } -+ -+ div.toc { -+ padding: 14px 25px; -+ background-color: #F4F6FA; -+ border: 1px solid #D8DFEE; -+ border-radius: 7px 7px 7px 7px; -+ float: right; -+ height: auto; -+ margin: 0 20px 10px 10px; -+ width: 200px; -+ } -+ -+ div.toc li { -+ background: url("bdwn.png") no-repeat scroll 0 5px transparent; -+ font: 10px/1.2 Verdana,DejaVu Sans,Geneva,sans-serif; -+ margin-top: 5px; -+ padding-left: 10px; -+ padding-top: 2px; -+ } -+ -+ div.toc h3 { -+ font: bold 12px/1.2 Arial,FreeSans,sans-serif; -+ color: #4665A2; -+ border-bottom: 0 none; -+ margin: 0; -+ } -+ -+ div.toc ul { -+ list-style: none outside none; -+ border: medium none; -+ padding: 0px; -+ } -+ -+ div.toc li.level1 { -+ margin-left: 0px; -+ } -+ -+ div.toc li.level2 { -+ margin-left: 15px; -+ } -+ -+ div.toc li.level3 { -+ margin-left: 30px; -+ } -+ -+ div.toc li.level4 { -+ margin-left: 45px; -+ } -+ -+ .inherit_header { -+ font-weight: bold; -+ color: gray; -+ cursor: pointer; -+ -webkit-touch-callout: none; -+ -webkit-user-select: none; -+ -khtml-user-select: none; -+ -moz-user-select: none; -+ -ms-user-select: none; -+ user-select: none; -+ } -+ -+ .inherit_header td { -+ padding: 6px 0px 2px 5px; -+ } -+ -+ .inherit { -+ display: none; -+ } -+ -+ tr.heading h2 { -+ margin-top: 12px; -+ margin-bottom: 4px; -+ } -+ -+ /* tooltip related style info */ -+ -+ .ttc { -+ position: absolute; -+ display: none; -+ } -+ -+ #powerTip { -+ cursor: default; -+ white-space: nowrap; -+ background-color: white; -+ border: 1px solid gray; -+ border-radius: 4px 4px 4px 4px; -+ box-shadow: 1px 1px 7px gray; -+ display: none; -+ font-size: smaller; -+ max-width: 80%; -+ opacity: 0.9; -+ padding: 1ex 1em 1em; -+ position: absolute; -+ z-index: 2147483647; -+ } -+ -+ #powerTip div.ttdoc { -+ color: grey; -+ font-style: italic; -+ } -+ -+ #powerTip div.ttname a { -+ font-weight: bold; -+ } -+ -+ #powerTip div.ttname { -+ font-weight: bold; -+ } -+ -+ #powerTip div.ttdeci { -+ color: #006318; -+ } -+ -+ #powerTip div { -+ margin: 0px; -+ padding: 0px; -+ font: 12px/16px Roboto,sans-serif; -+ } -+ -+ #powerTip:before, #powerTip:after { -+ content: ""; -+ position: absolute; -+ margin: 0px; -+ } -+ -+ #powerTip.n:after, #powerTip.n:before, -+ #powerTip.s:after, #powerTip.s:before, -+ #powerTip.w:after, #powerTip.w:before, -+ #powerTip.e:after, #powerTip.e:before, -+ #powerTip.ne:after, #powerTip.ne:before, -+ #powerTip.se:after, #powerTip.se:before, -+ #powerTip.nw:after, #powerTip.nw:before, -+ #powerTip.sw:after, #powerTip.sw:before { -+ border: solid transparent; -+ content: " "; -+ height: 0; -+ width: 0; -+ position: absolute; -+ } -+ -+ #powerTip.n:after, #powerTip.s:after, -+ #powerTip.w:after, #powerTip.e:after, -+ #powerTip.nw:after, #powerTip.ne:after, -+ #powerTip.sw:after, #powerTip.se:after { -+ border-color: rgba(255, 255, 255, 0); -+ } -+ -+ #powerTip.n:before, #powerTip.s:before, -+ #powerTip.w:before, #powerTip.e:before, -+ #powerTip.nw:before, #powerTip.ne:before, -+ #powerTip.sw:before, #powerTip.se:before { -+ border-color: rgba(128, 128, 128, 0); -+ } -+ -+ #powerTip.n:after, #powerTip.n:before, -+ #powerTip.ne:after, #powerTip.ne:before, -+ #powerTip.nw:after, #powerTip.nw:before { -+ top: 100%; -+ } -+ -+ #powerTip.n:after, #powerTip.ne:after, #powerTip.nw:after { -+ border-top-color: #ffffff; -+ border-width: 10px; -+ margin: 0px -10px; -+ } -+ #powerTip.n:before { -+ border-top-color: #808080; -+ border-width: 11px; -+ margin: 0px -11px; -+ } -+ #powerTip.n:after, #powerTip.n:before { -+ left: 50%; -+ } -+ -+ #powerTip.nw:after, #powerTip.nw:before { -+ right: 14px; -+ } -+ -+ #powerTip.ne:after, #powerTip.ne:before { -+ left: 14px; -+ } -+ -+ #powerTip.s:after, #powerTip.s:before, -+ #powerTip.se:after, #powerTip.se:before, -+ #powerTip.sw:after, #powerTip.sw:before { -+ bottom: 100%; -+ } -+ -+ #powerTip.s:after, #powerTip.se:after, #powerTip.sw:after { -+ border-bottom-color: #ffffff; -+ border-width: 10px; -+ margin: 0px -10px; -+ } -+ -+ #powerTip.s:before, #powerTip.se:before, #powerTip.sw:before { -+ border-bottom-color: #808080; -+ border-width: 11px; -+ margin: 0px -11px; -+ } -+ -+ #powerTip.s:after, #powerTip.s:before { -+ left: 50%; -+ } -+ -+ #powerTip.sw:after, #powerTip.sw:before { -+ right: 14px; -+ } -+ -+ #powerTip.se:after, #powerTip.se:before { -+ left: 14px; -+ } -+ -+ #powerTip.e:after, #powerTip.e:before { -+ left: 100%; -+ } -+ #powerTip.e:after { -+ border-left-color: #ffffff; -+ border-width: 10px; -+ top: 50%; -+ margin-top: -10px; -+ } -+ #powerTip.e:before { -+ border-left-color: #808080; -+ border-width: 11px; -+ top: 50%; -+ margin-top: -11px; -+ } -+ -+ #powerTip.w:after, #powerTip.w:before { -+ right: 100%; -+ } -+ #powerTip.w:after { -+ border-right-color: #ffffff; -+ border-width: 10px; -+ top: 50%; -+ margin-top: -10px; -+ } -+ #powerTip.w:before { -+ border-right-color: #808080; -+ border-width: 11px; -+ top: 50%; -+ margin-top: -11px; -+ } -+ -+ @media print -+ { -+ #top { display: none; } -+ #side-nav { display: none; } -+ #nav-path { display: none; } -+ body { overflow:visible; } -+ h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } -+ .summary { display: none; } -+ .memitem { page-break-inside: avoid; } -+ #doc-content -+ { -+ margin-left:0 !important; -+ height:auto !important; -+ width:auto !important; -+ overflow:inherit; -+ display:inline; -+ } -+ } -+ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen.png differ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h.html 2017-06-08 10:42:11.632548300 +0200 -*************** -*** 0 **** ---- 1,64 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: doxygen.h File Reference -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+
-+
doxygen.h File Reference
-+
-+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h_source.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h_source.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h_source.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/doxygen_8h_source.html 2017-06-08 10:42:11.632548300 +0200 -*************** -*** 0 **** ---- 1,62 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: doxygen.h Source File -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+
-+
doxygen.h
-+
-+
-+ Go to the documentation of this file.
1 
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dynsections.js motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dynsections.js -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dynsections.js 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/dynsections.js 2017-06-08 10:42:11.632548300 +0200 -*************** -*** 0 **** ---- 1,104 ---- -+ function toggleVisibility(linkObj) -+ { -+ var base = $(linkObj).attr('id'); -+ var summary = $('#'+base+'-summary'); -+ var content = $('#'+base+'-content'); -+ var trigger = $('#'+base+'-trigger'); -+ var src=$(trigger).attr('src'); -+ if (content.is(':visible')===true) { -+ content.hide(); -+ summary.show(); -+ $(linkObj).addClass('closed').removeClass('opened'); -+ $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); -+ } else { -+ content.show(); -+ summary.hide(); -+ $(linkObj).removeClass('closed').addClass('opened'); -+ $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); -+ } -+ return false; -+ } -+ -+ function updateStripes() -+ { -+ $('table.directory tr'). -+ removeClass('even').filter(':visible:even').addClass('even'); -+ } -+ -+ function toggleLevel(level) -+ { -+ $('table.directory tr').each(function() { -+ var l = this.id.split('_').length-1; -+ var i = $('#img'+this.id.substring(3)); -+ var a = $('#arr'+this.id.substring(3)); -+ if (l -+ -+ -+ -+ -+ -+ instaspin_motion: File List -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+
-+
-+
-+
File List
-+
-+
-+
Here is a list of all files with brief descriptions:
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
 32b/cal.c [external]
 32b/cal.h [external]
 32b/clarke.c [external]
 32b/clarke.h [external]
 32b/ctrl.c [external]
 32b/ctrl.h [external]
 32b/ctrl_obj.h [external]
 32b/est.h [external]
 32b/filter_fo.c [external]
 32b/filter_fo.h [external]
 32b/filter_so.c [external]
 32b/filter_so.h [external]
 32b/hal_data.h [external]
 32b/ipark.c [external]
 32b/ipark.h [external]
 32b/IQmathLib.h [external]
 32b/math.h [external]
 32b/motor.h [external]
 32b/offset.c [external]
 32b/offset.h [external]
 32b/park.c [external]
 32b/park.h [external]
 32b/pi.c [external]
 32b/pi.h [external]
 32b/pid.c [external]
 32b/pid.h [external]
 32b/svgen.c [external]
 32b/svgen.h [external]
 32b/traj.c [external]
 32b/traj.h [external]
 32b/user.c [external]
 adc.c [external]
 adc.h [external]
 adc_obj.h [external]
 afsel.h [external]
 angle.h [external]
 boostxldrv8301_revB/f28x/f2806x/src/hal.c [external]
 boostxldrv8301_revB/f28x/f2806x/src/hal.h [external]
 boostxldrv8301_revB/f28x/f2806x/src/hal_obj.h [external]
 cal_states.h [external]
 can.h [external]
 cap.c [external]
 cap.h [external]
 cla.h [external]
 CLAmath.h [external]
 clarke/docs/doxygen/doxygen.h [external]
 clk.c [external]
 clk.h [external]
 comp.c [external]
 comp.h [external]
 cpu.c [external]
 cpu.h [external]
 cpu_usage.c [external]
 cpu_usage.h [external]
 ctrl_states.h [external]
 ctrlQEP.c [external]
 ctrlQEP.h [external]
 dlog/docs/doxygen/doxygen.h [external]
 dlog4ch.c [external]
 dlog4ch.h [external]
 docs/doxygen/doxygen.h [external]
 doxygen.h
 doxygen.h [external]
 drv8301.c [external]
 drv8301.h [external]
 drv8301kit_revD/f28x/f2806x/src/float/hal.c [external]
 drv8301kit_revD/f28x/f2806x/src/float/hal.h [external]
 drv8301kit_revD/f28x/f2806x/src/float/hal_obj.h [external]
 drv8301kit_revD/f28x/f2806x/src/hal.c [external]
 drv8301kit_revD/f28x/f2806x/src/hal.h [external]
 drv8301kit_revD/f28x/f2806x/src/hal_obj.h [external]
 drv8312kit_revD/f28x/f2806x/src/float/hal.c [external]
 drv8312kit_revD/f28x/f2806x/src/float/hal.h [external]
 drv8312kit_revD/f28x/f2806x/src/float/hal_obj.h [external]
 drv8312kit_revD/f28x/f2806x/src/hal.c [external]
 drv8312kit_revD/f28x/f2806x/src/hal.h [external]
 drv8312kit_revD/f28x/f2806x/src/hal_obj.h [external]
 emu.h [external]
 enc.c [external]
 enc.h [external]
 est/docs/doxygen/doxygen.h [external]
 est_Flux_states.h [external]
 est_Ls_states.h [external]
 est_Rr_states.h [external]
 est_Rs_states.h [external]
 est_states.h [external]
 est_Traj_states.h [external]
 fast/src/32b/userParams.h [external]
 fem.c [external]
 fem.h [external]
 flash.c [external]
 flash.h [external]
 float/cal.c [external]
 float/cal.h [external]
 float/clarke.c [external]
 float/clarke.h [external]
 float/ctrl.c [external]
 float/ctrl.h [external]
 float/ctrl_obj.h [external]
 float/est.h [external]
 float/filter_fo.c [external]
 float/filter_fo.h [external]
 float/filter_so.c [external]
 float/filter_so.h [external]
 float/hal_data.h [external]
 float/ipark.c [external]
 float/ipark.h [external]
 float/IQmathLib.h [external]
 float/math.h [external]
 float/motor.h [external]
 float/offset.c [external]
 float/offset.h [external]
 float/park.c [external]
 float/park.h [external]
 float/pi.c [external]
 float/pi.h [external]
 float/pid.c [external]
 float/pid.h [external]
 float/svgen.c [external]
 float/svgen.h [external]
 float/traj.c [external]
 float/traj.h [external]
 float/user.c [external]
 fstart.h [external]
 fw.c [external]
 fw.h [external]
 gpio.c [external]
 gpio.h [external]
 hal_both.c [external]
 hal_both.h [external]
 hal_obj_both.h [external]
 hvkit_rev1p1/f28x/f2806x/src/float/hal.c [external]
 hvkit_rev1p1/f28x/f2806x/src/float/hal.h [external]
 hvkit_rev1p1/f28x/f2806x/src/float/hal_obj.h [external]
 hvkit_rev1p1/f28x/f2806x/src/hal.c [external]
 hvkit_rev1p1/f28x/f2806x/src/hal.h [external]
 hvkit_rev1p1/f28x/f2806x/src/hal_obj.h [external]
 i2c.h [external]
 ipark/docs/doxygen/doxygen.h [external]
 ipd_hfi.h [external]
 IQlog.h [external]
 iqmath/docs/doxygen/doxygen.h [external]
 lin.h [external]
 main.hDefines the structures, global initialization, and functions used in MAIN
 main_position.h
 math/docs/doxygen/doxygen.h [external]
 memCopy.c [external]
 memCopy.h [external]
 memCopy/docs/doxygen/doxygen.h [external]
 motor/docs/doxygen/doxygen.h [external]
 osc.c [external]
 osc.h [external]
 park/docs/doxygen/doxygen.h [external]
 pid/docs/doxygen/doxygen.h [external]
 pie.c [external]
 pie.h [external]
 pll.c [external]
 pll.h [external]
 proj_lab05c.cInstaSPIN-MOTION Inertia Identification
 proj_lab05d.cInstaSPIN-MOTION SpinTAC Speed Controller
 proj_lab05e.cTuning the SpinTAC Velocity Controller
 proj_lab05f.cComparing performance of PI velocity controller & SpinTAC velocity controller
 proj_lab06a.cDesigning velocity trajectory changes using the SpinTAC Velocity Profile Generator
 proj_lab06b.cDesigning Motion Sequences using SpinTAC Plan
 proj_lab06c.cMotion Sequence Example: Washing Machine
 proj_lab06d.cDesign a motion sequence
 proj_lab10b.cAutomatic Field Weakening and Space Vector Over-Modulation with SpinTAC
 proj_lab12a.cInstaSPIN-MOTION Inertia Identification using a quadrature encoder for feedback
 proj_lab12b.cSpinTAC Velocity Controller using a quadrature encoder for feedback
 proj_lab13a.cTuning the InstaSPIN-MOTION Position Controller
 proj_lab13b.cMooth Position Transitions with SpinTAC Move
 proj_lab13c.cMotion Sequence Example with SpinTAC Plan
 proj_lab13d.cMotion Sequence Real World Example: Vending Machine
 proj_lab13e.cSmooth Velocity Transitions in Position Control
 pwm.c [external]
 pwm.h [external]
 pwmdac.h [external]
 pwr.c [external]
 pwr.h [external]
 qep.c [external]
 qep.h [external]
 queue.c [external]
 queue.h [external]
 queue/docs/doxygen/doxygen.h [external]
 sci.c [external]
 sci.h [external]
 slip.c [external]
 slip.h [external]
 spi.c [external]
 spi.h [external]
 spintac_pos_conv.h [external]
 spintac_pos_ctl.h [external]
 spintac_pos_move.h [external]
 spintac_pos_plan.h [external]
 spintac_position.hContains public interface to various functions related to the SpinTAC (ST) object
 spintac_vel_ctl.h [external]
 spintac_vel_id.h [external]
 spintac_vel_move.h [external]
 spintac_vel_plan.h [external]
 spintac_velocity.hContains public interface to various functions related to the SpinTAC (ST) object
 spintac_version.h [external]
 svgen/docs/doxygen/doxygen.h [external]
 svgen_current.c [external]
 svgen_current.h [external]
 timer.c [external]
 timer.h [external]
 traj/docs/doxygen/doxygen.h [external]
 types.h [external]
 types/docs/doxygen/doxygen.h [external]
 usDelay.h [external]
 usDelay/docs/doxygen/doxygen.h [external]
 user.c
 user.hContains the public interface for user initialization data for the CTRL, HAL, and EST modules
 user/src/32b/userParams.h [external]
 user/src/float/userParams.h [external]
 user_j1.hContains the public interface for user initialization data for the CTRL, HAL, and EST modules
 user_j5.hContains the public interface for user initialization data for the CTRL, HAL, and EST modules
 vib_comp.h [external]
 wdog.c [external]
 wdog.h [external]
-+
-+
-+ -+ -+ -+ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/folderclosed.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/folderclosed.png differ -Binary files motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/folderopen.png and motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/folderopen.png differ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions.html 2017-06-08 10:42:11.663748300 +0200 -*************** -*** 0 **** ---- 1,469 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Data Fields -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all struct and union fields with links to the structures/unions they belong to:
-+ -+

- c -

-+ -+ -+

- e -

-+ -+ -+

- f -

-+ -+ -+

- i -

-+ -+ -+

- k -

-+ -+ -+

- l -

-+ -+ -+

- m -

-+ -+ -+

- o -

-+ -+ -+

- p -

-+ -+ -+

- r -

-+ -+ -+

- s -

-+ -+ -+

- t -

-+ -+ -+

- u -

-+ -+ -+

- v -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions_vars.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions_vars.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions_vars.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/functions_vars.html 2017-06-08 10:42:11.679348300 +0200 -*************** -*** 0 **** ---- 1,469 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Data Fields - Variables -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- c -

-+ -+ -+

- e -

-+ -+ -+

- f -

-+ -+ -+

- i -

-+ -+ -+

- k -

-+ -+ -+

- l -

-+ -+ -+

- m -

-+ -+ -+

- o -

-+ -+ -+

- p -

-+ -+ -+

- r -

-+ -+ -+

- s -

-+ -+ -+

- t -

-+ -+ -+

- u -

-+ -+ -+

- v -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals.html 2017-06-08 10:42:11.679348300 +0200 -*************** -*** 0 **** ---- 1,100 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- a -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_b.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_b.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_b.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_b.html 2017-06-08 10:42:11.694948300 +0200 -*************** -*** 0 **** ---- 1,96 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- b -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_c.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_c.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_c.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_c.html 2017-06-08 10:42:11.694948300 +0200 -*************** -*** 0 **** ---- 1,136 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- c -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_defs.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_defs.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_defs.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_defs.html 2017-06-08 10:42:11.710548300 +0200 -*************** -*** 0 **** ---- 1,531 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- a -

-+ -+ -+

- b -

-+ -+ -+

- e -

-+ -+ -+

- g -

-+ -+ -+

- i -

-+ -+ -+

- j -

-+ -+ -+

- l -

-+ -+ -+

- m -

-+ -+ -+

- n -

-+ -+ -+

- s -

-+ -+ -+

- t -

-+ -+ -+

- u -

-+ -+ -+

- v -

-+ -+ -+

- w -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_e.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_e.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_e.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_e.html 2017-06-08 10:42:11.710548300 +0200 -*************** -*** 0 **** ---- 1,114 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- e -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_enum.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_enum.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_enum.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_enum.html 2017-06-08 10:42:11.713048300 +0200 -*************** -*** 0 **** ---- 1,149 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+   -+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_eval.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_eval.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_eval.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_eval.html 2017-06-08 10:42:11.713048300 +0200 -*************** -*** 0 **** ---- 1,539 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- g -

-+ -+ -+

- n -

-+ -+ -+

- s -

-+ -+ -+

- t -

-+ -+ -+

- v -

-+ -+ -+

- w -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_f.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_f.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_f.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_f.html 2017-06-08 10:42:11.728648300 +0200 -*************** -*** 0 **** ---- 1,116 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- f -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_func.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_func.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_func.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_func.html 2017-06-08 10:42:11.744248300 +0200 -*************** -*** 0 **** ---- 1,359 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- a -

-+ -+ -+

- c -

-+ -+ -+

- m -

-+ -+ -+

- r -

-+ -+ -+

- s -

-+ -+ -+

- u -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_g.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_g.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_g.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_g.html 2017-06-08 10:42:11.744248300 +0200 -*************** -*** 0 **** ---- 1,516 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- g -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_h.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_h.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_h.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_h.html 2017-06-08 10:42:11.759848300 +0200 -*************** -*** 0 **** ---- 1,110 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- h -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_i.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_i.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_i.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_i.html 2017-06-08 10:42:11.759848300 +0200 -*************** -*** 0 **** ---- 1,111 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- i -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_j.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_j.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_j.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_j.html 2017-06-08 10:42:11.775448300 +0200 -*************** -*** 0 **** ---- 1,95 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- j -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_l.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_l.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_l.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_l.html 2017-06-08 10:42:11.775448300 +0200 -*************** -*** 0 **** ---- 1,110 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- l -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_m.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_m.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_m.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_m.html 2017-06-08 10:42:11.775448300 +0200 -*************** -*** 0 **** ---- 1,144 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- m -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_n.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_n.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_n.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_n.html 2017-06-08 10:42:11.791048300 +0200 -*************** -*** 0 **** ---- 1,167 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- n -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_p.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_p.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_p.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_p.html 2017-06-08 10:42:11.791048300 +0200 -*************** -*** 0 **** ---- 1,110 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- p -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_r.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_r.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_r.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_r.html 2017-06-08 10:42:11.791048300 +0200 -*************** -*** 0 **** ---- 1,100 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- r -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_s.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_s.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_s.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_s.html 2017-06-08 10:42:11.806648300 +0200 -*************** -*** 0 **** ---- 1,372 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- s -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_t.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_t.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_t.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_t.html 2017-06-08 10:42:11.806648300 +0200 -*************** -*** 0 **** ---- 1,189 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- t -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_type.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_type.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_type.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_type.html 2017-06-08 10:42:11.822248300 +0200 -*************** -*** 0 **** ---- 1,89 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+   -+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_u.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_u.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_u.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_u.html 2017-06-08 10:42:11.822248300 +0200 -*************** -*** 0 **** ---- 1,429 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- u -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_v.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_v.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_v.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_v.html 2017-06-08 10:42:11.837848300 +0200 -*************** -*** 0 **** ---- 1,206 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- v -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars.html 2017-06-08 10:42:11.837848300 +0200 -*************** -*** 0 **** ---- 1,116 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_e.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_e.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_e.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_e.html 2017-06-08 10:42:11.837848300 +0200 -*************** -*** 0 **** ---- 1,98 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- e -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_f.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_f.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_f.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_f.html 2017-06-08 10:42:11.853448300 +0200 -*************** -*** 0 **** ---- 1,104 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- f -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_g.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_g.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_g.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_g.html 2017-06-08 10:42:11.853448300 +0200 -*************** -*** 0 **** ---- 1,381 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- g -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_h.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_h.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_h.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_h.html 2017-06-08 10:42:11.853448300 +0200 -*************** -*** 0 **** ---- 1,98 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_i.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_i.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_i.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_i.html 2017-06-08 10:42:11.869048300 +0200 -*************** -*** 0 **** ---- 1,83 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- i -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_s.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_s.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_s.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_vars_s.html 2017-06-08 10:42:11.869048300 +0200 -*************** -*** 0 **** ---- 1,152 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+   -+ -+

- s -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/globals_w.html 2017-06-08 10:42:11.884648300 +0200 -*************** -*** 0 **** ---- 1,197 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Globals -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+ -+ -+ -+
-+
-+
Here is a list of all functions, variables, defines, enums, and typedefs with links to the files they belong to:
-+ -+

- w -

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c.html 2017-06-08 10:42:11.884648300 +0200 -*************** -*** 0 **** ---- 1,767 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB05c -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB05c
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void CTRL_resetLs_qFmt (CTRL_Handle handle, const uint_least8_t Ls_qFmt)
 Reset Ls Q format to a higher value when Ls identification starts. More...
 
void recalcKpKiPmsm (CTRL_Handle handle)
 Recalculate Kp and Ki gains to fix the R/L limitation of 2000.0 and Kp limitation of 0.11. More...
 
void CTRL_calcMax_Ls_qFmt (CTRL_Handle handle, uint_least8_t *pLs_qFmt)
 Calculates the maximum qFmt value for Ls identification, to get a more accurate Ls per unit. More...
 
void recalcKpKi (CTRL_Handle handle)
 Recalculate Kp and Ki gains to fix the R/L limitation of 2000.0 and Kp limitation of 0.11. More...
 
void setFeLimitZero (CTRL_Handle handle)
 Set electrical frequency limit to zero while identifying an induction motor. More...
 
void acim_Dir_qFmtCalc (CTRL_Handle handle)
 Calculates Dir_qFmt for ACIM. More...
 
void ST_runVelId (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Identify. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_iq gLs_pu = _IQ30(0.0)
 
uint_least8_t gLs_qFmt = 0
 
uint_least8_t gMax_Ls_qFmt = 0
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab05c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void acim_Dir_qFmtCalc (CTRL_Handle handle)
-+
-+ -+

Calculates Dir_qFmt for ACIM.

-+ -+

Definition at line 751 of file proj_lab05c.c.

-+ -+

References EST_computeDirection_qFmt(), EST_getState(), EST_setDir_qFmt(), and _CTRL_Obj_::estHandle.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void CTRL_calcMax_Ls_qFmt (CTRL_Handle handle,
uint_least8_t * pLs_qFmt 
)
-+
-+ -+

Calculates the maximum qFmt value for Ls identification, to get a more accurate Ls per unit.

-+ -+

Definition at line 671 of file proj_lab05c.c.

-+ -+

References _IQ30toF(), CTRL_getLhf(), EST_getLs_coarse_max_pu(), EST_getState(), EST_isMotorIdentified(), _CTRL_Obj_::estHandle, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, and USER_VOLTAGE_FILTER_POLE_rps.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void CTRL_resetLs_qFmt (CTRL_Handle handle,
const uint_least8_t Ls_qFmt 
)
-+
-+ -+

Reset Ls Q format to a higher value when Ls identification starts.

-+ -+

Definition at line 593 of file proj_lab05c.c.

-+ -+

References _IQ30, EST_getLs_d_pu(), EST_getState(), EST_setLs_qFmt(), and _CTRL_Obj_::estHandle.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 125 of file proj_lab05c.c.

-+ -+

References _IQ, _IQmpy, acim_Dir_qFmtCalc(), CTRL_calcMax_Ls_qFmt(), CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getMotorType(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getLs_d_pu(), EST_getLs_qFmt(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gLs_pu, gLs_qFmt, gMax_Ls_qFmt, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), _MOTOR_Vars_t_::I_bias, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, _MOTOR_Vars_t_::Kp_spd, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, recalcKpKi(), recalcKpKiPmsm(), setFeLimitZero(), _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelId(), ST_SPEED_KRPM_PER_PU, stHandle, STVELID_getGoalSpeed(), STVELID_getTorqueRampTime_sec(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, _MOTOR_Vars_t_::V_bias, _MATH_vec3_::value, _ST_Vars_t::VelIdGoalSpeed_krpm, _ST_Obj::velIdHandle, and _ST_Vars_t::VelIdTorqueRampTime_sec.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void recalcKpKi (CTRL_Handle handle)
-+
-+ -+

Recalculate Kp and Ki gains to fix the R/L limitation of 2000.0 and Kp limitation of 0.11.

-+ -+

Definition at line 689 of file proj_lab05c.c.

-+ -+

References _IQ, CTRL_getLhf(), CTRL_getRhf(), CTRL_setKi(), CTRL_setKp(), CTRL_setRoverL(), EST_getState(), EST_isMotorIdentified(), _CTRL_Obj_::estHandle, PID_setKi(), _CTRL_Obj_::pidHandle_Id, _CTRL_Obj_::pidHandle_Iq, USER_CTRL_PERIOD_sec, USER_IQ_FULL_SCALE_CURRENT_A, and USER_IQ_FULL_SCALE_VOLTAGE_V.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void recalcKpKiPmsm (CTRL_Handle handle)
-+
-+ -+

Recalculate Kp and Ki gains to fix the R/L limitation of 2000.0 and Kp limitation of 0.11.

-+

as well as recalculates gains based on estimator state to allow low inductance pmsm to id

-+ -+

Definition at line 616 of file proj_lab05c.c.

-+ -+

References _IQ, CTRL_getLhf(), CTRL_getRhf(), CTRL_setKi(), CTRL_setKp(), CTRL_setRoverL(), EST_getState(), EST_isMotorIdentified(), _CTRL_Obj_::estHandle, PID_setKi(), PID_setKp(), _CTRL_Obj_::pidHandle_Id, _CTRL_Obj_::pidHandle_Iq, _CTRL_Obj_::pidHandle_spd, TRAJ_setTargetValue(), _CTRL_Obj_::trajHandle_spdMax, USER_CTRL_PERIOD_sec, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MOTOR_MAX_CURRENT, and USER_MOTOR_RES_EST_CURRENT.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void setFeLimitZero (CTRL_Handle handle)
-+
-+ -+

Set electrical frequency limit to zero while identifying an induction motor.

-+ -+

Definition at line 722 of file proj_lab05c.c.

-+ -+

References _IQ30, CTRL_getMotorType(), EST_getState(), EST_isMotorIdentified(), EST_setFe_neg_max_pu(), EST_setFe_pos_min_pu(), _CTRL_Obj_::estHandle, and USER_ZEROSPEEDLIMIT.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelId (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+ -+

Runs SpinTAC Velocity Identify.

-+ -+

Definition at line 765 of file proj_lab05c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 574 of file proj_lab05c.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab05c.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab05c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 116 of file proj_lab05c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 114 of file proj_lab05c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 96 of file proj_lab05c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gLs_pu = _IQ30(0.0)
-+
-+ -+

Definition at line 105 of file proj_lab05c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least8_t gLs_qFmt = 0
-+
-+ -+

Definition at line 106 of file proj_lab05c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least8_t gMax_Ls_qFmt = 0
-+
-+ -+

Definition at line 107 of file proj_lab05c.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab05c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 98 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 120 of file proj_lab05c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 118 of file proj_lab05c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab05c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab05c.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05c___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:11.900248300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

InstaSPIN-MOTION Inertia Identification

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d.html 2017-06-08 10:42:11.900248300 +0200 -*************** -*** 0 **** ---- 1,530 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB05d -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB05d
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab05d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 122 of file proj_lab05d.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), stHandle, STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, and _ST_Vars_t::VelCtlOutputMin_A.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+ -+

The main interrupt service (ISR) routine.

-+ -+

Definition at line 442 of file proj_lab05d.c.

-+ -+

References CTRL_run(), CTRL_setup(), gLEDcnt, HAL_acqAdcInt(), HAL_readAdcData(), HAL_toggleLed, HAL_writePwmData(), ISR_TICKS_PER_SPINTAC_TICK, LED_BLINK_FREQ_Hz, ST_runVelCtl(), stHandle, and USER_ISR_FREQ_Hz.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+ -+

Runs SpinTAC Velocity Control.

-+ -+

Definition at line 569 of file proj_lab05d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 550 of file proj_lab05d.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab05d.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab05d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 113 of file proj_lab05d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 111 of file proj_lab05d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 96 of file proj_lab05d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab05d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 98 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 117 of file proj_lab05d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 115 of file proj_lab05d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab05d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab05d.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05d___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:11.915848300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Running the SpinTAC Velocity Controller

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e.html 2017-06-08 10:42:11.915848300 +0200 -*************** -*** 0 **** ---- 1,532 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB05e -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB05e
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab05e.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 122 of file proj_lab05e.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, and _ST_Vars_t::VelCtlOutputMin_A.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+ -+

The main interrupt service (ISR) routine.

-+ -+

Definition at line 448 of file proj_lab05e.c.

-+ -+

References CTRL_run(), CTRL_setup(), gLEDcnt, HAL_acqAdcInt(), HAL_readAdcData(), HAL_toggleLed, HAL_writePwmData(), ISR_TICKS_PER_SPINTAC_TICK, LED_BLINK_FREQ_Hz, ST_runVelCtl(), stHandle, and USER_ISR_FREQ_Hz.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 556 of file proj_lab05e.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab05e.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab05e.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 113 of file proj_lab05e.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 111 of file proj_lab05e.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 96 of file proj_lab05e.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab05e.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 98 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 117 of file proj_lab05e.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 115 of file proj_lab05e.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab05e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab05e.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05e___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:11.931448300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Tuning the SpinTAC Velocity Controller

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f.html 2017-06-08 10:42:11.931448300 +0200 -*************** -*** 0 **** ---- 1,676 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB05f -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB05f
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
#define GRAPH_SIZE   300
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
volatile bool Graph_Flag_Enable_update = false
 
volatile unsigned int Graph_Counter = 0
 
volatile unsigned short Graph_Tick_Counter = 0
 
volatile unsigned short Graph_Tick_Counter_Value = 10
 
volatile _iq Graph_Data [GRAPH_SIZE]
 
volatile _iq Graph_Data2 [GRAPH_SIZE]
 
volatile _iq SpeedRef_krpm_previous = _IQ(0.0)
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define GRAPH_SIZE   300
-+
-+ -+

Definition at line 105 of file proj_lab05f.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 132 of file proj_lab05f.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, Graph_Data, Graph_Data2, GRAPH_SIZE, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, _MOTOR_Vars_t_::Kp_spd, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Vars_t::VelCtlEnb, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, and _ST_Vars_t::VelCtlOutputMin_A.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 608 of file proj_lab05f.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab05f.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab05f.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 123 of file proj_lab05f.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 121 of file proj_lab05f.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 96 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab05f.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 98 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile unsigned int Graph_Counter = 0
-+
-+ -+

Definition at line 102 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile _iq Graph_Data[GRAPH_SIZE]
-+
-+ -+

Definition at line 106 of file proj_lab05f.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile _iq Graph_Data2[GRAPH_SIZE]
-+
-+ -+

Definition at line 107 of file proj_lab05f.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile bool Graph_Flag_Enable_update = false
-+
-+ -+

Definition at line 101 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile unsigned short Graph_Tick_Counter = 0
-+
-+ -+

Definition at line 103 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile unsigned short Graph_Tick_Counter_Value = 10
-+
-+ -+

Definition at line 104 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 127 of file proj_lab05f.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 125 of file proj_lab05f.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile _iq SpeedRef_krpm_previous = _IQ(0.0)
-+
-+ -+

Definition at line 108 of file proj_lab05f.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab05f.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab05f.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b05f___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.277148300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Comparing performance of PI velocity controller & SpinTAC velocity controller

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a.html 2017-06-08 10:42:12.292748300 +0200 -*************** -*** 0 **** ---- 1,567 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB06a -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB06a
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runVelMove (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Move. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab06a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 122 of file proj_lab06a.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), ST_setupVelMove(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), STVELMOVE_setVelocityEnd(), STVELMOVE_setVelocityStart(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, _ST_Vars_t::VelCtlOutputMin_A, and _ST_Obj::velMoveHandle.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+ -+

The main interrupt service (ISR) routine.

-+ -+

Definition at line 453 of file proj_lab06a.c.

-+ -+

References CTRL_run(), CTRL_setup(), gLEDcnt, HAL_acqAdcInt(), HAL_readAdcData(), HAL_toggleLed, HAL_writePwmData(), ISR_TICKS_PER_SPINTAC_TICK, LED_BLINK_FREQ_Hz, ST_runVelCtl(), ST_runVelMove(), stHandle, and USER_ISR_FREQ_Hz.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelMove (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+ -+

Runs SpinTAC Velocity Move.

-+ -+

Definition at line 590 of file proj_lab06a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 571 of file proj_lab06a.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab06a.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab06a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 113 of file proj_lab06a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 111 of file proj_lab06a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 96 of file proj_lab06a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab06a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 98 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 117 of file proj_lab06a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 115 of file proj_lab06a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab06a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab06a.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06a___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.323948300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Designing velocity trajectory changes using the SpinTAC Velocity Profile Generator

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b.html 2017-06-08 10:42:12.339548300 +0200 -*************** -*** 0 **** ---- 1,769 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB06b -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Enumerations | -+ Functions | -+ Variables
-+
-+
PROJ_LAB06b
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
#define ST_VELPLAN_CFG_ARRAY_DWORDS
 
-+ -+ -+ -+ -+ -+

-+ Enumerations

enum  PlanState_e { STATE_A = 0, -+ STATE_B, -+ STATE_C, -+ NUM_PLAN_STATES -+ }
 
enum  PlanTran_e { TRAN_A_TO_B = 0, -+ TRAN_B_TO_C, -+ TRAN_C_TO_A, -+ NUM_PLAN_TRANS -+ }
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_setupVelPlan (ST_Handle handle)
 Setups SpinTAC Velocity Plan. More...
 
void ST_runVelPlan (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Plan. More...
 
void ST_runVelMove (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Move. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
ST_PlanButton_e gVelPlanRunFlag = ST_PLAN_STOP
 
uint32_t stVelPlanCfgArray [ST_VELPLAN_CFG_ARRAY_DWORDS]
 
PlanState_e gState = STATE_A
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab06b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_VELPLAN_CFG_ARRAY_DWORDS
-+
-+ Value:
-+
(ST_VEL_PLAN_STATE_DWORDS * NUM_PLAN_STATES))
-+
#define ST_VEL_PLAN_TRAN_DWORDS
-+ -+ -+
-+

Definition at line 119 of file proj_lab06b.c.

-+ -+
-+
-+

Enumeration Type Documentation

-+ -+
-+
-+ -+ -+ -+ -+
enum PlanState_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
STATE_A  -+
STATE_B  -+
STATE_C  -+
NUM_PLAN_STATES  -+
-+ -+

Definition at line 100 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum PlanTran_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
TRAN_A_TO_B  -+
TRAN_B_TO_C  -+
TRAN_C_TO_A  -+
NUM_PLAN_TRANS  -+
-+ -+

Definition at line 109 of file proj_lab06b.c.

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 153 of file proj_lab06b.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), ST_setupVelMove(), ST_setupVelPlan(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), STVELMOVE_setVelocityEnd(), STVELMOVE_setVelocityStart(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, _ST_Vars_t::VelCtlOutputMin_A, and _ST_Obj::velMoveHandle.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelPlan (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+ -+

Runs SpinTAC Velocity Plan.

-+ -+

Definition at line 663 of file proj_lab06b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupVelPlan (ST_Handle handle)
-+
-+ -+

Setups SpinTAC Velocity Plan.

-+ -+

Definition at line 633 of file proj_lab06b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 532 of file proj_lab06b.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_get_pu_to_krpm_sf(), EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getSpeed_krpm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpeedTraj_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_PU_PER_KRPM, STVELCTL_getErrorID(), STVELCTL_getFriction(), STVELCTL_getInertia(), STVELCTL_getStatus(), STVELCTL_getTorqueReference(), STVELMOVE_getErrorID(), STVELMOVE_getProfileTime_tick(), STVELMOVE_getStatus(), STVELMOVE_getVelocityReference(), STVELPLAN_getCfgError(), STVELPLAN_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, _MOTOR_Vars_t_::VdcBus_kV, _ST_Vars_t::VelCtlErrorID, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlStatus, _ST_Vars_t::VelMoveErrorID, _ST_Obj::velMoveHandle, _ST_Vars_t::VelMoveStatus, _ST_Vars_t::VelMoveTime_ticks, _ST_Vars_t::VelPlanCfgErrorCode, _ST_Vars_t::VelPlanCfgErrorIdx, _ST_Vars_t::VelPlanErrorID, _ST_Obj::velPlanHandle, and _ST_Vars_t::VelPlanStatus.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 614 of file proj_lab06b.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab06b.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab06b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 144 of file proj_lab06b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 142 of file proj_lab06b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 127 of file proj_lab06b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab06b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 129 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
PlanState_e gState = STATE_A
-+
-+ -+

Definition at line 125 of file proj_lab06b.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 148 of file proj_lab06b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 146 of file proj_lab06b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_PlanButton_e gVelPlanRunFlag = ST_PLAN_STOP
-+
-+ -+

Definition at line 97 of file proj_lab06b.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab06b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab06b.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint32_t stVelPlanCfgArray[ST_VELPLAN_CFG_ARRAY_DWORDS]
-+
-+ -+

Definition at line 123 of file proj_lab06b.c.

-+ -+

Referenced by ST_setupVelPlan().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06b___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.355148300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Designing Motion Sequences using SpinTAC Plan

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c.html 2017-06-08 10:42:12.355148300 +0200 -*************** -*** 0 **** ---- 1,997 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB06c -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Enumerations | -+ Functions | -+ Variables
-+
-+
PROJ_LAB06c
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
#define WASHER_MAX_WATER_LEVEL   (1000)
 
#define WASHER_MIN_WATER_LEVEL   (0)
 
#define ST_VELPLAN_CFG_ARRAY_DWORDS
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Enumerations

enum  WASHER_State_e {
-+   WASHER_IDLE = 0, -+ WASHER_FILL, -+ WASHER_AGI_CCW, -+ WASHER_AGI_CW, -+
-+   WASHER_DRAIN, -+ WASHER_DRY, -+ NUM_WASHER_STATES -+
-+ }
 
enum  WASHER_Vars_e {
-+   WASHER_FillSensor = 0, -+ WASHER_DrainSensor, -+ WASHER_CycleCounter, -+ WASHER_FillValve, -+
-+   WASHER_DrainValve, -+ NUM_WASHER_VARS -+
-+ }
 
enum  WASHER_Cond_e {
-+   WASHER_WaterFull = 0, -+ WASHER_AgiNotDone, -+ WASHER_AgiDone, -+ WASHER_WaterEmpty, -+
-+   NUM_WASHER_CONDS -+
-+ }
 
enum  WASHER_Acts_e {
-+   WASHER_SetCycleCnt = 0, -+ WASHER_DecCycleCnt, -+ WASHER_OpenFillValve, -+ WASHER_CloseValveWhenFull, -+
-+   WASHER_OpenDrainValve, -+ WASHER_CloseDrainWhenDone, -+ NUM_WASHER_ACTS -+
-+ }
 
enum  WASHER_Trans_e {
-+   WASHER_IdleToFill = 0, -+ WASHER_FillToAgi1, -+ WASHER_Agi1ToAgi2, -+ WASHER_Agi2ToAgi1, -+
-+   WASHER_Agi2ToDrain, -+ WASHER_DrainToDry, -+ WASHER_DryToIdle, -+ NUM_WASHER_TRANS -+
-+ }
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_setupVelPlan (ST_Handle handle)
 Setups SpinTAC Velocity Plan. More...
 
void ST_runVelPlan (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Plan. More...
 
void ST_runVelMove (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Move. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
ST_PlanButton_e gVelPlanRunFlag = ST_PLAN_STOP
 
uint32_t stVelPlanCfgArray [ST_VELPLAN_CFG_ARRAY_DWORDS]
 
_iq gVelPanVar [NUM_WASHER_VARS]
 
WASHER_State_e gWasherState = WASHER_IDLE
 
unsigned long gWaterLevel = 0
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab06c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_VELPLAN_CFG_ARRAY_DWORDS
-+
-+ Value:
-+
(ST_VEL_PLAN_COND_DWORDS * NUM_WASHER_CONDS) + \
-+ -+
(ST_VEL_PLAN_TRAN_DWORDS * NUM_WASHER_TRANS) + \
-+ -+
#define ST_VEL_PLAN_STATE_DWORDS
-+ -+
#define ST_VEL_PLAN_VAR_DWORDS
-+ -+ -+ -+ -+
#define ST_VEL_PLAN_ACT_DWORDS
-+
-+

Definition at line 162 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define WASHER_MAX_WATER_LEVEL   (1000)
-+
-+ -+

Definition at line 67 of file proj_lab06c.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define WASHER_MIN_WATER_LEVEL   (0)
-+
-+ -+

Definition at line 69 of file proj_lab06c.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+

Enumeration Type Documentation

-+ -+
-+
-+ -+ -+ -+ -+
enum WASHER_Acts_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
WASHER_SetCycleCnt  -+
WASHER_DecCycleCnt  -+
WASHER_OpenFillValve  -+
WASHER_CloseValveWhenFull  -+
WASHER_OpenDrainValve  -+
WASHER_CloseDrainWhenDone  -+
NUM_WASHER_ACTS  -+
-+ -+

Definition at line 136 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum WASHER_Cond_e
-+
-+ -+ -+ -+ -+ -+ -+
Enumerator
WASHER_WaterFull  -+
WASHER_AgiNotDone  -+
WASHER_AgiDone  -+
WASHER_WaterEmpty  -+
NUM_WASHER_CONDS  -+
-+ -+

Definition at line 126 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum WASHER_State_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
WASHER_IDLE  -+
WASHER_FILL  -+
WASHER_AGI_CCW  -+
WASHER_AGI_CW  -+
WASHER_DRAIN  -+
WASHER_DRY  -+
NUM_WASHER_STATES  -+
-+ -+

Definition at line 103 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum WASHER_Trans_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
WASHER_IdleToFill  -+
WASHER_FillToAgi1  -+
WASHER_Agi1ToAgi2  -+
WASHER_Agi2ToAgi1  -+
WASHER_Agi2ToDrain  -+
WASHER_DrainToDry  -+
WASHER_DryToIdle  -+
NUM_WASHER_TRANS  -+
-+ -+

Definition at line 148 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum WASHER_Vars_e
-+
-+ -+ -+ -+ -+ -+ -+ -+
Enumerator
WASHER_FillSensor  -+
WASHER_DrainSensor  -+
WASHER_CycleCounter  -+
WASHER_FillValve  -+
WASHER_DrainValve  -+
NUM_WASHER_VARS  -+
-+ -+

Definition at line 115 of file proj_lab06c.c.

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 205 of file proj_lab06c.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), ST_setupVelMove(), ST_setupVelPlan(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), STVELMOVE_setVelocityEnd(), STVELMOVE_setVelocityStart(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, _ST_Vars_t::VelCtlOutputMin_A, and _ST_Obj::velMoveHandle.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 584 of file proj_lab06c.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_get_pu_to_krpm_sf(), EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getSpeed_krpm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpeedTraj_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_PU_PER_KRPM, STVELCTL_getErrorID(), STVELCTL_getFriction(), STVELCTL_getInertia(), STVELCTL_getStatus(), STVELCTL_getTorqueReference(), STVELMOVE_getErrorID(), STVELMOVE_getProfileTime_tick(), STVELMOVE_getStatus(), STVELMOVE_getVelocityReference(), STVELPLAN_getCfgError(), STVELPLAN_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, _MOTOR_Vars_t_::VdcBus_kV, _ST_Vars_t::VelCtlErrorID, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlStatus, _ST_Vars_t::VelMoveErrorID, _ST_Obj::velMoveHandle, _ST_Vars_t::VelMoveStatus, _ST_Vars_t::VelMoveTime_ticks, _ST_Vars_t::VelPlanCfgErrorCode, _ST_Vars_t::VelPlanCfgErrorIdx, _ST_Vars_t::VelPlanErrorID, _ST_Obj::velPlanHandle, and _ST_Vars_t::VelPlanStatus.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 666 of file proj_lab06c.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 93 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 78 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 76 of file proj_lab06c.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 86 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 74 of file proj_lab06c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 196 of file proj_lab06c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 194 of file proj_lab06c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 179 of file proj_lab06c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 88 of file proj_lab06c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 181 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 84 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 200 of file proj_lab06c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 198 of file proj_lab06c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 82 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gVelPanVar[NUM_WASHER_VARS]
-+
-+ -+

Definition at line 172 of file proj_lab06c.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_PlanButton_e gVelPlanRunFlag = ST_PLAN_STOP
-+
-+ -+

Definition at line 100 of file proj_lab06c.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
WASHER_State_e gWasherState = WASHER_IDLE
-+
-+ -+

Definition at line 174 of file proj_lab06c.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
unsigned long gWaterLevel = 0
-+
-+ -+

Definition at line 177 of file proj_lab06c.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 80 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 96 of file proj_lab06c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 97 of file proj_lab06c.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint32_t stVelPlanCfgArray[ST_VELPLAN_CFG_ARRAY_DWORDS]
-+
-+ -+

Definition at line 169 of file proj_lab06c.c.

-+ -+

Referenced by ST_setupVelPlan().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06c___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.370748300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Motion Sequence Example: Washing Machine

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d.html 2017-06-08 10:42:12.386348300 +0200 -*************** -*** 0 **** ---- 1,1378 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB06d -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Enumerations | -+ Functions | -+ Variables
-+
-+
PROJ_LAB06d
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
#define ST_VELPLAN_CFG_ARRAY_DWORDS
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Enumerations

enum  PLAN_SELECT_e { TEST_PATTERN =0, -+ GROCERY_CONVEYOR, -+ GARAGE_DOOR -+ }
 
enum  TEST_State_e {
-+   TEST_0 = 0, -+ TEST_4000, -+ TEST_N4000, -+ TEST_2000, -+
-+   TEST_N2000, -+ TEST_1000, -+ TEST_N1000, -+ TEST_500, -+
-+   TEST_N500, -+ TEST_250, -+ TEST_N250, -+ NUM_TEST_STATES -+
-+ }
 
enum  TEST_Trans_e {
-+   TEST_0to4000 = 0, -+ TEST_4000toN4000, -+ TEST_N4000to2000, -+ TEST_2000toN2000, -+
-+   TEST_N2000to1000, -+ TEST_1000toN1000, -+ TEST_N1000to500, -+ TEST_500toN500, -+
-+   TEST_N500to250, -+ TEST_250toN250, -+ TEST_N250to0, -+ NUM_TEST_TRANS -+
-+ }
 
enum  GROCERY_State_e { GROCERY_Idle = 0, -+ GROCERY_Convey, -+ NUM_GROCERY_STATES -+ }
 
enum  GROCERY_Vars_e { GROCERY_OnOff = 0, -+ GROCERY_ProxSensor, -+ NUM_GROCERY_VARS -+ }
 
enum  GROCERY_Cond_e {
-+   GROCERY_SwitchOn = 0, -+ GROCERY_SwitchOff, -+ GROCERY_ProxOpen, -+ GROCERY_ProxBlocked, -+
-+   NUM_GROCERY_CONDS -+
-+ }
 
enum  GROCERY_Trans_e { GROCERY_IdleToConvey = 0, -+ GROCERY_ConveyToIdle, -+ NUM_GROCERY_TRANS -+ }
 
enum  GARAGE_State_e { GARAGE_Idle = 0, -+ GARAGE_Down, -+ GARAGE_Up, -+ NUM_GARAGE_STATES -+ }
 
enum  GARAGE_Vars_e { GARAGE_DownSensor = 0, -+ GARAGE_UpSensor, -+ GARAGE_Button, -+ NUM_GARAGE_VARS -+ }
 
enum  GARAGE_Cond_e { GARAGE_DoorDown = 0, -+ GARAGE_DoorUp, -+ GARAGE_ButtonPressed, -+ NUM_GARAGE_CONDS -+ }
 
enum  GARAGE_Acts_e {
-+   GARAGE_ClearButtonDown = 0, -+ GARAGE_ClearButtonUp, -+ GARAGE_ClearDownSensor, -+ GARAGE_ClearUpSensor, -+
-+   NUM_GARAGE_ACTS -+
-+ }
 
enum  GARAGE_Trans_e {
-+   GARAGE_IdleToDown = 0, -+ GARAGE_IdleToUp, -+ GARAGE_DownToUp, -+ GARAGE_UpToDown, -+
-+   GARAGE_DownToIdle, -+ GARAGE_UpToIdle, -+ NUM_GARAGE_TRANS -+
-+ }
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void ST_setupVelPlan_TestPattern (ST_Handle sthandle)
 
void ST_setupVelPlan_GroceryConveyor (ST_Handle sthandle)
 
void ST_setupVelPlan_GarageDoor (ST_Handle sthandle)
 
void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_setupVelPlan (ST_Handle handle)
 Setups SpinTAC Velocity Plan. More...
 
void ST_runVelPlan (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Plan. More...
 
void ST_runVelMove (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Move. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
ST_PlanButton_e gVelPlanRunFlag = ST_PLAN_STOP
 
PLAN_SELECT_e gSelectedPlan = TEST_PATTERN
 
PLAN_SELECT_e gConfiguredPlan = TEST_PATTERN
 
uint32_t stVelPlanCfgArray [ST_VELPLAN_CFG_ARRAY_DWORDS]
 
TEST_State_e gTestState = TEST_0
 
GROCERY_State_e gGroceryState = GROCERY_Idle
 
_iq gGroceryConveyorOnOff = 0
 
_iq gGroceryConveyorProxSensor = 0
 
GARAGE_State_e gGarageState = GARAGE_Idle
 
_iq gGarageDoorDown = 1
 
_iq gGarageDoorUp = 0
 
_iq gGarageDoorButton = 0
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab06d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_VELPLAN_CFG_ARRAY_DWORDS
-+
-+ Value:
-+
(ST_VEL_PLAN_COND_DWORDS * 5) + \
-+ -+
(ST_VEL_PLAN_TRAN_DWORDS * 15) + \
-+ -+
#define ST_VEL_PLAN_STATE_DWORDS
-+
#define ST_VEL_PLAN_VAR_DWORDS
-+
#define ST_VEL_PLAN_ACT_DWORDS
-+
-+

Definition at line 233 of file proj_lab06d.c.

-+ -+
-+
-+

Enumeration Type Documentation

-+ -+
-+
-+ -+ -+ -+ -+
enum GARAGE_Acts_e
-+
-+ -+ -+ -+ -+ -+ -+
Enumerator
GARAGE_ClearButtonDown  -+
GARAGE_ClearButtonUp  -+
GARAGE_ClearDownSensor  -+
GARAGE_ClearUpSensor  -+
NUM_GARAGE_ACTS  -+
-+ -+

Definition at line 211 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GARAGE_Cond_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
GARAGE_DoorDown  -+
GARAGE_DoorUp  -+
GARAGE_ButtonPressed  -+
NUM_GARAGE_CONDS  -+
-+ -+

Definition at line 202 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GARAGE_State_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
GARAGE_Idle  -+
GARAGE_Down  -+
GARAGE_Up  -+
NUM_GARAGE_STATES  -+
-+ -+

Definition at line 184 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GARAGE_Trans_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
GARAGE_IdleToDown  -+
GARAGE_IdleToUp  -+
GARAGE_DownToUp  -+
GARAGE_UpToDown  -+
GARAGE_DownToIdle  -+
GARAGE_UpToIdle  -+
NUM_GARAGE_TRANS  -+
-+ -+

Definition at line 221 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GARAGE_Vars_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
GARAGE_DownSensor  -+
GARAGE_UpSensor  -+
GARAGE_Button  -+
NUM_GARAGE_VARS  -+
-+ -+

Definition at line 193 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GROCERY_Cond_e
-+
-+ -+ -+ -+ -+ -+ -+
Enumerator
GROCERY_SwitchOn  -+
GROCERY_SwitchOff  -+
GROCERY_ProxOpen  -+
GROCERY_ProxBlocked  -+
NUM_GROCERY_CONDS  -+
-+ -+

Definition at line 165 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GROCERY_State_e
-+
-+ -+ -+ -+ -+
Enumerator
GROCERY_Idle  -+
GROCERY_Convey  -+
NUM_GROCERY_STATES  -+
-+ -+

Definition at line 149 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GROCERY_Trans_e
-+
-+ -+ -+ -+ -+
Enumerator
GROCERY_IdleToConvey  -+
GROCERY_ConveyToIdle  -+
NUM_GROCERY_TRANS  -+
-+ -+

Definition at line 175 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum GROCERY_Vars_e
-+
-+ -+ -+ -+ -+
Enumerator
GROCERY_OnOff  -+
GROCERY_ProxSensor  -+
NUM_GROCERY_VARS  -+
-+ -+

Definition at line 157 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum PLAN_SELECT_e
-+
-+ -+ -+ -+ -+
Enumerator
TEST_PATTERN  -+
GROCERY_CONVEYOR  -+
GARAGE_DOOR  -+
-+ -+

Definition at line 68 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum TEST_State_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
TEST_0  -+
TEST_4000  -+
TEST_N4000  -+
TEST_2000  -+
TEST_N2000  -+
TEST_1000  -+
TEST_N1000  -+
TEST_500  -+
TEST_N500  -+
TEST_250  -+
TEST_N250  -+
NUM_TEST_STATES  -+
-+ -+

Definition at line 114 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum TEST_Trans_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
TEST_0to4000  -+
TEST_4000toN4000  -+
TEST_N4000to2000  -+
TEST_2000toN2000  -+
TEST_N2000to1000  -+
TEST_1000toN1000  -+
TEST_N1000to500  -+
TEST_500toN500  -+
TEST_N500to250  -+
TEST_250toN250  -+
TEST_N250to0  -+
NUM_TEST_TRANS  -+
-+ -+

Definition at line 131 of file proj_lab06d.c.

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 286 of file proj_lab06d.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, GARAGE_DOOR, gConfiguredPlan, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, GROCERY_CONVEYOR, gSelectedPlan, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_runVelPlan(), ST_setupVelCtl(), ST_setupVelMove(), ST_setupVelPlan(), ST_setupVelPlan_GarageDoor(), ST_setupVelPlan_GroceryConveyor(), ST_setupVelPlan_TestPattern(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), STVELMOVE_setVelocityEnd(), STVELMOVE_setVelocityStart(), STVELPLAN_getStatus(), TEST_PATTERN, updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, _ST_Vars_t::VelCtlOutputMin_A, _ST_Obj::velMoveHandle, and _ST_Obj::velPlanHandle.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
interrupt void mainISR (void )
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupVelPlan (ST_Handle handle)
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupVelPlan_TestPattern (ST_Handle sthandle)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 716 of file proj_lab06d.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_get_pu_to_krpm_sf(), EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getSpeed_krpm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpeedTraj_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_PU_PER_KRPM, STVELCTL_getErrorID(), STVELCTL_getFriction(), STVELCTL_getInertia(), STVELCTL_getStatus(), STVELCTL_getTorqueReference(), STVELMOVE_getErrorID(), STVELMOVE_getProfileTime_tick(), STVELMOVE_getStatus(), STVELMOVE_getVelocityReference(), STVELPLAN_getCfgError(), STVELPLAN_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, _MOTOR_Vars_t_::VdcBus_kV, _ST_Vars_t::VelCtlErrorID, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlStatus, _ST_Vars_t::VelMoveErrorID, _ST_Obj::velMoveHandle, _ST_Vars_t::VelMoveStatus, _ST_Vars_t::VelMoveTime_ticks, _ST_Vars_t::VelPlanCfgErrorCode, _ST_Vars_t::VelPlanCfgErrorIdx, _ST_Vars_t::VelPlanErrorID, _ST_Obj::velPlanHandle, and _ST_Vars_t::VelPlanStatus.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 798 of file proj_lab06d.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 97 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 82 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 80 of file proj_lab06d.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 90 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
PLAN_SELECT_e gConfiguredPlan = TEST_PATTERN
-+
-+ -+

Definition at line 110 of file proj_lab06d.c.

-+ -+

Referenced by main(), and ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 78 of file proj_lab06d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 274 of file proj_lab06d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 272 of file proj_lab06d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gGarageDoorButton = 0
-+
-+ -+

Definition at line 255 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gGarageDoorDown = 1
-+
-+ -+

Definition at line 253 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gGarageDoorUp = 0
-+
-+ -+

Definition at line 254 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
GARAGE_State_e gGarageState = GARAGE_Idle
-+
-+ -+

Definition at line 252 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gGroceryConveyorOnOff = 0
-+
-+ -+

Definition at line 248 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gGroceryConveyorProxSensor = 0
-+
-+ -+

Definition at line 249 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
GROCERY_State_e gGroceryState = GROCERY_Idle
-+
-+ -+

Definition at line 247 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 257 of file proj_lab06d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 92 of file proj_lab06d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 259 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 88 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
PLAN_SELECT_e gSelectedPlan = TEST_PATTERN
-+
-+ -+

Definition at line 107 of file proj_lab06d.c.

-+ -+

Referenced by main(), and ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
TEST_State_e gTestState = TEST_0
-+
-+ -+

Definition at line 244 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 278 of file proj_lab06d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 276 of file proj_lab06d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 86 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_PlanButton_e gVelPlanRunFlag = ST_PLAN_STOP
-+
-+ -+

Definition at line 104 of file proj_lab06d.c.

-+ -+

Referenced by ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 84 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 100 of file proj_lab06d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 101 of file proj_lab06d.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint32_t stVelPlanCfgArray[ST_VELPLAN_CFG_ARRAY_DWORDS]
-+
-+ -+

Definition at line 241 of file proj_lab06d.c.

-+ -+

Referenced by ST_setupVelPlan().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b06d___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.401948300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Design a motion sequence

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b.html 2017-06-08 10:42:12.401948300 +0200 -*************** -*** 0 **** ---- 1,691 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB10b -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB10b
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runVelMove (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Move. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
SVGENCURRENT_Obj svgencurrent
 
SVGENCURRENT_Handle svgencurrentHandle
 
int16_t gCmpOffset = (int16_t)(1.0 * USER_SYSTEM_FREQ_MHz)
 
MATH_vec3 gIavg = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
 
uint16_t gIavg_shift = 1
 
FW_Obj fw
 
FW_Handle fwHandle
 
_iq Iq_Max_pu
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab10b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 139 of file proj_lab10b.c.

-+ -+

References _IQ, _IQmpy, _IQsqrt, CTRL_getFlag_enableUserMotorParams(), CTRL_getId_ref_pu(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setMaxVsMag_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_setSpdMax(), CTRL_updateState(), _MOTOR_Vars_t_::CtrlVersion, EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableFieldWeakening, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, FW_clearCounter(), FW_DEC_DELTA, FW_INC_DELTA, FW_init(), FW_NUM_ISR_TICKS_PER_CTRL_TICK, FW_setDeltas(), FW_setFlag_enableFw(), FW_setMinMax(), FW_setNumIsrTicksPerFwTick(), FW_setOutput(), gCounter_updateGlobals, gMaxCurrentSlope, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MATH_TWO_OVER_THREE, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _MOTOR_Vars_t_::OverModulation, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupVelCtl(), ST_setupVelMove(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), STVELMOVE_setVelocityEnd(), STVELMOVE_setVelocityStart(), SVGENCURRENT_init(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_MAX_NEGATIVE_ID_REF_CURRENT_A, USER_MOTOR_MAX_CURRENT, USER_setParams(), USER_softwareUpdate1p6(), USER_SYSTEM_FREQ_MHz, _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, _ST_Vars_t::VelCtlOutputMin_A, and _ST_Obj::velMoveHandle.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 655 of file proj_lab10b.c.

-+ -+

References _IQ, _IQmpy, _IQsqrt, CTRL_getId_in_pu(), CTRL_getIq_in_pu(), CTRL_getState(), CTRL_getVd_out_pu(), CTRL_getVq_out_pu(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_get_pu_to_krpm_sf(), EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getSpeed_krpm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, _MOTOR_Vars_t_::Id_A, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::Iq_A, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Is_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpeedTraj_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_PU_PER_KRPM, STVELCTL_getErrorID(), STVELCTL_getFriction(), STVELCTL_getInertia(), STVELCTL_getStatus(), STVELCTL_getTorqueReference(), STVELMOVE_getErrorID(), STVELMOVE_getProfileTime_tick(), STVELMOVE_getStatus(), STVELMOVE_getVelocityReference(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, _MOTOR_Vars_t_::Vd, _MOTOR_Vars_t_::VdcBus_kV, _ST_Vars_t::VelCtlErrorID, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlStatus, _ST_Vars_t::VelMoveErrorID, _ST_Obj::velMoveHandle, _ST_Vars_t::VelMoveStatus, _ST_Vars_t::VelMoveTime_ticks, _MOTOR_Vars_t_::Vq, and _MOTOR_Vars_t_::Vs.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 741 of file proj_lab10b.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab10b.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
FW_Obj fw
-+
-+ -+

Definition at line 116 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
FW_Handle fwHandle
-+
-+ -+

Definition at line 117 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
int16_t gCmpOffset = (int16_t)(1.0 * USER_SYSTEM_FREQ_MHz)
-+
-+ -+

Definition at line 110 of file proj_lab10b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab10b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 130 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 128 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
MATH_vec3 gIavg = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 112 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gIavg_shift = 1
-+
-+ -+

Definition at line 113 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 96 of file proj_lab10b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab10b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 98 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 134 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 132 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq Iq_Max_pu
-+
-+ -+

Definition at line 119 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 93 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 94 of file proj_lab10b.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SVGENCURRENT_Obj svgencurrent
-+
-+ -+

Definition at line 106 of file proj_lab10b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SVGENCURRENT_Handle svgencurrentHandle
-+
-+ -+

Definition at line 107 of file proj_lab10b.c.

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b10b___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.417548300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Experimentation with Space Vector Over-Modulation and Field Weakening using InstaSPIN-MOTION

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a.html 2017-06-08 10:42:12.417548300 +0200 -*************** -*** 0 **** ---- 1,639 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB12a -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB12a
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runVelId (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Identify. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab12a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 128 of file proj_lab12a.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupVelId(), ST_SPEED_KRPM_PER_PU, stHandle, STVELID_getGoalSpeed(), STVELID_getTorqueRampTime_sec(), STVELID_setSensorlessFeedback(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelIdGoalSpeed_krpm, _ST_Obj::velIdHandle, and _ST_Vars_t::VelIdTorqueRampTime_sec.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+ -+

Runs SpinTAC Positon Convert.

-+ -+

Definition at line 615 of file proj_lab12a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 521 of file proj_lab12a.c.

-+ -+

References _IQ, _IQmpy, CTRL_getSpd_int_ref_pu(), CTRL_getSpd_out_pu(), CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_get_pu_to_krpm_sf(), EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getSpeed_krpm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _ST_Vars_t::PosConvErrorID, _ST_Obj::posConvHandle, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpeedQEP_krpm, _MOTOR_Vars_t_::SpeedTraj_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_KRPM_PER_PU, ST_SPEED_PU_PER_KRPM, STPOSCONV_getErrorID(), STPOSCONV_getVelocityFiltered(), STVELID_getErrorID(), STVELID_getFrictionEstimate(), STVELID_getInertiaEstimate(), STVELID_getStatus(), STVELID_getTorqueReference(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, _MOTOR_Vars_t_::VdcBus_kV, _ST_Vars_t::VelIdErrorID, _ST_Obj::velIdHandle, _ST_Vars_t::VelIdRun, and _ST_Vars_t::VelIdStatus.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 596 of file proj_lab12a.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 94 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 93 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab12a.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab12a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 119 of file proj_lab12a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 117 of file proj_lab12a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 102 of file proj_lab12a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab12a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 104 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 123 of file proj_lab12a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 121 of file proj_lab12a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 97 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 96 of file proj_lab12a.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 99 of file proj_lab12a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 100 of file proj_lab12a.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12a___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.433148300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

InstaSPIN-MOTION Inertia Identification using a quadrature encoder for feedback

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b.html 2017-06-08 10:42:12.448748300 +0200 -*************** -*** 0 **** ---- 1,641 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB12b -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB12b
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runVelCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Velocity Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab12b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 128 of file proj_lab12b.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpeedRef_krpm, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupVelCtl(), stHandle, STVELCTL_getBandwidth_radps(), STVELCTL_getOutputMaximum(), STVELCTL_getOutputMinimum(), STVELCTL_setBandwidth_radps(), STVELCTL_setEnable(), STVELCTL_setOutputMaximums(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, _MATH_vec3_::value, _ST_Vars_t::VelCtlBw_radps, _ST_Obj::velCtlHandle, _ST_Vars_t::VelCtlOutputMax_A, and _ST_Vars_t::VelCtlOutputMin_A.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 608 of file proj_lab12b.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 94 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 93 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab12b.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab12b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 119 of file proj_lab12b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 117 of file proj_lab12b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 102 of file proj_lab12b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab12b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 104 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 123 of file proj_lab12b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 121 of file proj_lab12b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 97 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 96 of file proj_lab12b.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 99 of file proj_lab12b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 100 of file proj_lab12b.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b12b___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.448748300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

SpinTAC Velocity Controller using a quadrature encoder for feedback

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a.html 2017-06-08 10:42:12.464348300 +0200 -*************** -*** 0 **** ---- 1,639 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB13A -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB13A
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runPosCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Control. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab13a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 128 of file proj_lab13a.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _ST_Vars_t::PosCtlBw_radps, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlOutputMax_A, _ST_Vars_t::PosCtlOutputMin_A, _ST_Obj::posMoveHandle, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupPosCtl(), stHandle, STPOSCTL_getBandwidth_radps(), STPOSCTL_getOutputMaximum(), STPOSCTL_getOutputMinimum(), STPOSCTL_setBandwidth_radps(), STPOSCTL_setEnable(), STPOSCTL_setOutputMaximums(), STPOSMOVE_getVelocityReference(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, and _MATH_vec3_::value.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosCtl (ST_Handle handle,
CTRL_Handle ctrlHandle 
)
-+
-+ -+

Runs SpinTAC Positon Control.

-+ -+

Definition at line 646 of file proj_lab13a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 604 of file proj_lab13a.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 94 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 93 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab13a.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab13a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 119 of file proj_lab13a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 117 of file proj_lab13a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 102 of file proj_lab13a.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab13a.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 104 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 123 of file proj_lab13a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 121 of file proj_lab13a.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 97 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 96 of file proj_lab13a.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 99 of file proj_lab13a.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 100 of file proj_lab13a.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_a___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.479948300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Tuning the InstaSPIN-MOTION Position Controller

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b.html 2017-06-08 10:42:12.479948300 +0200 -*************** -*** 0 **** ---- 1,666 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB13B -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB13B
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runPosCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Control. More...
 
void ST_runPosMove (ST_Handle handle)
 Runs SpinTAC Positon Move. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab13b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 128 of file proj_lab13b.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlBw_radps, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlOutputMax_A, _ST_Vars_t::PosCtlOutputMin_A, _ST_Obj::posMoveHandle, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupPosCtl(), ST_setupPosMove(), stHandle, STPOSCONV_getPosition_mrev(), STPOSCTL_getBandwidth_radps(), STPOSCTL_getOutputMaximum(), STPOSCTL_getOutputMinimum(), STPOSCTL_setBandwidth_radps(), STPOSCTL_setEnable(), STPOSCTL_setOutputMaximums(), STPOSMOVE_getVelocityReference(), STPOSMOVE_setPositionStart_mrev(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, and _MATH_vec3_::value.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosMove (ST_Handle handle)
-+
-+ -+

Runs SpinTAC Positon Move.

-+ -+

Definition at line 681 of file proj_lab13b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 543 of file proj_lab13b.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _ST_Vars_t::PosConvErrorID, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlErrorID, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlStatus, _MOTOR_Vars_t_::PositionError_MRev, _ST_Vars_t::PosMoveErrorID, _ST_Obj::posMoveHandle, _ST_Vars_t::PosMoveStatus, _ST_Vars_t::PosMoveTime_mticks, _ST_Vars_t::PosMoveTime_ticks, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_KRPM_PER_PU, ST_SPEED_PU_PER_KRPM, STPOSCONV_getErrorID(), STPOSCONV_getVelocityFiltered(), STPOSCTL_getErrorID(), STPOSCTL_getFriction(), STPOSCTL_getInertia(), STPOSCTL_getPositionError_mrev(), STPOSCTL_getStatus(), STPOSCTL_getTorqueReference(), STPOSMOVE_getErrorID(), STPOSMOVE_getProfileTime_tick(), STPOSMOVE_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, and _MOTOR_Vars_t_::VdcBus_kV.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 621 of file proj_lab13b.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 94 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 93 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab13b.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab13b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 119 of file proj_lab13b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 117 of file proj_lab13b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 102 of file proj_lab13b.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab13b.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 104 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 123 of file proj_lab13b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 121 of file proj_lab13b.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 97 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 96 of file proj_lab13b.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 99 of file proj_lab13b.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 100 of file proj_lab13b.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_b___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.495548300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Smooth Position Transitions with SpinTAC Move

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c.html 2017-06-08 10:42:12.495548300 +0200 -*************** -*** 0 **** ---- 1,858 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB13C -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Enumerations | -+ Functions | -+ Variables
-+
-+
PROJ_LAB13C
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
#define ST_POSPLAN_CFG_ARRAY_DWORDS
 
-+ -+ -+ -+ -+ -+

-+ Enumerations

enum  PLAN_State_e { STATE_A = 0, -+ STATE_B, -+ STATE_C, -+ NUM_PLAN_STATES -+ }
 
enum  PLAN_Trans_e { TRAN_AtoB = 0, -+ TRAN_BtoC, -+ TRAN_CtoA, -+ NUM_PLAN_TRANS -+ }
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_setupPosPlan (ST_Handle sthandle)
 Setups SpinTAC Positon Plan. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runPosCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Control. More...
 
void ST_runPosMove (ST_Handle handle)
 Runs SpinTAC Positon Move. More...
 
void ST_runPosPlan (ST_Handle handle)
 Runs SpinTAC Positon Plan. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
ST_PlanButton_e gPosPlanRunFlag = ST_PLAN_STOP
 
uint32_t stPosPlanCfgArray [ST_POSPLAN_CFG_ARRAY_DWORDS]
 
PLAN_State_e gState = STATE_A
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab13c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_POSPLAN_CFG_ARRAY_DWORDS
-+
-+ Value:
-+
(ST_POS_PLAN_STATE_DWORDS * NUM_PLAN_STATES))
-+
#define ST_POS_PLAN_TRAN_DWORDS
-+ -+ -+
-+

Definition at line 125 of file proj_lab13c.c.

-+ -+
-+
-+

Enumeration Type Documentation

-+ -+
-+
-+ -+ -+ -+ -+
enum PLAN_State_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
STATE_A  -+
STATE_B  -+
STATE_C  -+
NUM_PLAN_STATES  -+
-+ -+

Definition at line 106 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum PLAN_Trans_e
-+
-+ -+ -+ -+ -+ -+
Enumerator
TRAN_AtoB  -+
TRAN_BtoC  -+
TRAN_CtoA  -+
NUM_PLAN_TRANS  -+
-+ -+

Definition at line 115 of file proj_lab13c.c.

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 159 of file proj_lab13c.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlBw_radps, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlOutputMax_A, _ST_Vars_t::PosCtlOutputMin_A, _ST_Obj::posMoveHandle, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupPosCtl(), ST_setupPosMove(), ST_setupPosPlan(), stHandle, STPOSCONV_getPosition_mrev(), STPOSCTL_getBandwidth_radps(), STPOSCTL_getOutputMaximum(), STPOSCTL_getOutputMinimum(), STPOSCTL_setBandwidth_radps(), STPOSCTL_setEnable(), STPOSCTL_setOutputMaximums(), STPOSMOVE_getVelocityReference(), STPOSMOVE_setPositionStart_mrev(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, and _MATH_vec3_::value.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosPlan (ST_Handle handle)
-+
-+ -+

Runs SpinTAC Positon Plan.

-+ -+

Definition at line 782 of file proj_lab13c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupPosPlan (ST_Handle sthandle)
-+
-+ -+

Setups SpinTAC Positon Plan.

-+ -+

Definition at line 684 of file proj_lab13c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 578 of file proj_lab13c.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _ST_Vars_t::PosConvErrorID, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlErrorID, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlStatus, _MOTOR_Vars_t_::PositionError_MRev, _ST_Vars_t::PosMoveErrorID, _ST_Obj::posMoveHandle, _ST_Vars_t::PosMoveStatus, _ST_Vars_t::PosMoveTime_mticks, _ST_Vars_t::PosMoveTime_ticks, _ST_Vars_t::PosPlanCfgErrorCode, _ST_Vars_t::PosPlanCfgErrorIdx, _ST_Vars_t::PosPlanErrorID, _ST_Obj::posPlanHandle, _ST_Vars_t::PosPlanStatus, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_KRPM_PER_PU, ST_SPEED_PU_PER_KRPM, STPOSCONV_getErrorID(), STPOSCONV_getVelocityFiltered(), STPOSCTL_getErrorID(), STPOSCTL_getFriction(), STPOSCTL_getInertia(), STPOSCTL_getPositionError_mrev(), STPOSCTL_getStatus(), STPOSCTL_getTorqueReference(), STPOSMOVE_getErrorID(), STPOSMOVE_getProfileTime_tick(), STPOSMOVE_getStatus(), STPOSPLAN_getCfgError(), STPOSPLAN_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, and _MOTOR_Vars_t_::VdcBus_kV.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 665 of file proj_lab13c.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 94 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 93 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab13c.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab13c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 150 of file proj_lab13c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 148 of file proj_lab13c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 133 of file proj_lab13c.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab13c.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 135 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_PlanButton_e gPosPlanRunFlag = ST_PLAN_STOP
-+
-+ -+

Definition at line 103 of file proj_lab13c.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
PLAN_State_e gState = STATE_A
-+
-+ -+

Definition at line 131 of file proj_lab13c.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 154 of file proj_lab13c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 152 of file proj_lab13c.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 97 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 96 of file proj_lab13c.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 99 of file proj_lab13c.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 100 of file proj_lab13c.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint32_t stPosPlanCfgArray[ST_POSPLAN_CFG_ARRAY_DWORDS]
-+
-+ -+

Definition at line 129 of file proj_lab13c.c.

-+ -+

Referenced by ST_setupPosPlan().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_c___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.511148300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Motion Sequence Example with SpinTAC Plan

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d.html 2017-06-08 10:42:12.511148300 +0200 -*************** -*** 0 **** ---- 1,1099 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB13D -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Enumerations | -+ Functions | -+ Variables
-+
-+
PROJ_LAB13D
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+ -+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
#define VEND_INITIAL_INVENTORY   10
 
#define ST_POSPLAN_CFG_ARRAY_DWORDS
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Enumerations

enum  VEND_State_e {
-+   VEND_INIT = 0, -+ VEND_ITEM0, -+ VEND_ITEM1, -+ VEND_ITEM2, -+
-+   VEND_ITEM3, -+ NUM_VEND_STATES -+
-+ }
 
enum  VEND_Trans_e {
-+   VEND_INITto2 = 0, -+ VEND_0toINIT, -+ VEND_0to1, -+ VEND_1to2, -+
-+   VEND_2to3, -+ VEND_3to0, -+ NUM_VEND_TRANS -+
-+ }
 
enum  VEND_Var_e {
-+   VEND_Fwd = 0, -+ VEND_Item0Inv, -+ VEND_Item1Inv, -+ VEND_Item2Inv, -+
-+   VEND_Item3Inv, -+ VEND_TotalInv, -+ NUM_VEND_VARS -+
-+ }
 
enum  VEND_Cond_e {
-+   VEND_FwdPressed = 0, -+ VEND_Item0InvEmpty, -+ VEND_Item1InvEmpty, -+ VEND_Item2InvEmpty, -+
-+   VEND_Item3InvEmpty, -+ VEND_InvEmpty, -+ NUM_VEND_CONDS -+
-+ }
 
enum  VEND_Acts_e {
-+   VEND_ClearFwdItem0 = 0, -+ VEND_ClearFwdItem1, -+ VEND_ClearFwdItem2, -+ VEND_ClearFwdItem3, -+
-+   NUM_VEND_ACTS -+
-+ }
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_setupPosPlan (ST_Handle handle)
 Setups SpinTAC Positon Plan. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runPosCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Control. More...
 
void ST_runPosMove (ST_Handle handle)
 Runs SpinTAC Positon Move. More...
 
void ST_runPosPlan (ST_Handle handle)
 Runs SpinTAC Positon Plan. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
ST_PlanButton_e gPosPlanRunFlag = ST_PLAN_STOP
 
uint32_t stPosPlanCfgArray [ST_POSPLAN_CFG_ARRAY_DWORDS]
 
VEND_State_e gVendState = VEND_INIT
 
_iq gVendFwdButton = 0
 
_iq gVendSelectButton = 0
 
uint16_t gVendInventory [4] = {VEND_INITIAL_INVENTORY, VEND_INITIAL_INVENTORY, VEND_INITIAL_INVENTORY, VEND_INITIAL_INVENTORY}
 
VEND_State_e gVendAvailableItem = VEND_ITEM0
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab13d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_POSPLAN_CFG_ARRAY_DWORDS
-+
-+ Value:
-+
(ST_POS_PLAN_COND_DWORDS * NUM_VEND_CONDS) + \
-+ -+
(ST_POS_PLAN_TRAN_DWORDS * NUM_VEND_TRANS) + \
-+ -+
#define ST_POS_PLAN_STATE_DWORDS
-+ -+ -+ -+ -+
#define ST_POS_PLAN_VAR_DWORDS
-+ -+
#define ST_POS_PLAN_ACT_DWORDS
-+
-+

Definition at line 166 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define VEND_INITIAL_INVENTORY   10
-+
-+ -+

Definition at line 67 of file proj_lab13d.c.

-+ -+

Referenced by ST_setupPosPlan().

-+ -+
-+
-+

Enumeration Type Documentation

-+ -+
-+
-+ -+ -+ -+ -+
enum VEND_Acts_e
-+
-+ -+ -+ -+ -+ -+ -+
Enumerator
VEND_ClearFwdItem0  -+
VEND_ClearFwdItem1  -+
VEND_ClearFwdItem2  -+
VEND_ClearFwdItem3  -+
NUM_VEND_ACTS  -+
-+ -+

Definition at line 155 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum VEND_Cond_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
VEND_FwdPressed  -+
VEND_Item0InvEmpty  -+
VEND_Item1InvEmpty  -+
VEND_Item2InvEmpty  -+
VEND_Item3InvEmpty  -+
VEND_InvEmpty  -+
NUM_VEND_CONDS  -+
-+ -+

Definition at line 143 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum VEND_State_e
-+
-+ -+ -+ -+ -+ -+ -+ -+
Enumerator
VEND_INIT  -+
VEND_ITEM0  -+
VEND_ITEM1  -+
VEND_ITEM2  -+
VEND_ITEM3  -+
NUM_VEND_STATES  -+
-+ -+

Definition at line 108 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum VEND_Trans_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
VEND_INITto2  -+
VEND_0toINIT  -+
VEND_0to1  -+
VEND_1to2  -+
VEND_2to3  -+
VEND_3to0  -+
NUM_VEND_TRANS  -+
-+ -+

Definition at line 119 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum VEND_Var_e
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
Enumerator
VEND_Fwd  -+
VEND_Item0Inv  -+
VEND_Item1Inv  -+
VEND_Item2Inv  -+
VEND_Item3Inv  -+
VEND_TotalInv  -+
NUM_VEND_VARS  -+
-+ -+

Definition at line 131 of file proj_lab13d.c.

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 210 of file proj_lab13d.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlBw_radps, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlOutputMax_A, _ST_Vars_t::PosCtlOutputMin_A, _ST_Obj::posMoveHandle, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupPosCtl(), ST_setupPosMove(), ST_setupPosPlan(), stHandle, STPOSCONV_getPosition_mrev(), STPOSCTL_getBandwidth_radps(), STPOSCTL_getOutputMaximum(), STPOSCTL_getOutputMinimum(), STPOSCTL_setBandwidth_radps(), STPOSCTL_setEnable(), STPOSCTL_setOutputMaximums(), STPOSMOVE_getVelocityReference(), STPOSMOVE_setPositionStart_mrev(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, and _MATH_vec3_::value.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 628 of file proj_lab13d.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _ST_Vars_t::PosConvErrorID, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlErrorID, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlStatus, _MOTOR_Vars_t_::PositionError_MRev, _ST_Vars_t::PosMoveErrorID, _ST_Obj::posMoveHandle, _ST_Vars_t::PosMoveStatus, _ST_Vars_t::PosMoveTime_mticks, _ST_Vars_t::PosMoveTime_ticks, _ST_Vars_t::PosPlanCfgErrorCode, _ST_Vars_t::PosPlanCfgErrorIdx, _ST_Vars_t::PosPlanErrorID, _ST_Obj::posPlanHandle, _ST_Vars_t::PosPlanStatus, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_KRPM_PER_PU, ST_SPEED_PU_PER_KRPM, STPOSCONV_getErrorID(), STPOSCONV_getVelocityFiltered(), STPOSCTL_getErrorID(), STPOSCTL_getFriction(), STPOSCTL_getInertia(), STPOSCTL_getPositionError_mrev(), STPOSCTL_getStatus(), STPOSCTL_getTorqueReference(), STPOSMOVE_getErrorID(), STPOSMOVE_getProfileTime_tick(), STPOSMOVE_getStatus(), STPOSPLAN_getCfgError(), STPOSPLAN_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, and _MOTOR_Vars_t_::VdcBus_kV.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 715 of file proj_lab13d.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 92 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 77 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 96 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 95 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 75 of file proj_lab13d.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 85 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 73 of file proj_lab13d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 201 of file proj_lab13d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 199 of file proj_lab13d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 184 of file proj_lab13d.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 87 of file proj_lab13d.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 186 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_PlanButton_e gPosPlanRunFlag = ST_PLAN_STOP
-+
-+ -+

Definition at line 105 of file proj_lab13d.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 83 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 205 of file proj_lab13d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 203 of file proj_lab13d.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 81 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
VEND_State_e gVendAvailableItem = VEND_ITEM0
-+
-+ -+

Definition at line 182 of file proj_lab13d.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gVendFwdButton = 0
-+
-+ -+

Definition at line 179 of file proj_lab13d.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+

Definition at line 181 of file proj_lab13d.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gVendSelectButton = 0
-+
-+ -+

Definition at line 180 of file proj_lab13d.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
VEND_State_e gVendState = VEND_INIT
-+
-+ -+

Definition at line 176 of file proj_lab13d.c.

-+ -+

Referenced by ST_runPosPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 79 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 99 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 98 of file proj_lab13d.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 101 of file proj_lab13d.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 102 of file proj_lab13d.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint32_t stPosPlanCfgArray[ST_POSPLAN_CFG_ARRAY_DWORDS]
-+
-+ -+

Definition at line 173 of file proj_lab13d.c.

-+ -+

Referenced by ST_setupPosPlan().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_d___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.526748300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Motion Sequence Real World Example: Vending Machine

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e.html 2017-06-08 10:42:12.542348300 +0200 -*************** -*** 0 **** ---- 1,668 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: PROJ_LAB13E -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Modules | -+ Macros | -+ Functions | -+ Variables
-+
-+
PROJ_LAB13E
-+
-+
-+ -+ -+ -+ -+

-+ Modules

 Project Overview
 
-+ -+ -+ -+

-+ Macros

#define LED_BLINK_FREQ_Hz   5
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void main (void)
 
interrupt void mainISR (void)
 The main interrupt service (ISR) routine. More...
 
void updateGlobalVariables_motor (CTRL_Handle handle, ST_Handle sthandle)
 Updates the global motor variables. More...
 
void updateKpKiGains (CTRL_Handle handle)
 Updates Kp and Ki gains in the controller object. More...
 
void ST_runPosConv (ST_Handle handle, ENC_Handle encHandle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runPosCtl (ST_Handle handle, CTRL_Handle ctrlHandle)
 Runs SpinTAC Positon Control. More...
 
void ST_runPosMove (ST_Handle handle)
 Runs SpinTAC Positon Move. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Variables

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)
 
CTRL_Obj ctrl
 
ENC_Handle encHandle
 
ENC_Obj enc
 
SLIP_Handle slipHandle
 
SLIP_Obj slip
 
ST_Obj st_obj
 
ST_Handle stHandle
 
uint16_t gLEDcnt = 0
 
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
 
_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
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define LED_BLINK_FREQ_Hz   5
-+
-+ -+

Definition at line 65 of file proj_lab13e.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void main (void )
-+
-+ -+

Definition at line 128 of file proj_lab13e.c.

-+ -+

References _IQ, _IQmpy, CTRL_getFlag_enableUserMotorParams(), CTRL_getKi(), CTRL_getKp(), CTRL_getState(), CTRL_getVersion(), CTRL_initCtrl(), CTRL_isError(), CTRL_setFlag_enableCtrl(), CTRL_setFlag_enableDcBusComp(), CTRL_setFlag_enableOffset(), CTRL_setFlag_enablePowerWarp(), CTRL_setFlag_enableSpeedCtrl(), CTRL_setFlag_enableUserMotorParams(), CTRL_setMaxAccel_pu(), CTRL_setParams(), CTRL_setSpd_ref_krpm(), CTRL_updateState(), _USER_Params_::ctrlPeriod_sec, _MOTOR_Vars_t_::CtrlVersion, ENC_init(), ENC_setup(), EST_getMaxCurrentSlope_pu(), EST_getState(), EST_isMotorIdentified(), EST_setFlag_enableForceAngle(), EST_setFlag_enableRsRecalc(), EST_setMaxCurrentSlope_pu(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::Flag_enableForceAngle, _MOTOR_Vars_t_::Flag_enableOffsetcalc, _MOTOR_Vars_t_::Flag_enablePowerWarp, _MOTOR_Vars_t_::Flag_enableRsRecalc, _MOTOR_Vars_t_::Flag_enableSys, _MOTOR_Vars_t_::Flag_enableUserParams, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Flag_Run_Identify, gCounter_updateGlobals, gFlux_pu_to_VpHz_sf, gFlux_pu_to_Wb_sf, gMaxCurrentSlope, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, hal, HAL_disablePwm(), HAL_enableAdcInts(), HAL_enableDebugInt(), HAL_enableDrv(), HAL_enableGlobalInts(), HAL_enablePwm(), HAL_getBias(), HAL_init(), HAL_initIntVectorTable(), HAL_readDrvData(), HAL_setBias(), HAL_setParams(), HAL_setupDrvSpi(), HAL_setupFaults(), HAL_updateAdcBias(), HAL_writeDrvData(), I_A_offset, I_B_offset, _MOTOR_Vars_t_::I_bias, I_C_offset, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Kp_Idq, MAX_ACCEL_KRPMPS_SF, _MOTOR_Vars_t_::MaxAccel_krpmps, _MOTOR_Vars_t_::MaxVel_krpm, memCopy(), _CTRL_Version_::minor, NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlBw_radps, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlOutputMax_A, _ST_Vars_t::PosCtlOutputMin_A, _ST_Obj::posMoveHandle, SLIP_init(), SLIP_setup(), slipHandle, _MOTOR_Vars_t_::SpinTAC, ST_init(), ST_setupPosConv(), ST_setupPosCtl(), ST_setupPosMove(), stHandle, STPOSCONV_getPosition_mrev(), STPOSCTL_getBandwidth_radps(), STPOSCTL_getOutputMaximum(), STPOSCTL_getOutputMinimum(), STPOSCTL_setBandwidth_radps(), STPOSCTL_setEnable(), STPOSCTL_setOutputMaximums(), STPOSMOVE_getVelocityReference(), STPOSMOVE_setPositionStart_mrev(), updateGlobalVariables_motor(), updateKpKiGains(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_getErrorCode(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_ISR_FREQ_Hz, USER_MOTOR_ENCODER_LINES, USER_MOTOR_NUM_POLE_PAIRS, USER_setParams(), USER_softwareUpdate1p6(), _MOTOR_Vars_t_::UserErrorCode, V_A_offset, V_B_offset, _MOTOR_Vars_t_::V_bias, V_C_offset, and _MATH_vec3_::value.

-+ -+
-+
-+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle handle,
ENC_Handle encHandle,
CTRL_Handle ctrlHandle 
)
-+
-+
-+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void updateGlobalVariables_motor (CTRL_Handle handle,
ST_Handle sthandle 
)
-+
-+ -+

Updates the global motor variables.

-+ -+

Definition at line 545 of file proj_lab13e.c.

-+ -+

References _IQ, _IQmpy, CTRL_getState(), _MOTOR_Vars_t_::CtrlState, _HAL_AdcData_t_::dcBus, EST_getFlux_VpHz(), EST_getIdRated(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRr_Ohm(), EST_getRs_Ohm(), EST_getState(), _CTRL_Obj_::estHandle, _MOTOR_Vars_t_::EstState, _MOTOR_Vars_t_::Flux_VpHz, _MOTOR_Vars_t_::Flux_Wb, _ST_Vars_t::FrictionEstimate_Aperkrpm, gFlux_pu_to_Wb_sf, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf, _ST_Vars_t::InertiaEstimate_Aperkrpm, _MOTOR_Vars_t_::IqRef_A, _MOTOR_Vars_t_::Lsd_H, _MOTOR_Vars_t_::Lsq_H, _MOTOR_Vars_t_::MagnCurr_A, _ST_Vars_t::PosConvErrorID, _ST_Obj::posConvHandle, _ST_Vars_t::PosCtlErrorID, _ST_Obj::posCtlHandle, _ST_Vars_t::PosCtlStatus, _MOTOR_Vars_t_::PositionError_MRev, _ST_Vars_t::PosMoveErrorID, _ST_Obj::posMoveHandle, _ST_Vars_t::PosMoveStatus, _ST_Vars_t::PosMoveTime_mticks, _ST_Vars_t::PosMoveTime_ticks, _MOTOR_Vars_t_::Rr_Ohm, _MOTOR_Vars_t_::Rs_Ohm, _MOTOR_Vars_t_::Speed_krpm, _MOTOR_Vars_t_::SpinTAC, ST_SPEED_KRPM_PER_PU, ST_SPEED_PU_PER_KRPM, STPOSCONV_getErrorID(), STPOSCONV_getVelocityFiltered(), STPOSCTL_getErrorID(), STPOSCTL_getFriction(), STPOSCTL_getInertia(), STPOSCTL_getPositionError_mrev(), STPOSCTL_getStatus(), STPOSCTL_getTorqueReference(), STPOSMOVE_getErrorID(), STPOSMOVE_getProfileTime_tick(), STPOSMOVE_getStatus(), _MOTOR_Vars_t_::Torque_Nm, USER_computeFlux(), USER_computeTorque_Nm(), USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, and _MOTOR_Vars_t_::VdcBus_kV.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void updateKpKiGains (CTRL_Handle handle)
-+
-+ -+

Updates Kp and Ki gains in the controller object.

-+ -+

Definition at line 623 of file proj_lab13e.c.

-+ -+

References CTRL_setKi(), CTRL_setKp(), _MOTOR_Vars_t_::CtrlState, Flag_Latch_softwareUpdate, _MOTOR_Vars_t_::Flag_MotorIdentified, _MOTOR_Vars_t_::Ki_Idq, _MOTOR_Vars_t_::Ki_spd, _MOTOR_Vars_t_::Kp_Idq, and _MOTOR_Vars_t_::Kp_spd.

-+ -+

Referenced by main().

-+ -+
-+
-+

Variable Documentation

-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Obj ctrl
-+
-+ -+

Definition at line 90 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
CTRL_Handle ctrlHandle
-+
-+ -+

Definition at line 75 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Obj enc
-+
-+ -+

Definition at line 94 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ENC_Handle encHandle
-+
-+ -+

Definition at line 93 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
bool Flag_Latch_softwareUpdate = true
-+
-+ -+

Definition at line 73 of file proj_lab13e.c.

-+ -+

Referenced by main(), and updateKpKiGains().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_AdcData_t gAdcData
-+
-+ -+

Definition at line 83 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint_least16_t gCounter_updateGlobals = 0
-+
-+ -+

Definition at line 71 of file proj_lab13e.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_VpHz_sf
-+
-+ -+

Definition at line 119 of file proj_lab13e.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gFlux_pu_to_Wb_sf
-+
-+ -+

Definition at line 117 of file proj_lab13e.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
uint16_t gLEDcnt = 0
-+
-+ -+

Definition at line 102 of file proj_lab13e.c.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gMaxCurrentSlope = _IQ(0.0)
-+
-+ -+

Definition at line 85 of file proj_lab13e.c.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT
-+
-+ -+

Definition at line 104 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)}
-+
-+ -+

Definition at line 81 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Flux_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 123 of file proj_lab13e.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf
-+
-+ -+

Definition at line 121 of file proj_lab13e.c.

-+ -+

Referenced by main(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
USER_Params gUserParams
-+
-+ -+

Definition at line 79 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
HAL_Handle halHandle
-+
-+ -+

Definition at line 77 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Obj slip
-+
-+ -+

Definition at line 97 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
SLIP_Handle slipHandle
-+
-+ -+

Definition at line 96 of file proj_lab13e.c.

-+ -+

Referenced by main(), mainISR(), and ST_runPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Obj st_obj
-+
-+ -+

Definition at line 99 of file proj_lab13e.c.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
ST_Handle stHandle
-+
-+ -+

Definition at line 100 of file proj_lab13e.c.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e___o_v_e_r_v_i_e_w.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e___o_v_e_r_v_i_e_w.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e___o_v_e_r_v_i_e_w.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___p_r_o_j___l_a_b13_e___o_v_e_r_v_i_e_w.html 2017-06-08 10:42:12.557948300 +0200 -*************** -*** 0 **** ---- 1,53 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: Project Overview -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
Project Overview
-+
-+
-+

Smooth Velocity Transitions in Position Control

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___s_t.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___s_t.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___s_t.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___s_t.html 2017-06-08 10:42:12.557948300 +0200 -*************** -*** 0 **** ---- 1,1951 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: ST -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+ -+
-+
ST
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Data Structures

struct  _POS_Params_t
 Defines the position components of SpinTAC (ST) More...
 
struct  _ST_Obj
 Defines the SpinTAC (ST) object. More...
 
struct  _ST_Vars_t
 Defines the SpinTAC (ST) global variables. More...
 
struct  _VEL_Params_t
 Defines the velocity components of SpinTAC (ST) More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Macros

#define ST_MREV_ROLLOVER   (10.0)
 ROTATION UNIT MAXIMUMS. More...
 
#define ST_EREV_MAXIMUM   (1.0)
 Defines the maximum value for an Electrical Revolution [ERev]. More...
 
#define ST_POS_ERROR_MAXIMUM_MREV   (2.0)
 Defines the maximum value of error allowable in SpinTAC Position Control, MRev This value should be the maximum amount of position error that is allowable in your system. If the position error exceeds this value, SpinTAC Position Control will hold it's output to 0. More...
 
#define ISR_TICKS_PER_SPINTAC_TICK   (USER_NUM_ISR_TICKS_PER_CTRL_TICK * USER_NUM_CTRL_TICKS_PER_SPEED_TICK)
 SAMPLE TIME. More...
 
#define ST_SAMPLE_TIME   (ISR_TICKS_PER_SPINTAC_TICK / USER_ISR_FREQ_Hz)
 Defines the SpinTAC execution period, sec. More...
 
#define ST_SPEED_PU_PER_KRPM   (USER_MOTOR_NUM_POLE_PAIRS / (0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz))
 UNIT SCALING. More...
 
#define ST_SPEED_KRPM_PER_PU   ((0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz) / USER_MOTOR_NUM_POLE_PAIRS)
 Defines the speed scale factor for the system. More...
 
#define ST_SYSTEM_INERTIA_PU   (USER_SYSTEM_INERTIA * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
 Defines the default inertia for the system, PU/(pu/s^2) More...
 
#define ST_SYSTEM_FRICTION_PU   (USER_SYSTEM_FRICTION * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
 Defines the default friction for the system, PU/(pu/s^2) More...
 
#define ST_MIN_ID_SPEED_RPM   (5)
 SPINTAC IDENTIFY SETTINGS. More...
 
#define ST_MIN_ID_SPEED_PU   (ST_MIN_ID_SPEED_RPM * 0.001 * ST_SPEED_PU_PER_KRPM)
 Defines the minimum speed from which the SpinTAC Identify will start running Compile time calculation that converts the minimum identification speed into pu/s. More...
 
#define ST_ID_INCOMPLETE_ERROR   (2005)
 Defines the SpinTAC Identify error code that needs to run to completion Identifies the error code that should not halt operation. More...
 
#define ST_VARS_DEFAULTS
 GLOBAL VARIABLE INITIALIZATION. More...
 
#define ISR_TICKS_PER_SPINTAC_TICK   (USER_NUM_ISR_TICKS_PER_CTRL_TICK * USER_NUM_CTRL_TICKS_PER_SPEED_TICK)
 SAMPLE TIME. More...
 
#define ST_SAMPLE_TIME   (ISR_TICKS_PER_SPINTAC_TICK / USER_ISR_FREQ_Hz)
 Defines the SpinTAC execution period, sec. More...
 
#define ST_SPEED_PU_PER_KRPM   (USER_MOTOR_NUM_POLE_PAIRS / (0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz))
 UNIT SCALING. More...
 
#define ST_SPEED_KRPM_PER_PU   ((0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz) / USER_MOTOR_NUM_POLE_PAIRS)
 Defines the speed scale factor for the system. More...
 
#define ST_SYSTEM_INERTIA_PU   (USER_SYSTEM_INERTIA * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
 Defines the default inertia for the system, PU/(pu/s^2) More...
 
#define ST_SYSTEM_FRICTION_PU   (USER_SYSTEM_FRICTION * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
 Defines the default friction for the system, PU/(pu/s^2) More...
 
#define ST_MIN_ID_SPEED_RPM   (5)
 SPINTAC IDENTIFY SETTINGS. More...
 
#define ST_MIN_ID_SPEED_PU   (ST_MIN_ID_SPEED_RPM * 0.001 * ST_SPEED_PU_PER_KRPM)
 Defines the minimum speed from which the SpinTAC Identify will start running Compile time calculation that converts the minimum identification speed into pu/s. More...
 
#define ST_ID_INCOMPLETE_ERROR   (2005)
 Defines the SpinTAC Identify error code that needs to run to completion Identifies the error code that should not halt operation. More...
 
#define ST_VARS_DEFAULTS
 GLOBAL VARIABLE INITIALIZATION. More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Typedefs

typedef struct _POS_Params_t POS_Params_t
 Defines the position components of SpinTAC (ST) More...
 
typedef struct _ST_Obj ST_Obj
 Defines the SpinTAC (ST) object. More...
 
typedef struct _ST_Obj_ * ST_Handle
 Handle. More...
 
typedef struct _ST_Vars_t ST_Vars_t
 Defines the SpinTAC (ST) global variables. More...
 
typedef struct _VEL_Params_t VEL_Params_t
 Defines the velocity components of SpinTAC (ST) More...
 
typedef struct _ST_Obj ST_Obj
 Defines the SpinTAC (ST) object. More...
 
typedef struct _ST_Obj_ * ST_Handle
 Handle. More...
 
typedef struct _ST_Vars_t ST_Vars_t
 Defines the SpinTAC (ST) global variables. More...
 
-+ -+ -+ -+ -+ -+ -+ -+

-+ Enumerations

enum  ST_PlanButton_e {
-+   ST_PLAN_STOP = 0, -+ ST_PLAN_START, -+ ST_PLAN_PAUSE, -+ ST_PLAN_STOP = 0, -+
-+   ST_PLAN_START, -+ ST_PLAN_PAUSE -+
-+ }
 Enumeration for the control of the position motion state machine (SpinTAC Position Plan) More...
 
enum  ST_PlanButton_e {
-+   ST_PLAN_STOP = 0, -+ ST_PLAN_START, -+ ST_PLAN_PAUSE, -+ ST_PLAN_STOP = 0, -+
-+   ST_PLAN_START, -+ ST_PLAN_PAUSE -+
-+ }
 Enumeration for the control of the velocity motion state machine (SpinTAC Velocity Plan) More...
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

ST_Handle ST_init (void *pMemory, const size_t numBytes)
 Initalizes the SpinTAC (ST) object. More...
 
void ST_setupPosConv (ST_Handle handle)
 Setups SpinTAC Position Convert. More...
 
void ST_setupPosCtl (ST_Handle handle)
 Setups SpinTAC Position Control. More...
 
void ST_setupPosMove (ST_Handle handle)
 Setups SpinTAC Position Move. More...
 
void ST_setupPosPlan (ST_Handle)
 Setups SpinTAC Positon Plan. More...
 
void ST_runPosPlanTick (ST_Handle handle)
 Runs the time-critical components of SpinTAC Positon Plan. More...
 
void ST_runPosConv (ST_Handle, ENC_Handle, CTRL_Handle)
 Runs SpinTAC Positon Convert. More...
 
void ST_runPosCtl (ST_Handle, CTRL_Handle)
 Runs SpinTAC Positon Control. More...
 
void ST_runPosMove (ST_Handle)
 Runs SpinTAC Positon Move. More...
 
void ST_runPosPlan (ST_Handle)
 Runs SpinTAC Positon Plan. More...
 
void ST_setupVelCtl (ST_Handle handle)
 Setups SpinTAC Velocity Control. More...
 
void ST_setupVelMove (ST_Handle handle)
 Setups SpinTAC Velocity Move. More...
 
void ST_setupVelPlan (ST_Handle)
 Setups SpinTAC Velocity Plan. More...
 
void ST_runVelPlanTick (ST_Handle handle)
 Runs the time-critical components of SpinTAC Velocity Plan. More...
 
void ST_setupVelId (ST_Handle handle)
 Setups SpinTAC Velocity Identify. More...
 
void ST_runVelCtl (ST_Handle, CTRL_Handle)
 Runs SpinTAC Velocity Control. More...
 
void ST_runVelMove (ST_Handle, CTRL_Handle)
 Runs SpinTAC Velocity Move. More...
 
void ST_runVelPlan (ST_Handle, CTRL_Handle)
 Runs SpinTAC Velocity Plan. More...
 
void ST_runVelId (ST_Handle, CTRL_Handle)
 Runs SpinTAC Velocity Identify. More...
 
-+

Detailed Description

-+

Data Structure Documentation

-+ -+
-+
-+ -+ -+ -+ -+
struct _POS_Params_t
-+
-+

Defines the position components of SpinTAC (ST)

-+ -+

Definition at line 157 of file spintac_position.h.

-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Data Fields
-+ ST_PosConv_t -+ conv -+ the position converter (ST_PosConv) object
-+ ST_PosCtl_t -+ ctl -+ the position controller (ST_PosCtl) object
-+ ST_PosMove_t -+ move -+ the position profile generator (ST_PosMove) object
-+ ST_PosPlan_t -+ plan -+ the position motion sequencer (ST_PosPlan) object
-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
struct _ST_Obj
-+
-+

Defines the SpinTAC (ST) object.

-+ -+

Definition at line 167 of file spintac_position.h.

-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Data Fields
-+ POS_Params_t -+ pos -+ the position components of the SpinTAC (ST) object
-+ ST_POSCONV_Handle -+ posConvHandle -+ Handle for Position Converter (ST_PosConv)
-+ ST_POSCTL_Handle -+ posCtlHandle -+ Handle for Position Controller (ST_PosCtl)
-+ ST_POSMOVE_Handle -+ posMoveHandle -+ Handle for Position Move (ST_PosMove)
-+ ST_POSPLAN_Handle -+ posPlanHandle -+ Handle for Position Plan (ST_PosPlan)
-+ VEL_Params_t -+ vel -+ the velocity components of the SpinTAC (ST) object
-+ ST_VELCTL_Handle -+ velCtlHandle -+ Handle for Velocity Controller (ST_VelCtl)
-+ ST_VELID_Handle -+ velIdHandle -+ Handle for Velocity Identify (ST_VelId)
-+ ST_VELMOVE_Handle -+ velMoveHandle -+ Handle for Velocity Move (ST_VelMove)
-+ ST_VELPLAN_Handle -+ velPlanHandle -+ Handle for Velocity Plan (ST_VelPlan)
-+ ST_Ver_t -+ version -+ the version (ST_Ver) object
-+ ST_VER_Handle -+ versionHandle -+ Handle for Version (ST_Ver)
-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
struct _ST_Vars_t
-+
-+

Defines the SpinTAC (ST) global variables.

-+ -+

Definition at line 193 of file spintac_position.h.

-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Data Fields
-+ _iq24 -+ FrictionEstimate_Aperkrpm -+ displays the friction used by Position Controller (ST_PosCtl)

displays the friction estimated by Velocity Identify (ST_VelId) and used by Velocity Controller (ST_VelCtl)

-+
-+ _iq24 -+ InertiaEstimate_Aperkrpm -+ displays the inertia used by Position Controller (ST_PosCtl)

displays the inertia estimated by Velocity Identify (ST_VelId) and used by Velocity Controller (ST_VelCtl)

-+
-+ uint16_t -+ PosConvErrorID -+ displays the error seen by the Position Converter (ST_PosConv)
-+ _iq20 -+ PosCtlBw_radps -+ sets the tuning (Bw_radps) of the Position Controller (ST_PosCtl)
-+ uint16_t -+ PosCtlErrorID -+ displays the error seen by Position Controller (ST_PosCtl)
-+ _iq24 -+ PosCtlOutputMax_A -+ sets the maximum amount of current the Position Controller (ST_PosCtl) will supply as Iq reference
-+ _iq24 -+ PosCtlOutputMin_A -+ sets the minimum amount of current the Position Controller (ST_PosCtl) will supply as Iq reference
-+ ST_CtlStatus_e -+ PosCtlStatus -+ status of Position Controller (ST_PosCtl)
-+ ST_MoveCurveType_e -+ PosMoveCurveType -+ selects the curve type used by Position Move (ST_PosMove)
-+ uint16_t -+ PosMoveErrorID -+ displays the error seen by Position Move (ST_PosMove)
-+ ST_MoveStatus_e -+ PosMoveStatus -+ status of Position Move (ST_PosMove)
-+ int32_t -+ PosMoveTime_mticks -+ Profile time million tick part value, together with ProTime_tick to present the total amount of time (ST_PosMove)
-+ int32_t -+ PosMoveTime_ticks -+ Amount of time profile will take within 1 million ticks (ST_PosMove)
-+ uint16_t -+ PosPlanCfgErrorCode -+ displays the specific configuration error in Position Plan (ST_PosPlan)
-+ uint16_t -+ PosPlanCfgErrorIdx -+ displays which index caused a configuration error in Position Plan (ST_PosPlan)
-+ uint16_t -+ PosPlanErrorID -+ displays the error seen by Position Plan (ST_PosPlan)
-+ ST_PlanButton_e -+ PosPlanRun -+ contols the operation of Position Plan (ST_PosPlan)
-+ ST_PlanStatus_e -+ PosPlanStatus -+ status of Position Plan (ST_PosPlan)
-+ _iq20 -+ VelCtlBw_radps -+ sets the tuning (Bw_radps) of the Velocity Controller (ST_VelCtl)
-+ bool -+ VelCtlEnb -+ selects the velocity controller to use { true: SpinTAC false: PI }
-+ uint16_t -+ VelCtlErrorID -+ displays the error seen by Velocity Controller (ST_VelCtl)
-+ _iq24 -+ VelCtlOutputMax_A -+ sets the maximum amount of current the Velocity Controller (ST_VelCtl) will supply as Iq reference
-+ _iq24 -+ VelCtlOutputMin_A -+ sets the minimum amount of current the Velocity Controller (ST_VelCtl) will supply as Iq reference
-+ ST_CtlStatus_e -+ VelCtlStatus -+ status of Velocity Controller (ST_VelCtl)
-+ uint16_t -+ VelIdErrorID -+ displays the error seen by Velocity Identify (ST_VelId)
-+ _iq24 -+ VelIdGoalSpeed_krpm -+ sets the goal speed of Velocity Identify (ST_VelId)
-+ bool -+ VelIdRun -+ controls the operation of the Velocity Identify (ST_VelId)
-+ ST_VelIdStatus_e -+ VelIdStatus -+ status of Velocity Identify (ST_VelId)
-+ _iq24 -+ VelIdTorqueRampTime_sec -+ sets the rate at which torque is applied during Identification (ST_VelId)
-+ ST_MoveCurveType_e -+ VelMoveCurveType -+ selects the curve type used by Velocity Move (ST_VelMove)
-+ uint16_t -+ VelMoveErrorID -+ displays the error seen by Velocity Move (ST_VelMove)
-+ ST_MoveStatus_e -+ VelMoveStatus -+ status of Velocity Move (ST_VelMove)
-+ int32_t -+ VelMoveTime_ticks -+ displys the time that the current profile will take { unit: [ticks] } (ST_VelMove)
-+ uint16_t -+ VelPlanCfgErrorCode -+ displays the specific configuration error in Velocity Plan (ST_VelPlan)
-+ uint16_t -+ VelPlanCfgErrorIdx -+ displays which index caused a configuration error in Velocity Plan (ST_VelPlan)
-+ uint16_t -+ VelPlanErrorID -+ displays the error seen by Velocity Plan (ST_VelPlan)
-+ ST_PlanButton_e -+ VelPlanRun -+ contols the operation of Velocity Plan (ST_VelPlan)
-+ ST_PlanStatus_e -+ VelPlanStatus -+ status of Velocity Plan (ST_VelPlan)
-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
struct _VEL_Params_t
-+
-+

Defines the velocity components of SpinTAC (ST)

-+ -+

Definition at line 143 of file spintac_velocity.h.

-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
Data Fields
-+ ST_PosConv_t -+ conv -+ the position converter (ST_PosConv) object
-+ ST_VelCtl_t -+ ctl -+ the velocity controller (ST_VelCtl) object
-+ ST_VelId_t -+ id -+ the velocity identify (ST_VelId) object
-+ ST_VelMove_t -+ move -+ the velocity profile generator (ST_VelMove) object
-+ ST_VelPlan_t -+ plan -+ the velocity motion sequence generator (ST_VelPlan) object
-+ -+
-+
-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define ISR_TICKS_PER_SPINTAC_TICK   (USER_NUM_ISR_TICKS_PER_CTRL_TICK * USER_NUM_CTRL_TICKS_PER_SPEED_TICK)
-+
-+ -+

SAMPLE TIME.

-+

Defines the number of interrupt ticks per SpinTAC tick Should be the same as the InstSpin-FOC speed controller clock tick

-+ -+

Definition at line 71 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ISR_TICKS_PER_SPINTAC_TICK   (USER_NUM_ISR_TICKS_PER_CTRL_TICK * USER_NUM_CTRL_TICKS_PER_SPEED_TICK)
-+
-+ -+

SAMPLE TIME.

-+

Defines the number of interrupt ticks per SpinTAC tick Should be the same as the InstSpin-FOC speed controller clock tick

-+ -+

Definition at line 90 of file spintac_position.h.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_EREV_MAXIMUM   (1.0)
-+
-+ -+

Defines the maximum value for an Electrical Revolution [ERev].

-+

The position siganl produced by the ENC module is a sawtooth signal This signal varies from 0 to the value specified in ST_EREV_MAXIMUM

-+ -+

Definition at line 78 of file spintac_position.h.

-+ -+

Referenced by ST_setupPosConv().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_ID_INCOMPLETE_ERROR   (2005)
-+
-+ -+

Defines the SpinTAC Identify error code that needs to run to completion Identifies the error code that should not halt operation.

-+ -+

Definition at line 108 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_ID_INCOMPLETE_ERROR   (2005)
-+
-+ -+

Defines the SpinTAC Identify error code that needs to run to completion Identifies the error code that should not halt operation.

-+ -+

Definition at line 127 of file spintac_position.h.

-+ -+

Referenced by ST_runVelId().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_MIN_ID_SPEED_PU   (ST_MIN_ID_SPEED_RPM * 0.001 * ST_SPEED_PU_PER_KRPM)
-+
-+ -+

Defines the minimum speed from which the SpinTAC Identify will start running Compile time calculation that converts the minimum identification speed into pu/s.

-+ -+

Definition at line 104 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_MIN_ID_SPEED_PU   (ST_MIN_ID_SPEED_RPM * 0.001 * ST_SPEED_PU_PER_KRPM)
-+
-+ -+

Defines the minimum speed from which the SpinTAC Identify will start running Compile time calculation that converts the minimum identification speed into pu/s.

-+ -+

Definition at line 123 of file spintac_position.h.

-+ -+

Referenced by ST_runVelId(), ST_runVelMove(), and ST_runVelPlan().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_MIN_ID_SPEED_RPM   (5)
-+
-+ -+

SPINTAC IDENTIFY SETTINGS.

-+

Defines the minimum speed from which the SpinTAC Identify will start running, rpm This value needs to be low enough that the motor is effectivly stopped

-+ -+

Definition at line 100 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_MIN_ID_SPEED_RPM   (5)
-+
-+ -+

SPINTAC IDENTIFY SETTINGS.

-+

Defines the minimum speed from which the SpinTAC Identify will start running, rpm This value needs to be low enough that the motor is effectivly stopped

-+ -+

Definition at line 119 of file spintac_position.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_MREV_ROLLOVER   (10.0)
-+
-+ -+

ROTATION UNIT MAXIMUMS.

-+

Defines the maximum and minimum value at which the Mechanical Revolution [MRev] will rollover. The position signal produced by SpinTAC Position Converter is a sawtooth signal. All SpinTAC Components need to be aware of the bounds of this signal. When the position signal reaches the maximum value it will immediatly go to the minimum value. The minimum value is the negative of the maximum value.

-+ -+

Definition at line 73 of file spintac_position.h.

-+ -+

Referenced by ST_setupPosConv(), ST_setupPosCtl(), and ST_setupPosMove().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_POS_ERROR_MAXIMUM_MREV   (2.0)
-+
-+ -+

Defines the maximum value of error allowable in SpinTAC Position Control, MRev This value should be the maximum amount of position error that is allowable in your system. If the position error exceeds this value, SpinTAC Position Control will hold it's output to 0.

-+ -+

Definition at line 83 of file spintac_position.h.

-+ -+

Referenced by ST_setupPosCtl().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SAMPLE_TIME   (ISR_TICKS_PER_SPINTAC_TICK / USER_ISR_FREQ_Hz)
-+
-+ -+

Defines the SpinTAC execution period, sec.

-+ -+

Definition at line 74 of file spintac_velocity.h.

-+ -+

Referenced by ST_setupVelCtl(), ST_setupVelId(), and ST_setupVelMove().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SAMPLE_TIME   (ISR_TICKS_PER_SPINTAC_TICK / USER_ISR_FREQ_Hz)
-+
-+ -+

Defines the SpinTAC execution period, sec.

-+ -+

Definition at line 93 of file spintac_position.h.

-+ -+

Referenced by ST_setupPosConv(), ST_setupPosCtl(), ST_setupPosMove(), ST_setupPosPlan(), ST_setupVelPlan(), ST_setupVelPlan_GarageDoor(), ST_setupVelPlan_GroceryConveyor(), and ST_setupVelPlan_TestPattern().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SPEED_KRPM_PER_PU   ((0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz) / USER_MOTOR_NUM_POLE_PAIRS)
-+
-+ -+

Defines the speed scale factor for the system.

-+

Compile time calculation for scale factor (ratio) used throughout the system

-+ -+

Definition at line 85 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SPEED_KRPM_PER_PU   ((0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz) / USER_MOTOR_NUM_POLE_PAIRS)
-+
-+ -+

Defines the speed scale factor for the system.

-+

Compile time calculation for scale factor (ratio) used throughout the system

-+ -+

Definition at line 104 of file spintac_position.h.

-+ -+

Referenced by main(), ST_runPosPlan(), ST_runVelPlan(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SPEED_PU_PER_KRPM   (USER_MOTOR_NUM_POLE_PAIRS / (0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz))
-+
-+ -+

UNIT SCALING.

-+

Defines the speed scale factor for the system Compile time calculation for scale factor (ratio) used throughout the system

-+ -+

Definition at line 81 of file spintac_velocity.h.

-+ -+

Referenced by ST_setupVelId().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SPEED_PU_PER_KRPM   (USER_MOTOR_NUM_POLE_PAIRS / (0.001 * 60.0 * USER_IQ_FULL_SCALE_FREQ_Hz))
-+
-+ -+

UNIT SCALING.

-+

Defines the speed scale factor for the system Compile time calculation for scale factor (ratio) used throughout the system

-+ -+

Definition at line 100 of file spintac_position.h.

-+ -+

Referenced by ST_runPosMove(), ST_runVelId(), ST_runVelMove(), ST_setupPosCtl(), ST_setupPosMove(), ST_setupPosPlan(), ST_setupVelPlan(), ST_setupVelPlan_GarageDoor(), ST_setupVelPlan_GroceryConveyor(), ST_setupVelPlan_TestPattern(), and updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SYSTEM_FRICTION_PU   (USER_SYSTEM_FRICTION * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
-+
-+ -+

Defines the default friction for the system, PU/(pu/s^2)

-+

This value should be calculated from the friction estimated with SpinTAC Identify

-+ -+

Definition at line 93 of file spintac_velocity.h.

-+ -+

Referenced by ST_setupVelCtl().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SYSTEM_FRICTION_PU   (USER_SYSTEM_FRICTION * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
-+
-+ -+

Defines the default friction for the system, PU/(pu/s^2)

-+

This value should be calculated from the friction estimated with SpinTAC Identify

-+ -+

Definition at line 112 of file spintac_position.h.

-+ -+

Referenced by ST_setupPosCtl().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SYSTEM_INERTIA_PU   (USER_SYSTEM_INERTIA * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
-+
-+ -+

Defines the default inertia for the system, PU/(pu/s^2)

-+

This value should be calculated from the inertia estimated with SpinTAC Identify

-+ -+

Definition at line 89 of file spintac_velocity.h.

-+ -+

Referenced by ST_setupVelCtl().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_SYSTEM_INERTIA_PU   (USER_SYSTEM_INERTIA * ST_SPEED_KRPM_PER_PU * (1.0 / USER_IQ_FULL_SCALE_CURRENT_A))
-+
-+ -+

Defines the default inertia for the system, PU/(pu/s^2)

-+

This value should be calculated from the inertia estimated with SpinTAC Identify

-+ -+

Definition at line 108 of file spintac_position.h.

-+ -+

Referenced by ST_setupPosCtl().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_VARS_DEFAULTS
-+
-+ Value:
{false, \
-+
ST_VEL_ID_IDLE, \
-+
0, \
-+
0, \
-+
0, \
-+
0, \
-+
0, \
-+
true, \
-+
ST_CTL_IDLE, \
-+ -+ -+ -+
0, \
-+
ST_MOVE_IDLE, \
-+
ST_MOVE_CUR_STCRV, \
-+
0, \
-+
0, \
-+ -+
ST_PLAN_IDLE, \
-+
0, \
-+
0, \
-+
0, \
-+
0}
-+
#define _IQ24(A)
-+
#define USER_SYSTEM_BANDWIDTH
USER MOTOR & ID SETTINGS.
Definition: user_j1.h:209
-+
stops the current motion sequence
-+
#define USER_MOTOR_MAX_CURRENT
Definition: user_j1.h:264
-+
-+

GLOBAL VARIABLE INITIALIZATION.

-+

Initalization values of SpinTAC global variables

-+ -+

Definition at line 114 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define ST_VARS_DEFAULTS
-+
-+ Value:
{ST_CTL_IDLE, \
-+ -+ -+ -+ -+ -+
0, \
-+
ST_MOVE_IDLE, \
-+
ST_MOVE_CUR_STCRV, \
-+
0, \
-+
0, \
-+
0, \
-+ -+
ST_PLAN_IDLE, \
-+
0, \
-+
0, \
-+
0, \
-+
0}
-+
#define USER_SYSTEM_FRICTION
Definition: user_j1.h:269
-+
#define _IQ24(A)
-+
#define USER_SYSTEM_INERTIA
Definition: user_j1.h:268
-+
#define USER_SYSTEM_BANDWIDTH
USER MOTOR & ID SETTINGS.
Definition: user_j1.h:209
-+
stops the current motion sequence
-+
#define USER_MOTOR_MAX_CURRENT
Definition: user_j1.h:264
-+
-+

GLOBAL VARIABLE INITIALIZATION.

-+

Initalization values of SpinTAC global variables

-+ -+

Definition at line 133 of file spintac_position.h.

-+ -+
-+
-+

Typedef Documentation

-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _POS_Params_t POS_Params_t
-+
-+ -+

Defines the position components of SpinTAC (ST)

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _ST_Obj_* ST_Handle
-+
-+ -+

Handle.

-+ -+

Definition at line 168 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _ST_Obj_* ST_Handle
-+
-+ -+

Handle.

-+ -+

Definition at line 180 of file spintac_position.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _ST_Obj ST_Obj
-+
-+ -+

Defines the SpinTAC (ST) object.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _ST_Obj ST_Obj
-+
-+ -+

Defines the SpinTAC (ST) object.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _ST_Vars_t ST_Vars_t
-+
-+ -+

Defines the SpinTAC (ST) global variables.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _ST_Vars_t ST_Vars_t
-+
-+ -+

Defines the SpinTAC (ST) global variables.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
typedef struct _VEL_Params_t VEL_Params_t
-+
-+ -+

Defines the velocity components of SpinTAC (ST)

-+ -+
-+
-+

Enumeration Type Documentation

-+ -+
-+
-+ -+ -+ -+ -+
enum ST_PlanButton_e
-+
-+ -+

Enumeration for the control of the velocity motion state machine (SpinTAC Velocity Plan)

-+ -+ -+ -+ -+ -+ -+ -+
Enumerator
ST_PLAN_STOP  -+

stops the current motion sequence

-+
ST_PLAN_START  -+

starts the current motion sequence

-+
ST_PLAN_PAUSE  -+

pauses the current motion sequence

-+
ST_PLAN_STOP  -+

stops the current motion sequence

-+
ST_PLAN_START  -+

starts the current motion sequence

-+
ST_PLAN_PAUSE  -+

pauses the current motion sequence

-+
-+ -+

Definition at line 172 of file spintac_velocity.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
enum ST_PlanButton_e
-+
-+ -+

Enumeration for the control of the position motion state machine (SpinTAC Position Plan)

-+ -+ -+ -+ -+ -+ -+ -+
Enumerator
ST_PLAN_STOP  -+

stops the current motion sequence

-+
ST_PLAN_START  -+

starts the current motion sequence

-+
ST_PLAN_PAUSE  -+

pauses the current motion sequence

-+
ST_PLAN_STOP  -+

stops the current motion sequence

-+
ST_PLAN_START  -+

starts the current motion sequence

-+
ST_PLAN_PAUSE  -+

pauses the current motion sequence

-+
-+ -+

Definition at line 184 of file spintac_position.h.

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
ST_Handle ST_init (void * pMemory,
const size_t numBytes 
)
-+
-+ inline
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosConv (ST_Handle ,
ENC_Handle ,
CTRL_Handle  
)
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runPosPlanTick (ST_Handle handle)
-+
-+ inline
-+
-+ -+

Runs the time-critical components of SpinTAC Positon Plan.

-+ -+

Definition at line 315 of file spintac_position.h.

-+ -+

References _ST_Obj::posMoveHandle, _ST_Obj::posPlanHandle, STPOSMOVE_getStatus(), STPOSPLAN_runTick(), and STPOSPLAN_setUnitProfDone().

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_runVelPlanTick (ST_Handle handle)
-+
-+ inline
-+
-+ -+

Runs the time-critical components of SpinTAC Velocity Plan.

-+ -+

Definition at line 296 of file spintac_velocity.h.

-+ -+

References STVELMOVE_getStatus(), STVELPLAN_runTick(), STVELPLAN_setUnitProfDone(), _ST_Obj::velMoveHandle, and _ST_Obj::velPlanHandle.

-+ -+

Referenced by mainISR().

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupVelCtl (ST_Handle handle)
-+
-+ inline
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupVelId (ST_Handle handle)
-+
-+ inline
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void ST_setupVelMove (ST_Handle handle)
-+
-+ inline
-+
-+
-+ -+ -+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___u_s_e_r.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___u_s_e_r.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___u_s_e_r.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/group___u_s_e_r.html 2017-06-08 10:42:12.573548300 +0200 -*************** -*** 0 **** ---- 1,3037 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: USER -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+ Macros | -+ Functions
-+
-+
USER
-+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Macros

#define USER_VOLTAGE_SF   ((float_t)((USER_ADC_FULL_SCALE_VOLTAGE_V)/(USER_IQ_FULL_SCALE_VOLTAGE_V)))
 CURRENTS AND VOLTAGES. More...
 
#define USER_CURRENT_SF   ((float_t)((USER_ADC_FULL_SCALE_CURRENT_A)/(USER_IQ_FULL_SCALE_CURRENT_A)))
 Defines the current scale factor for the system. More...
 
#define USER_SYSTEM_FREQ_MHz   (90.0)
 CLOCKS & TIMERS. More...
 
#define USER_CTRL_HANDLE_ADDRESS   (0x13C40)
 Defines the address of controller handle. More...
 
#define USER_EST_HANDLE_ADDRESS   (0x13840)
 Defines the address of estimator handle. More...
 
#define USER_VD_SF   (0.95)
 Defines the direct voltage (Vd) scale factor. More...
 
#define USER_PWM_PERIOD_usec   (1000.0/USER_PWM_FREQ_kHz)
 Defines the Pulse Width Modulation (PWM) period, usec. More...
 
#define USER_ISR_FREQ_Hz   ((float_t)USER_PWM_FREQ_kHz * 1000.0 / (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK)
 Defines the Interrupt Service Routine (ISR) frequency, Hz. More...
 
#define USER_ISR_PERIOD_usec   (USER_PWM_PERIOD_usec * (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK)
 Defines the Interrupt Service Routine (ISR) period, usec. More...
 
#define USER_CTRL_FREQ_Hz   (uint_least32_t)(USER_ISR_FREQ_Hz/USER_NUM_ISR_TICKS_PER_CTRL_TICK)
 DECIMATION. More...
 
#define USER_EST_FREQ_Hz   (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_EST_TICK)
 Defines the estimator frequency, Hz. More...
 
#define USER_TRAJ_FREQ_Hz   (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_TRAJ_TICK)
 Defines the trajectory frequency, Hz. More...
 
#define USER_CTRL_PERIOD_usec   (USER_ISR_PERIOD_usec * USER_NUM_ISR_TICKS_PER_CTRL_TICK)
 Defines the controller execution period, usec. More...
 
#define USER_CTRL_PERIOD_sec   ((float_t)USER_CTRL_PERIOD_usec/(float_t)1000000.0)
 Defines the controller execution period, sec. More...
 
#define USER_MAX_CURRENT_SLOPE_POWERWARP   (0.3*USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz)
 LIMITS. More...
 
#define USER_MAX_ACCEL_Hzps   (20.0)
 Defines the starting maximum acceleration AND deceleration for the speed profiles, Hz/s. More...
 
#define USER_MAX_ACCEL_EST_Hzps   (5.0)
 Defines maximum acceleration for the estimation speed profiles, Hz/s. More...
 
#define USER_MAX_CURRENT_SLOPE   (USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz)
 Defines the maximum current slope for Id trajectory during estimation. More...
 
#define USER_IDRATED_FRACTION_FOR_RATED_FLUX   (1.0)
 Defines the fraction of IdRated to use during rated flux estimation. More...
 
#define USER_IDRATED_FRACTION_FOR_L_IDENT   (1.0)
 Defines the fraction of IdRated to use during inductance estimation. More...
 
#define USER_IDRATED_DELTA   (0.00002)
 Defines the IdRated delta to use during estimation. More...
 
#define USER_SPEEDMAX_FRACTION_FOR_L_IDENT   (1.0)
 Defines the fraction of SpeedMax to use during inductance estimation. More...
 
#define USER_FLUX_FRACTION   (1.0)
 Defines flux fraction to use during inductance identification. More...
 
#define USER_POWERWARP_GAIN   (1.0)
 Defines the PowerWarp gain for computing Id reference. More...
 
#define USER_VOLTAGE_FILTER_POLE_rps   (2.0 * MATH_PI * USER_VOLTAGE_FILTER_POLE_Hz)
 POLES. More...
 
#define USER_OFFSET_POLE_rps   (20.0)
 Defines the software pole location for the voltage and current offset estimation, rad/s. More...
 
#define USER_FLUX_POLE_rps   (100.0)
 Defines the software pole location for the flux estimation, rad/s. More...
 
#define USER_DIRECTION_POLE_rps   (6.0)
 Defines the software pole location for the direction filter, rad/s. More...
 
#define USER_SPEED_POLE_rps   (100.0)
 Defines the software pole location for the speed control filter, rad/s. More...
 
#define USER_DCBUS_POLE_rps   (100.0)
 Defines the software pole location for the DC bus filter, rad/s. More...
 
#define USER_EST_KAPPAQ   (1.5)
 Defines the convergence factor for the estimator. More...
 
#define USER_IQ_FULL_SCALE_FREQ_Hz   (800.0)
 CURRENTS AND VOLTAGES. More...
 
#define USER_IQ_FULL_SCALE_VOLTAGE_V   (24.0)
 Defines full scale value for the IQ30 variable of Voltage inside the system. More...
 
#define USER_ADC_FULL_SCALE_VOLTAGE_V   (26.314)
 Defines the maximum voltage at the input to the AD converter. More...
 
#define USER_IQ_FULL_SCALE_CURRENT_A   (20.0)
 Defines the full scale current for the IQ variables, A. More...
 
#define USER_ADC_FULL_SCALE_CURRENT_A   (33.0)
 Defines the maximum current at the AD converter. More...
 
#define USER_NUM_CURRENT_SENSORS   (3)
 Defines the number of current sensors used. More...
 
#define USER_NUM_VOLTAGE_SENSORS   (3)
 Defines the number of voltage (phase) sensors. More...
 
#define I_A_offset   (0.8331743479)
 ADC current offsets for A, B, and C phases. More...
 
#define I_B_offset   (0.8355930448)
 
#define I_C_offset   (0.8392037153)
 
#define V_A_offset   (0.5271264911)
 ADC voltage offsets for A, B, and C phases. More...
 
#define V_B_offset   (0.5257175565)
 
#define V_C_offset   (0.5249399543)
 
#define USER_PWM_FREQ_kHz   (15.0)
 CLOCKS & TIMERS. More...
 
#define USER_MAX_VS_MAG_PU   (2.0/3.0)
 Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the. More...
 
#define USER_NUM_PWM_TICKS_PER_ISR_TICK   (1)
 DECIMATION. More...
 
#define USER_NUM_ISR_TICKS_PER_CTRL_TICK   (1)
 Defines the number of isr ticks (hardware) per controller clock tick (software) More...
 
#define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK   (1)
 Defines the number of controller clock ticks per current controller clock tick. More...
 
#define USER_NUM_CTRL_TICKS_PER_EST_TICK   (1)
 Defines the number of controller clock ticks per estimator clock tick. More...
 
#define USER_NUM_CTRL_TICKS_PER_SPEED_TICK   (15)
 Defines the number of controller clock ticks per speed controller clock tick. More...
 
#define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK   (15)
 Defines the number of controller clock ticks per trajectory clock tick. More...
 
#define USER_MAX_NEGATIVE_ID_REF_CURRENT_A   (-0.5 * USER_MOTOR_MAX_CURRENT)
 LIMITS. More...
 
#define USER_R_OVER_L_EST_FREQ_Hz   (300)
 Defines the R/L estimation frequency, Hz. More...
 
#define USER_ZEROSPEEDLIMIT   (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz)
 Defines the low speed limit for the flux integrator, pu. More...
 
#define USER_FORCE_ANGLE_FREQ_Hz   (2.0 * USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz)
 Defines the force angle frequency, Hz. More...
 
#define USER_VOLTAGE_FILTER_POLE_Hz   (364.682)
 POLES. More...
 
#define USER_SYSTEM_BANDWIDTH   (20.0)
 USER MOTOR & ID SETTINGS. More...
 
#define Estun_EMJ_04APB22   101
 Define each motor with a unique name and ID number. More...
 
#define Anaheim_BLY172S   102
 
#define Teknic_M2310PLN04K   104
 
#define Belt_Drive_Washer_IPM   201
 
#define Marathon_5K33GN2A   301
 
#define USER_MOTOR   Anaheim_BLY172S
 Uncomment the motor which should be included at compile. More...
 
#define USER_MOTOR_TYPE   MOTOR_Type_Pm
 
#define USER_MOTOR_NUM_POLE_PAIRS   (4)
 
#define USER_MOTOR_Rr   (NULL)
 
#define USER_MOTOR_Rs   (0.4110007)
 
#define USER_MOTOR_Ls_d   (0.0007092811)
 
#define USER_MOTOR_Ls_q   (0.0007092811)
 
#define USER_MOTOR_RATED_FLUX   (0.03279636)
 
#define USER_MOTOR_MAGNETIZING_CURRENT   (NULL)
 
#define USER_MOTOR_RES_EST_CURRENT   (1.0)
 
#define USER_MOTOR_IND_EST_CURRENT   (-1.0)
 
#define USER_MOTOR_MAX_CURRENT   (5.0)
 
#define USER_MOTOR_FLUX_EST_FREQ_Hz   (20.0)
 
#define USER_MOTOR_ENCODER_LINES   (2000.0)
 
#define USER_MOTOR_MAX_SPEED_KRPM   (4.0)
 
#define USER_SYSTEM_INERTIA   (0.02)
 
#define USER_SYSTEM_FRICTION   (0.01)
 
#define USER_IQ_FULL_SCALE_FREQ_Hz   (800.0)
 CURRENTS AND VOLTAGES. More...
 
#define USER_IQ_FULL_SCALE_VOLTAGE_V   (24.0)
 Defines full scale value for the IQ30 variable of Voltage inside the system. More...
 
#define USER_ADC_FULL_SCALE_VOLTAGE_V   (26.314)
 Defines the maximum voltage at the input to the AD converter. More...
 
#define USER_IQ_FULL_SCALE_CURRENT_A   (20.0)
 Defines the full scale current for the IQ variables, A. More...
 
#define USER_ADC_FULL_SCALE_CURRENT_A   (33.0)
 Defines the maximum current at the AD converter. More...
 
#define USER_NUM_CURRENT_SENSORS   (3)
 Defines the number of current sensors used. More...
 
#define USER_NUM_VOLTAGE_SENSORS   (3)
 Defines the number of voltage (phase) sensors. More...
 
#define I_A_offset   (0.8331743479)
 ADC current offsets for A, B, and C phases. More...
 
#define I_B_offset   (0.8355930448)
 
#define I_C_offset   (0.8392037153)
 
#define V_A_offset   (0.5271264911)
 ADC voltage offsets for A, B, and C phases. More...
 
#define V_B_offset   (0.5257175565)
 
#define V_C_offset   (0.5249399543)
 
#define USER_PWM_FREQ_kHz   (15.0)
 CLOCKS & TIMERS. More...
 
#define USER_MAX_VS_MAG_PU   (2.0/3.0)
 Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the. More...
 
#define USER_NUM_PWM_TICKS_PER_ISR_TICK   (1)
 DECIMATION. More...
 
#define USER_NUM_ISR_TICKS_PER_CTRL_TICK   (1)
 Defines the number of isr ticks (hardware) per controller clock tick (software) More...
 
#define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK   (1)
 Defines the number of controller clock ticks per current controller clock tick. More...
 
#define USER_NUM_CTRL_TICKS_PER_EST_TICK   (1)
 Defines the number of controller clock ticks per estimator clock tick. More...
 
#define USER_NUM_CTRL_TICKS_PER_SPEED_TICK   (15)
 Defines the number of controller clock ticks per speed controller clock tick. More...
 
#define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK   (15)
 Defines the number of controller clock ticks per trajectory clock tick. More...
 
#define USER_MAX_NEGATIVE_ID_REF_CURRENT_A   (-0.5 * USER_MOTOR_MAX_CURRENT)
 LIMITS. More...
 
#define USER_R_OVER_L_EST_FREQ_Hz   (300)
 Defines the R/L estimation frequency, Hz. More...
 
#define USER_ZEROSPEEDLIMIT   (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz)
 Defines the low speed limit for the flux integrator, pu. More...
 
#define USER_FORCE_ANGLE_FREQ_Hz   (2.0 * USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz)
 Defines the force angle frequency, Hz. More...
 
#define USER_VOLTAGE_FILTER_POLE_Hz   (364.682)
 POLES. More...
 
#define USER_SYSTEM_BANDWIDTH   (20.0)
 USER MOTOR & ID SETTINGS. More...
 
#define Estun_EMJ_04APB22   101
 Define each motor with a unique name and ID number. More...
 
#define Anaheim_BLY172S   102
 
#define Teknic_M2310PLN04K   104
 
#define Belt_Drive_Washer_IPM   201
 
#define Marathon_5K33GN2A   301
 
#define USER_MOTOR   Anaheim_BLY172S
 Uncomment the motor which should be included at compile. More...
 
#define USER_MOTOR_TYPE   MOTOR_Type_Pm
 
#define USER_MOTOR_NUM_POLE_PAIRS   (4)
 
#define USER_MOTOR_Rr   (NULL)
 
#define USER_MOTOR_Rs   (0.4110007)
 
#define USER_MOTOR_Ls_d   (0.0007092811)
 
#define USER_MOTOR_Ls_q   (0.0007092811)
 
#define USER_MOTOR_RATED_FLUX   (0.03279636)
 
#define USER_MOTOR_MAGNETIZING_CURRENT   (NULL)
 
#define USER_MOTOR_RES_EST_CURRENT   (1.0)
 
#define USER_MOTOR_IND_EST_CURRENT   (-1.0)
 
#define USER_MOTOR_MAX_CURRENT   (5.0)
 
#define USER_MOTOR_FLUX_EST_FREQ_Hz   (20.0)
 
#define USER_MOTOR_ENCODER_LINES   (2000.0)
 
#define USER_MOTOR_MAX_SPEED_KRPM   (4.0)
 
#define USER_SYSTEM_INERTIA   (0.02)
 
#define USER_SYSTEM_FRICTION   (0.01)
 
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+

-+ Functions

void USER_setParams (USER_Params *pUserParams)
 USER MOTOR & ID SETTINGS. More...
 
void USER_checkForErrors (USER_Params *pUserParams)
 Checks for errors in the user parameter values. More...
 
USER_ErrorCode_e USER_getErrorCode (USER_Params *pUserParams)
 Gets the error code in the user parameters. More...
 
void USER_setErrorCode (USER_Params *pUserParams, const USER_ErrorCode_e errorCode)
 Sets the error code in the user parameters. More...
 
void USER_softwareUpdate1p6 (CTRL_Handle handle)
 Recalculates Inductances with the correct Q Format. More...
 
void USER_calcPIgains (CTRL_Handle handle)
 Updates Id and Iq PI gains. More...
 
_iq USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf (void)
 Computes the scale factor needed to convert from torque created by Ld, Lq, Id and Iq, from per unit to Nm. More...
 
_iq USER_computeTorque_Flux_Iq_pu_to_Nm_sf (void)
 Computes the scale factor needed to convert from torque created by flux and Iq, from per unit to Nm. More...
 
_iq USER_computeFlux_pu_to_Wb_sf (void)
 Computes the scale factor needed to convert from per unit to Wb. More...
 
_iq USER_computeFlux_pu_to_VpHz_sf (void)
 Computes the scale factor needed to convert from per unit to V/Hz. More...
 
_iq USER_computeFlux (CTRL_Handle handle, const _iq sf)
 Computes Flux in Wb or V/Hz depending on the scale factor sent as parameter. More...
 
_iq USER_computeTorque_Nm (CTRL_Handle handle, const _iq torque_Flux_sf, const _iq torque_Ls_sf)
 Computes Torque in Nm. More...
 
_iq USER_computeTorque_lbin (CTRL_Handle handle, const _iq torque_Flux_sf, const _iq torque_Ls_sf)
 Computes Torque in lbin. More...
 
-+

Detailed Description

-+

Macro Definition Documentation

-+ -+
-+
-+ -+ -+ -+ -+
#define Anaheim_BLY172S   102
-+
-+ -+

Definition at line 214 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Anaheim_BLY172S   102
-+
-+ -+

Definition at line 214 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Belt_Drive_Washer_IPM   201
-+
-+ -+

Definition at line 220 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Belt_Drive_Washer_IPM   201
-+
-+ -+

Definition at line 220 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Estun_EMJ_04APB22   101
-+
-+ -+

Define each motor with a unique name and ID number.

-+ -+

Definition at line 213 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Estun_EMJ_04APB22   101
-+
-+ -+

Define each motor with a unique name and ID number.

-+ -+

Definition at line 213 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define I_A_offset   (0.8331743479)
-+
-+ -+

ADC current offsets for A, B, and C phases.

-+

One-time hardware dependent, though the calibration can be done at run-time as well After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller

-+ -+

Definition at line 106 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define I_A_offset   (0.8331743479)
-+
-+ -+

ADC current offsets for A, B, and C phases.

-+

One-time hardware dependent, though the calibration can be done at run-time as well After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller

-+ -+

Definition at line 106 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define I_B_offset   (0.8355930448)
-+
-+ -+

Definition at line 107 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define I_B_offset   (0.8355930448)
-+
-+ -+

Definition at line 107 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define I_C_offset   (0.8392037153)
-+
-+ -+

Definition at line 108 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define I_C_offset   (0.8392037153)
-+
-+ -+

Definition at line 108 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Marathon_5K33GN2A   301
-+
-+ -+

Definition at line 223 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Marathon_5K33GN2A   301
-+
-+ -+

Definition at line 223 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Teknic_M2310PLN04K   104
-+
-+ -+

Definition at line 215 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define Teknic_M2310PLN04K   104
-+
-+ -+

Definition at line 215 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ADC_FULL_SCALE_CURRENT_A   (33.0)
-+
-+ -+

Defines the maximum current at the AD converter.

-+

The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) Hardware dependent, this should be based on the current sensing and scaling to the ADC input

-+ -+

Definition at line 92 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ADC_FULL_SCALE_CURRENT_A   (33.0)
-+
-+ -+

Defines the maximum current at the AD converter.

-+

The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) Hardware dependent, this should be based on the current sensing and scaling to the ADC input

-+ -+

Definition at line 92 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ADC_FULL_SCALE_VOLTAGE_V   (26.314)
-+
-+ -+

Defines the maximum voltage at the input to the AD converter.

-+

The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) Hardware dependent, this should be based on the voltage sensing and scaling to the ADC input

-+ -+

Definition at line 82 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ADC_FULL_SCALE_VOLTAGE_V   (26.314)
-+
-+ -+

Defines the maximum voltage at the input to the AD converter.

-+

The value that will be represented by the maximum ADC input (3.3V) and conversion (0FFFh) Hardware dependent, this should be based on the voltage sensing and scaling to the ADC input

-+ -+

Definition at line 82 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_CTRL_FREQ_Hz   (uint_least32_t)(USER_ISR_FREQ_Hz/USER_NUM_ISR_TICKS_PER_CTRL_TICK)
-+
-+ -+

DECIMATION.

-+

Defines the controller frequency, Hz Compile time calculation

-+ -+

Definition at line 126 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_CTRL_HANDLE_ADDRESS   (0x13C40)
-+
-+ -+

Defines the address of controller handle.

-+ -+

Definition at line 99 of file user.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_CTRL_PERIOD_sec   ((float_t)USER_CTRL_PERIOD_usec/(float_t)1000000.0)
-+
-+ -+

Defines the controller execution period, sec.

-+

Compile time calculation

-+ -+

Definition at line 142 of file user.h.

-+ -+

Referenced by recalcKpKi(), recalcKpKiPmsm(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_CTRL_PERIOD_usec   (USER_ISR_PERIOD_usec * USER_NUM_ISR_TICKS_PER_CTRL_TICK)
-+
-+ -+

Defines the controller execution period, usec.

-+

Compile time calculation

-+ -+

Definition at line 138 of file user.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_CURRENT_SF   ((float_t)((USER_ADC_FULL_SCALE_CURRENT_A)/(USER_IQ_FULL_SCALE_CURRENT_A)))
-+
-+ -+

Defines the current scale factor for the system.

-+

Compile time calculation for scale factor (ratio) used throughout the system

-+ -+

Definition at line 89 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_DCBUS_POLE_rps   (100.0)
-+
-+ -+

Defines the software pole location for the DC bus filter, rad/s.

-+ -+

Definition at line 209 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_DIRECTION_POLE_rps   (6.0)
-+
-+ -+

Defines the software pole location for the direction filter, rad/s.

-+ -+

Definition at line 203 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_EST_FREQ_Hz   (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_EST_TICK)
-+
-+ -+

Defines the estimator frequency, Hz.

-+

Compile time calculation

-+ -+

Definition at line 130 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_EST_HANDLE_ADDRESS   (0x13840)
-+
-+ -+

Defines the address of estimator handle.

-+ -+

Definition at line 103 of file user.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_EST_KAPPAQ   (1.5)
-+
-+ -+

Defines the convergence factor for the estimator.

-+

Do not change from default for FAST

-+ -+

Definition at line 213 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_FLUX_FRACTION   (1.0)
-+
-+ -+

Defines flux fraction to use during inductance identification.

-+ -+

Definition at line 181 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_FLUX_POLE_rps   (100.0)
-+
-+ -+

Defines the software pole location for the flux estimation, rad/s.

-+

Should not be changed from default of (100.0)

-+ -+

Definition at line 200 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_FORCE_ANGLE_FREQ_Hz   (2.0 * USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz)
-+
-+ -+

Defines the force angle frequency, Hz.

-+

Frequency of stator vector rotation used by the ForceAngle object Can be positive or negative

-+ -+

Definition at line 192 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_FORCE_ANGLE_FREQ_Hz   (2.0 * USER_ZEROSPEEDLIMIT * USER_IQ_FULL_SCALE_FREQ_Hz)
-+
-+ -+

Defines the force angle frequency, Hz.

-+

Frequency of stator vector rotation used by the ForceAngle object Can be positive or negative

-+ -+

Definition at line 192 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IDRATED_DELTA   (0.00002)
-+
-+ -+

Defines the IdRated delta to use during estimation.

-+ -+

Definition at line 173 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IDRATED_FRACTION_FOR_L_IDENT   (1.0)
-+
-+ -+

Defines the fraction of IdRated to use during inductance estimation.

-+ -+

Definition at line 169 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IDRATED_FRACTION_FOR_RATED_FLUX   (1.0)
-+
-+ -+

Defines the fraction of IdRated to use during rated flux estimation.

-+ -+

Definition at line 165 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IQ_FULL_SCALE_CURRENT_A   (20.0)
-+
-+ -+

Defines the full scale current for the IQ variables, A.

-+

All currents are converted into (pu) based on the ratio to this value WARNING: this value MUST be larger than the maximum current readings that you are expecting from the motor or the reading will roll over to 0, creating a control issue

-+ -+

Definition at line 87 of file user_j1.h.

-+ -+

Referenced by CTRL_calcMax_Ls_qFmt(), main(), mainISR(), recalcKpKi(), recalcKpKiPmsm(), ST_setupPosCtl(), ST_setupVelCtl(), ST_setupVelId(), updateGlobalVariables_motor(), USER_calcPIgains(), USER_checkForErrors(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_setParams(), and USER_softwareUpdate1p6().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IQ_FULL_SCALE_CURRENT_A   (20.0)
-+
-+ -+

Defines the full scale current for the IQ variables, A.

-+

All currents are converted into (pu) based on the ratio to this value WARNING: this value MUST be larger than the maximum current readings that you are expecting from the motor or the reading will roll over to 0, creating a control issue

-+ -+

Definition at line 87 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IQ_FULL_SCALE_FREQ_Hz   (800.0)
-+
-+ -+

CURRENTS AND VOLTAGES.

-+

Defines the full scale frequency for IQ variable, Hz All frequencies are converted into (pu) based on the ratio to this value this value MUST be larger than the maximum speed that you are expecting from the motor

-+ -+

Definition at line 64 of file user_j1.h.

-+ -+

Referenced by main(), recalcKpKiPmsm(), ST_setupPosConv(), ST_setupPosCtl(), ST_setupPosMove(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IQ_FULL_SCALE_FREQ_Hz   (800.0)
-+
-+ -+

CURRENTS AND VOLTAGES.

-+

Defines the full scale frequency for IQ variable, Hz All frequencies are converted into (pu) based on the ratio to this value this value MUST be larger than the maximum speed that you are expecting from the motor

-+ -+

Definition at line 64 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IQ_FULL_SCALE_VOLTAGE_V   (24.0)
-+
-+ -+

Defines full scale value for the IQ30 variable of Voltage inside the system.

-+

All voltages are converted into (pu) based on the ratio to this value WARNING: this value MUST meet the following condition: USER_IQ_FULL_SCALE_VOLTAGE_V > 0.5 * USER_MOTOR_MAX_CURRENT * USER_MOTOR_Ls_d * USER_VOLTAGE_FILTER_POLE_rps, WARNING: otherwise the value can saturate and roll-over, causing an inaccurate value WARNING: this value is OFTEN greater than the maximum measured ADC value, especially with high Bemf motors operating at higher than rated speeds WARNING: if you know the value of your Bemf constant, and you know you are operating at a multiple speed due to field weakening, be sure to set this value higher than the expected Bemf voltage It is recommended to start with a value ~3x greater than the USER_ADC_FULL_SCALE_VOLTAGE_V and increase to 4-5x if scenarios where a Bemf calculation may exceed these limits This value is also used to calculate the minimum flux value: USER_IQ_FULL_SCALE_VOLTAGE_V/USER_EST_FREQ_Hz/0.7

-+ -+

Definition at line 77 of file user_j1.h.

-+ -+

Referenced by CTRL_calcMax_Ls_qFmt(), recalcKpKi(), recalcKpKiPmsm(), updateGlobalVariables_motor(), USER_calcPIgains(), USER_checkForErrors(), USER_computeFlux_pu_to_VpHz_sf(), USER_computeFlux_pu_to_Wb_sf(), USER_computeTorque_Flux_Iq_pu_to_Nm_sf(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_setParams(), and USER_softwareUpdate1p6().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_IQ_FULL_SCALE_VOLTAGE_V   (24.0)
-+
-+ -+

Defines full scale value for the IQ30 variable of Voltage inside the system.

-+

All voltages are converted into (pu) based on the ratio to this value WARNING: this value MUST meet the following condition: USER_IQ_FULL_SCALE_VOLTAGE_V > 0.5 * USER_MOTOR_MAX_CURRENT * USER_MOTOR_Ls_d * USER_VOLTAGE_FILTER_POLE_rps, WARNING: otherwise the value can saturate and roll-over, causing an inaccurate value WARNING: this value is OFTEN greater than the maximum measured ADC value, especially with high Bemf motors operating at higher than rated speeds WARNING: if you know the value of your Bemf constant, and you know you are operating at a multiple speed due to field weakening, be sure to set this value higher than the expected Bemf voltage It is recommended to start with a value ~3x greater than the USER_ADC_FULL_SCALE_VOLTAGE_V and increase to 4-5x if scenarios where a Bemf calculation may exceed these limits This value is also used to calculate the minimum flux value: USER_IQ_FULL_SCALE_VOLTAGE_V/USER_EST_FREQ_Hz/0.7

-+ -+

Definition at line 77 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ISR_FREQ_Hz   ((float_t)USER_PWM_FREQ_kHz * 1000.0 / (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK)
-+
-+ -+

Defines the Interrupt Service Routine (ISR) frequency, Hz.

-+ -+

Definition at line 115 of file user.h.

-+ -+

Referenced by main(), and mainISR().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ISR_PERIOD_usec   (USER_PWM_PERIOD_usec * (float_t)USER_NUM_PWM_TICKS_PER_ISR_TICK)
-+
-+ -+

Defines the Interrupt Service Routine (ISR) period, usec.

-+ -+

Definition at line 119 of file user.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_ACCEL_EST_Hzps   (5.0)
-+
-+ -+

Defines maximum acceleration for the estimation speed profiles, Hz/s.

-+

Only used during Motor ID (commission)

-+ -+

Definition at line 158 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_ACCEL_Hzps   (20.0)
-+
-+ -+

Defines the starting maximum acceleration AND deceleration for the speed profiles, Hz/s.

-+

Updated in run-time through user functions Inverter, motor, inertia, and load will limit actual acceleration capability

-+ -+

Definition at line 154 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_CURRENT_SLOPE   (USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz)
-+
-+ -+

Defines the maximum current slope for Id trajectory during estimation.

-+ -+

Definition at line 161 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_CURRENT_SLOPE_POWERWARP   (0.3*USER_MOTOR_RES_EST_CURRENT/USER_IQ_FULL_SCALE_CURRENT_A/USER_TRAJ_FREQ_Hz)
-+
-+ -+

LIMITS.

-+

Defines the maximum current slope for Id trajectory during PowerWarp For Induction motors only, controls how fast Id input can change under PowerWarp control

-+ -+

Definition at line 149 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_NEGATIVE_ID_REF_CURRENT_A   (-0.5 * USER_MOTOR_MAX_CURRENT)
-+
-+ -+

LIMITS.

-+

Defines the maximum negative current to be applied in Id reference Used in field weakening only, this is a safety setting (e.g. to protect against demagnetization) User must also be aware that overall current magnitude [sqrt(Id^2 + Iq^2)] should be kept below any machine design specifications

-+ -+

Definition at line 177 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_NEGATIVE_ID_REF_CURRENT_A   (-0.5 * USER_MOTOR_MAX_CURRENT)
-+
-+ -+

LIMITS.

-+

Defines the maximum negative current to be applied in Id reference Used in field weakening only, this is a safety setting (e.g. to protect against demagnetization) User must also be aware that overall current magnitude [sqrt(Id^2 + Iq^2)] should be kept below any machine design specifications

-+ -+

Definition at line 177 of file user_j1.h.

-+ -+

Referenced by main(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_VS_MAG_PU   (2.0/3.0)
-+
-+ -+

Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the.

-+

Id and Iq PI current controllers. The Id and Iq current controller outputs are Vd and Vq. The relationship between Vs, Vd, and Vq is: Vs = sqrt(Vd^2 + Vq^2). In this FOC controller, the Vd value is set equal to USER_MAX_VS_MAG*USER_VD_MAG_FACTOR. Vq = sqrt(USER_MAX_VS_MAG^2 - Vd^2). Set USER_MAX_VS_MAG = 0.5 for a pure sinewave with a peak at SQRT(3)/2 = 86.6% duty cycle. No current reconstruction is needed for this scenario. Set USER_MAX_VS_MAG = 1/SQRT(3) = 0.5774 for a pure sinewave with a peak at 100% duty cycle. Current reconstruction will be needed for this scenario (Lab10a-x). Set USER_MAX_VS_MAG = 2/3 = 0.6666 to create a trapezoidal voltage waveform. Current reconstruction will be needed for this scenario (Lab10a-x). For space vector over-modulation, see lab 10 for details on system requirements that will allow the SVM generator to go all the way to trapezoidal.

-+ -+

Definition at line 135 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MAX_VS_MAG_PU   (2.0/3.0)
-+
-+ -+

Defines the maximum Voltage vector (Vs) magnitude allowed. This value sets the maximum magnitude for the output of the.

-+

Id and Iq PI current controllers. The Id and Iq current controller outputs are Vd and Vq. The relationship between Vs, Vd, and Vq is: Vs = sqrt(Vd^2 + Vq^2). In this FOC controller, the Vd value is set equal to USER_MAX_VS_MAG*USER_VD_MAG_FACTOR. Vq = sqrt(USER_MAX_VS_MAG^2 - Vd^2). Set USER_MAX_VS_MAG = 0.5 for a pure sinewave with a peak at SQRT(3)/2 = 86.6% duty cycle. No current reconstruction is needed for this scenario. Set USER_MAX_VS_MAG = 1/SQRT(3) = 0.5774 for a pure sinewave with a peak at 100% duty cycle. Current reconstruction will be needed for this scenario (Lab10a-x). Set USER_MAX_VS_MAG = 2/3 = 0.6666 to create a trapezoidal voltage waveform. Current reconstruction will be needed for this scenario (Lab10a-x). For space vector over-modulation, see lab 10 for details on system requirements that will allow the SVM generator to go all the way to trapezoidal.

-+ -+

Definition at line 135 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR   Anaheim_BLY172S
-+
-+ -+

Uncomment the motor which should be included at compile.

-+

These motor ID settings and motor parameters are then available to be used by the control system Once your ideal settings and parameters are identified update the motor section here so it is available in the binary code

-+ -+

Definition at line 229 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR   Anaheim_BLY172S
-+
-+ -+

Uncomment the motor which should be included at compile.

-+

These motor ID settings and motor parameters are then available to be used by the control system Once your ideal settings and parameters are identified update the motor section here so it is available in the binary code

-+ -+

Definition at line 229 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_ENCODER_LINES   (2000.0)
-+
-+ -+

Definition at line 266 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_ENCODER_LINES   (2000.0)
-+
-+ -+

Definition at line 266 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_FLUX_EST_FREQ_Hz   (20.0)
-+
-+ -+

Definition at line 265 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_FLUX_EST_FREQ_Hz   (20.0)
-+
-+ -+

Definition at line 265 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_IND_EST_CURRENT   (-1.0)
-+
-+ -+

Definition at line 263 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_IND_EST_CURRENT   (-1.0)
-+
-+ -+

Definition at line 263 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Ls_d   (0.0007092811)
-+
-+ -+

Definition at line 258 of file user_j1.h.

-+ -+

Referenced by ST_setupPosConv(), USER_checkForErrors(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Ls_d   (0.0007092811)
-+
-+ -+

Definition at line 258 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Ls_q   (0.0007092811)
-+
-+ -+

Definition at line 259 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Ls_q   (0.0007092811)
-+
-+ -+

Definition at line 259 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_MAGNETIZING_CURRENT   (NULL)
-+
-+ -+

Definition at line 261 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_MAGNETIZING_CURRENT   (NULL)
-+
-+ -+

Definition at line 261 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_MAX_CURRENT   (5.0)
-+
-+ -+

Definition at line 264 of file user_j1.h.

-+ -+

Referenced by main(), recalcKpKiPmsm(), ST_setupPosCtl(), ST_setupVelCtl(), ST_setupVelId(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_MAX_CURRENT   (5.0)
-+
-+ -+

Definition at line 264 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_MAX_SPEED_KRPM   (4.0)
-+
-+ -+

Definition at line 267 of file user_j1.h.

-+ -+

Referenced by ST_setupPosCtl(), ST_setupPosMove(), ST_setupPosPlan(), and ST_setupVelId().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_MAX_SPEED_KRPM   (4.0)
-+
-+ -+

Definition at line 267 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_NUM_POLE_PAIRS   (4)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_NUM_POLE_PAIRS   (4)
-+
-+ -+

Definition at line 255 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_RATED_FLUX   (0.03279636)
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_RATED_FLUX   (0.03279636)
-+
-+ -+

Definition at line 260 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_RES_EST_CURRENT   (1.0)
-+
-+ -+

Definition at line 262 of file user_j1.h.

-+ -+

Referenced by recalcKpKiPmsm(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_RES_EST_CURRENT   (1.0)
-+
-+ -+

Definition at line 262 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Rr   (NULL)
-+
-+ -+

Definition at line 256 of file user_j1.h.

-+ -+

Referenced by ST_setupPosConv(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Rr   (NULL)
-+
-+ -+

Definition at line 256 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Rs   (0.4110007)
-+
-+ -+

Definition at line 257 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_Rs   (0.4110007)
-+
-+ -+

Definition at line 257 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_TYPE   MOTOR_Type_Pm
-+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_MOTOR_TYPE   MOTOR_Type_Pm
-+
-+ -+

Definition at line 254 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK   (1)
-+
-+ -+

Defines the number of controller clock ticks per current controller clock tick.

-+

Relationship of controller clock rate to current controller (FOC) rate

-+ -+

Definition at line 155 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_CURRENT_TICK   (1)
-+
-+ -+

Defines the number of controller clock ticks per current controller clock tick.

-+

Relationship of controller clock rate to current controller (FOC) rate

-+ -+

Definition at line 155 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_EST_TICK   (1)
-+
-+ -+

Defines the number of controller clock ticks per estimator clock tick.

-+

Relationship of controller clock rate to estimator (FAST) rate Depends on needed dynamic performance, FAST provides very good results as low as 1 KHz while more dynamic or high speed applications may require up to 15 KHz

-+ -+

Definition at line 160 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_EST_TICK   (1)
-+
-+ -+

Defines the number of controller clock ticks per estimator clock tick.

-+

Relationship of controller clock rate to estimator (FAST) rate Depends on needed dynamic performance, FAST provides very good results as low as 1 KHz while more dynamic or high speed applications may require up to 15 KHz

-+ -+

Definition at line 160 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_SPEED_TICK   (15)
-+
-+ -+

Defines the number of controller clock ticks per speed controller clock tick.

-+

Relationship of controller clock rate to speed loop rate

-+ -+

Definition at line 164 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_SPEED_TICK   (15)
-+
-+ -+

Defines the number of controller clock ticks per speed controller clock tick.

-+

Relationship of controller clock rate to speed loop rate

-+ -+

Definition at line 164 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK   (15)
-+
-+ -+

Defines the number of controller clock ticks per trajectory clock tick.

-+

Relationship of controller clock rate to trajectory loop rate Typically the same as the speed rate

-+ -+

Definition at line 169 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CTRL_TICKS_PER_TRAJ_TICK   (15)
-+
-+ -+

Defines the number of controller clock ticks per trajectory clock tick.

-+

Relationship of controller clock rate to trajectory loop rate Typically the same as the speed rate

-+ -+

Definition at line 169 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CURRENT_SENSORS   (3)
-+
-+ -+

Defines the number of current sensors used.

-+

Defined by the hardware capability present May be (2) or (3)

-+ -+

Definition at line 97 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_CURRENT_SENSORS   (3)
-+
-+ -+

Defines the number of current sensors used.

-+

Defined by the hardware capability present May be (2) or (3)

-+ -+

Definition at line 97 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_ISR_TICKS_PER_CTRL_TICK   (1)
-+
-+ -+

Defines the number of isr ticks (hardware) per controller clock tick (software)

-+

Controller clock tick (CTRL) is the main clock used for all timing in the software Typically the PWM Frequency triggers (can be decimated by the ePWM hardware for less overhead) an ADC SOC ADC SOC triggers an ADC Conversion Done ADC Conversion Done triggers ISR This relates the hardware ISR rate to the software controller rate Typcially want to consider some form of decimation (ePWM hardware, CURRENT or EST) over 16KHz ISR to insure interrupt completes and leaves time for background tasks

-+ -+

Definition at line 151 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_ISR_TICKS_PER_CTRL_TICK   (1)
-+
-+ -+

Defines the number of isr ticks (hardware) per controller clock tick (software)

-+

Controller clock tick (CTRL) is the main clock used for all timing in the software Typically the PWM Frequency triggers (can be decimated by the ePWM hardware for less overhead) an ADC SOC ADC SOC triggers an ADC Conversion Done ADC Conversion Done triggers ISR This relates the hardware ISR rate to the software controller rate Typcially want to consider some form of decimation (ePWM hardware, CURRENT or EST) over 16KHz ISR to insure interrupt completes and leaves time for background tasks

-+ -+

Definition at line 151 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_PWM_TICKS_PER_ISR_TICK   (1)
-+
-+ -+

DECIMATION.

-+

Defines the number of pwm clock ticks per isr clock tick Note: Valid values are 1, 2 or 3 only

-+ -+

Definition at line 142 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_PWM_TICKS_PER_ISR_TICK   (1)
-+
-+ -+

DECIMATION.

-+

Defines the number of pwm clock ticks per isr clock tick Note: Valid values are 1, 2 or 3 only

-+ -+

Definition at line 142 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_VOLTAGE_SENSORS   (3)
-+
-+ -+

Defines the number of voltage (phase) sensors.

-+

Must be (3)

-+ -+

Definition at line 101 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_NUM_VOLTAGE_SENSORS   (3)
-+
-+ -+

Defines the number of voltage (phase) sensors.

-+

Must be (3)

-+ -+

Definition at line 101 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_OFFSET_POLE_rps   (20.0)
-+
-+ -+

Defines the software pole location for the voltage and current offset estimation, rad/s.

-+

Should not be changed from default of (20.0)

-+ -+

Definition at line 196 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_POWERWARP_GAIN   (1.0)
-+
-+ -+

Defines the PowerWarp gain for computing Id reference.

-+

Induction motors only

-+ -+

Definition at line 185 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_PWM_FREQ_kHz   (15.0)
-+
-+ -+

CLOCKS & TIMERS.

-+

Defines the Pulse Width Modulation (PWM) frequency, kHz PWM frequency can be set directly here up to 30 KHz safely (60 KHz MAX in some cases) For higher PWM frequencies (60 KHz+ typical for low inductance, high current ripple motors) it is recommended to use the ePWM hardware and adjustable ADC SOC to decimate the ADC conversion done interrupt to the control system, or to use the software Que example. Otherwise you risk missing interrupts and disrupting the timing of the control state machine

-+ -+

Definition at line 125 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_PWM_FREQ_kHz   (15.0)
-+
-+ -+

CLOCKS & TIMERS.

-+

Defines the Pulse Width Modulation (PWM) frequency, kHz PWM frequency can be set directly here up to 30 KHz safely (60 KHz MAX in some cases) For higher PWM frequencies (60 KHz+ typical for low inductance, high current ripple motors) it is recommended to use the ePWM hardware and adjustable ADC SOC to decimate the ADC conversion done interrupt to the control system, or to use the software Que example. Otherwise you risk missing interrupts and disrupting the timing of the control state machine

-+ -+

Definition at line 125 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_PWM_PERIOD_usec   (1000.0/USER_PWM_FREQ_kHz)
-+
-+ -+

Defines the Pulse Width Modulation (PWM) period, usec.

-+

Compile time calculation

-+ -+

Definition at line 111 of file user.h.

-+ -+

Referenced by USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_R_OVER_L_EST_FREQ_Hz   (300)
-+
-+ -+

Defines the R/L estimation frequency, Hz.

-+

User higher values for low inductance motors and lower values for higher inductance motors. The values can range from 100 to 300 Hz.

-+ -+

Definition at line 182 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_R_OVER_L_EST_FREQ_Hz   (300)
-+
-+ -+

Defines the R/L estimation frequency, Hz.

-+

User higher values for low inductance motors and lower values for higher inductance motors. The values can range from 100 to 300 Hz.

-+ -+

Definition at line 182 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SPEED_POLE_rps   (100.0)
-+
-+ -+

Defines the software pole location for the speed control filter, rad/s.

-+ -+

Definition at line 206 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SPEEDMAX_FRACTION_FOR_L_IDENT   (1.0)
-+
-+ -+

Defines the fraction of SpeedMax to use during inductance estimation.

-+ -+

Definition at line 177 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_BANDWIDTH   (20.0)
-+
-+ -+

USER MOTOR & ID SETTINGS.

-+

Defines the default bandwidth for SpinTAC Control This value should be determined by putting SpinTAC Control through a tuning process If a Bandwidth Scale value has been previously identified multiply it by 20 to convert into Bandwidth

-+ -+

Definition at line 209 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_BANDWIDTH   (20.0)
-+
-+ -+

USER MOTOR & ID SETTINGS.

-+

Defines the default bandwidth for SpinTAC Control This value should be determined by putting SpinTAC Control through a tuning process If a Bandwidth Scale value has been previously identified multiply it by 20 to convert into Bandwidth

-+ -+

Definition at line 209 of file user_j1.h.

-+ -+

Referenced by ST_setupPosCtl(), and ST_setupVelCtl().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_FREQ_MHz   (90.0)
-+
-+ -+

CLOCKS & TIMERS.

-+

Defines the system clock frequency, MHz

-+ -+

Definition at line 95 of file user.h.

-+ -+

Referenced by main(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_FRICTION   (0.01)
-+
-+ -+

Definition at line 269 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_FRICTION   (0.01)
-+
-+ -+

Definition at line 269 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_INERTIA   (0.02)
-+
-+ -+

Definition at line 268 of file user_j1.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_SYSTEM_INERTIA   (0.02)
-+
-+ -+

Definition at line 268 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_TRAJ_FREQ_Hz   (uint_least32_t)(USER_CTRL_FREQ_Hz/USER_NUM_CTRL_TICKS_PER_TRAJ_TICK)
-+
-+ -+

Defines the trajectory frequency, Hz.

-+

Compile time calculation

-+ -+

Definition at line 134 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_VD_SF   (0.95)
-+
-+ -+

Defines the direct voltage (Vd) scale factor.

-+ -+

Definition at line 107 of file user.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_VOLTAGE_FILTER_POLE_Hz   (364.682)
-+
-+ -+

POLES.

-+

Defines the analog voltage filter pole location, Hz Must match the hardware filter for Vph

-+ -+

Definition at line 199 of file user_j1.h.

-+ -+

Referenced by USER_checkForErrors().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_VOLTAGE_FILTER_POLE_Hz   (364.682)
-+
-+ -+

POLES.

-+

Defines the analog voltage filter pole location, Hz Must match the hardware filter for Vph

-+ -+

Definition at line 199 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_VOLTAGE_FILTER_POLE_rps   (2.0 * MATH_PI * USER_VOLTAGE_FILTER_POLE_Hz)
-+
-+ -+

POLES.

-+

Defines the analog voltage filter pole location, rad/s Compile time calculation from Hz to rad/s

-+ -+

Definition at line 192 of file user.h.

-+ -+

Referenced by CTRL_calcMax_Ls_qFmt(), USER_checkForErrors(), USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf(), USER_setParams(), and USER_softwareUpdate1p6().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_VOLTAGE_SF   ((float_t)((USER_ADC_FULL_SCALE_VOLTAGE_V)/(USER_IQ_FULL_SCALE_VOLTAGE_V)))
-+
-+ -+

CURRENTS AND VOLTAGES.

-+

Defines the voltage scale factor for the system Compile time calculation for scale factor (ratio) used throughout the system

-+ -+

Definition at line 85 of file user.h.

-+ -+

Referenced by USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ZEROSPEEDLIMIT   (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz)
-+
-+ -+

Defines the low speed limit for the flux integrator, pu.

-+

This is the speed range (CW/CCW) at which the ForceAngle object is active, but only if Enabled Outside of this speed - or if Disabled - the ForcAngle will NEVER be active and the angle is provided by FAST only

-+ -+

Definition at line 187 of file user_j1.h.

-+ -+

Referenced by setFeLimitZero(), USER_checkForErrors(), and USER_setParams().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define USER_ZEROSPEEDLIMIT   (0.5 / USER_IQ_FULL_SCALE_FREQ_Hz)
-+
-+ -+

Defines the low speed limit for the flux integrator, pu.

-+

This is the speed range (CW/CCW) at which the ForceAngle object is active, but only if Enabled Outside of this speed - or if Disabled - the ForcAngle will NEVER be active and the angle is provided by FAST only

-+ -+

Definition at line 187 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define V_A_offset   (0.5271264911)
-+
-+ -+

ADC voltage offsets for A, B, and C phases.

-+

One-time hardware dependent, though the calibration can be done at run-time as well After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller

-+ -+

Definition at line 113 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define V_A_offset   (0.5271264911)
-+
-+ -+

ADC voltage offsets for A, B, and C phases.

-+

One-time hardware dependent, though the calibration can be done at run-time as well After initial board calibration these values should be updated for your specific hardware so they are available after compile in the binary to be loaded to the controller

-+ -+

Definition at line 113 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define V_B_offset   (0.5257175565)
-+
-+ -+

Definition at line 114 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define V_B_offset   (0.5257175565)
-+
-+ -+

Definition at line 114 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define V_C_offset   (0.5249399543)
-+
-+ -+

Definition at line 115 of file user_j5.h.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+
#define V_C_offset   (0.5249399543)
-+
-+ -+

Definition at line 115 of file user_j1.h.

-+ -+

Referenced by main().

-+ -+
-+
-+

Function Documentation

-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void USER_calcPIgains (CTRL_Handle handle)
-+
-+ -+

Updates Id and Iq PI gains.

-+
Parameters
-+ -+ -+
[in]handleThe controller (CTRL) handle
-+
-+
-+ -+

Definition at line 851 of file user.c.

-+ -+

References _IQ, CTRL_getCtrlPeriod_sec(), CTRL_setGains(), EST_getLs_d_H(), EST_getLs_q_H(), EST_getRs_Ohm(), _CTRL_Obj_::estHandle, PID_setKi(), _CTRL_Obj_::pidHandle_Id, _CTRL_Obj_::pidHandle_Iq, USER_IQ_FULL_SCALE_CURRENT_A, and USER_IQ_FULL_SCALE_VOLTAGE_V.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void USER_checkForErrors (USER_ParamspUserParams)
-+
-+ -+

Checks for errors in the user parameter values.

-+
Parameters
-+ -+ -+
[in]pUserParamsThe pointer to the user param structure
-+
-+
-+ -+

Definition at line 195 of file user.c.

-+ -+

References MATH_PI, USER_CTRL_FREQ_Hz, USER_CTRL_PERIOD_sec, USER_CURRENT_SF, USER_DCBUS_POLE_rps, USER_DIRECTION_POLE_rps, USER_EST_FREQ_Hz, USER_EST_KAPPAQ, USER_FLUX_FRACTION, USER_FLUX_POLE_rps, USER_FORCE_ANGLE_FREQ_Hz, USER_IDRATED_DELTA, USER_IDRATED_FRACTION_FOR_L_IDENT, USER_IDRATED_FRACTION_FOR_RATED_FLUX, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MAX_ACCEL_EST_Hzps, USER_MAX_ACCEL_Hzps, USER_MAX_CURRENT_SLOPE, USER_MAX_CURRENT_SLOPE_POWERWARP, USER_MAX_NEGATIVE_ID_REF_CURRENT_A, USER_MAX_VS_MAG_PU, USER_MOTOR_FLUX_EST_FREQ_Hz, USER_MOTOR_IND_EST_CURRENT, USER_MOTOR_Ls_d, USER_MOTOR_Ls_q, USER_MOTOR_MAGNETIZING_CURRENT, USER_MOTOR_MAX_CURRENT, USER_MOTOR_NUM_POLE_PAIRS, USER_MOTOR_RATED_FLUX, USER_MOTOR_RES_EST_CURRENT, USER_MOTOR_Rr, USER_MOTOR_Rs, USER_MOTOR_TYPE, USER_NUM_CTRL_TICKS_PER_CURRENT_TICK, USER_NUM_CTRL_TICKS_PER_EST_TICK, USER_NUM_CTRL_TICKS_PER_SPEED_TICK, USER_NUM_CTRL_TICKS_PER_TRAJ_TICK, USER_NUM_CURRENT_SENSORS, USER_NUM_ISR_TICKS_PER_CTRL_TICK, USER_NUM_PWM_TICKS_PER_ISR_TICK, USER_NUM_VOLTAGE_SENSORS, USER_OFFSET_POLE_rps, USER_POWERWARP_GAIN, USER_PWM_FREQ_kHz, USER_R_OVER_L_EST_FREQ_Hz, USER_setErrorCode(), USER_SPEED_POLE_rps, USER_SPEEDMAX_FRACTION_FOR_L_IDENT, USER_SYSTEM_FREQ_MHz, USER_TRAJ_FREQ_Hz, USER_VOLTAGE_FILTER_POLE_Hz, USER_VOLTAGE_FILTER_POLE_rps, USER_VOLTAGE_SF, and USER_ZEROSPEEDLIMIT.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeFlux (CTRL_Handle handle,
const _iq sf 
)
-+
-+ -+

Computes Flux in Wb or V/Hz depending on the scale factor sent as parameter.

-+
Parameters
-+ -+ -+ -+
[in]handleThe controller (CTRL) handle
[in]sfThe scale factor to convert flux from per unit to Wb or V/Hz
-+
-+
-+
Returns
The flux in Wb or V/Hz depending on the scale factor sent as parameter, in IQ24 format
-+ -+

Definition at line 962 of file user.c.

-+ -+

References _IQmpy, EST_getFlux_pu(), and _CTRL_Obj_::estHandle.

-+ -+

Referenced by updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeFlux_pu_to_VpHz_sf (void )
-+
-+ -+

Computes the scale factor needed to convert from per unit to V/Hz.

-+
Returns
The scale factor to convert from flux per unit to flux in V/Hz, in IQ24 format
-+ -+

Definition at line 950 of file user.c.

-+ -+

References _IQ, USER_EST_FREQ_Hz, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MOTOR_RATED_FLUX, and USER_MOTOR_TYPE.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeFlux_pu_to_Wb_sf (void )
-+
-+ -+

Computes the scale factor needed to convert from per unit to Wb.

-+
Returns
The scale factor to convert from flux per unit to flux in Wb, in IQ24 format
-+ -+

Definition at line 938 of file user.c.

-+ -+

References _IQ, MATH_PI, USER_EST_FREQ_Hz, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MOTOR_RATED_FLUX, and USER_MOTOR_TYPE.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeTorque_Flux_Iq_pu_to_Nm_sf (void )
-+
-+ -+

Computes the scale factor needed to convert from torque created by flux and Iq, from per unit to Nm.

-+
Returns
The scale factor to convert torque from Flux * Iq from per unit to Nm, in IQ24 format
-+ -+

Definition at line 925 of file user.c.

-+ -+

References _IQ, MATH_PI, USER_EST_FREQ_Hz, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MOTOR_NUM_POLE_PAIRS, USER_MOTOR_RATED_FLUX, and USER_MOTOR_TYPE.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeTorque_lbin (CTRL_Handle handle,
const _iq torque_Flux_sf,
const _iq torque_Ls_sf 
)
-+
-+ -+

Computes Torque in lbin.

-+
Parameters
-+ -+ -+ -+ -+
[in]handleThe controller (CTRL) handle
[in]torque_Flux_sfThe scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to lbin
[in]torque_Ls_sfThe scale factor to convert torque from Flux * Iq from per unit to lbin
-+
-+
-+
Returns
The torque in lbin, in IQ24 format
-+

Computes Torque in lbin.

-+ -+

Definition at line 990 of file user.c.

-+ -+

References _IQ, _IQ30toIQ, _IQmpy, EST_getFlux_pu(), EST_getLs_d_pu(), EST_getLs_q_pu(), _CTRL_Obj_::estHandle, MATH_Nm_TO_lbin_SF, PID_getFbackValue(), _CTRL_Obj_::pidHandle_Id, and _CTRL_Obj_::pidHandle_Iq.

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf (void )
-+
-+ -+

Computes the scale factor needed to convert from torque created by Ld, Lq, Id and Iq, from per unit to Nm.

-+
Returns
The scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to Nm, in IQ24 format
-+ -+

Definition at line 913 of file user.c.

-+ -+

References _IQ, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MOTOR_Ls_d, USER_MOTOR_NUM_POLE_PAIRS, and USER_VOLTAGE_FILTER_POLE_rps.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
_iq USER_computeTorque_Nm (CTRL_Handle handle,
const _iq torque_Flux_sf,
const _iq torque_Ls_sf 
)
-+
-+ -+

Computes Torque in Nm.

-+
Parameters
-+ -+ -+ -+ -+
[in]handleThe controller (CTRL) handle
[in]torque_Flux_sfThe scale factor to convert torque from (Ld - Lq) * Id * Iq from per unit to Nm
[in]torque_Ls_sfThe scale factor to convert torque from Flux * Iq from per unit to Nm
-+
-+
-+
Returns
The torque in Nm, in IQ24 format
-+ -+

Definition at line 972 of file user.c.

-+ -+

References _IQ30toIQ, _IQmpy, EST_getFlux_pu(), EST_getLs_d_pu(), EST_getLs_q_pu(), _CTRL_Obj_::estHandle, PID_getFbackValue(), _CTRL_Obj_::pidHandle_Id, and _CTRL_Obj_::pidHandle_Iq.

-+ -+

Referenced by updateGlobalVariables_motor().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
USER_ErrorCode_e USER_getErrorCode (USER_ParamspUserParams)
-+
-+ -+

Gets the error code in the user parameters.

-+
Parameters
-+ -+ -+
[in]pUserParamsThe pointer to the user param structure
-+
-+
-+
Returns
The error code
-+ -+

Definition at line 816 of file user.c.

-+ -+

References _USER_Params_::errorCode.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+ -+
void USER_setErrorCode (USER_ParamspUserParams,
const USER_ErrorCode_e errorCode 
)
-+
-+ -+

Sets the error code in the user parameters.

-+
Parameters
-+ -+ -+ -+
[in]pUserParamsThe pointer to the user param structure
[in]errorCodeThe error code
-+
-+
-+ -+

Definition at line 822 of file user.c.

-+ -+

References _USER_Params_::errorCode.

-+ -+

Referenced by USER_checkForErrors().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void USER_setParams (USER_ParamspUserParams)
-+
-+ -+

USER MOTOR & ID SETTINGS.

-+

Sets the user parameter values

Parameters
-+ -+ -+
[in]pUserParamsThe pointer to the user param structure
-+
-+
-+ -+

Definition at line 62 of file user.c.

-+ -+

References _USER_Params_::ctrlFreq_Hz, _USER_Params_::ctrlPeriod_sec, _USER_Params_::ctrlWaitTime, _USER_Params_::current_sf, _USER_Params_::dcBusPole_rps, _USER_Params_::directionPole_rps, _USER_Params_::estFreq_Hz, _USER_Params_::estKappa, _USER_Params_::estWaitTime, _USER_Params_::fluxEstFreq_Hz, _USER_Params_::fluxFraction, _USER_Params_::fluxPole_rps, _USER_Params_::FluxWaitTime, _USER_Params_::forceAngleFreq_Hz, _USER_Params_::IdRated, _USER_Params_::IdRated_delta, _USER_Params_::IdRatedFraction_indEst, _USER_Params_::IdRatedFraction_ratedFlux, _USER_Params_::indEst_speedMaxFraction, _USER_Params_::iqFullScaleCurrent_A, _USER_Params_::iqFullScaleFreq_Hz, _USER_Params_::iqFullScaleVoltage_V, _USER_Params_::LsWaitTime, _USER_Params_::maxAccel_est_Hzps, _USER_Params_::maxAccel_Hzps, _USER_Params_::maxCurrent, _USER_Params_::maxCurrent_indEst, _USER_Params_::maxCurrent_resEst, _USER_Params_::maxCurrentSlope, _USER_Params_::maxCurrentSlope_powerWarp, _USER_Params_::maxNegativeIdCurrent_a, _USER_Params_::maxVsMag_pu, _USER_Params_::motor_Ls_d, _USER_Params_::motor_Ls_q, _USER_Params_::motor_numPolePairs, _USER_Params_::motor_ratedFlux, _USER_Params_::motor_Rr, _USER_Params_::motor_Rs, _USER_Params_::motor_type, _USER_Params_::numCtrlTicksPerCurrentTick, _USER_Params_::numCtrlTicksPerEstTick, _USER_Params_::numCtrlTicksPerSpeedTick, _USER_Params_::numCtrlTicksPerTrajTick, _USER_Params_::numCurrentSensors, _USER_Params_::numIsrTicksPerCtrlTick, _USER_Params_::numVoltageSensors, _USER_Params_::offsetPole_rps, _USER_Params_::powerWarpGain, _USER_Params_::pwmPeriod_usec, _USER_Params_::RoverL_estFreq_Hz, _USER_Params_::RsWaitTime, _USER_Params_::speedPole_rps, _USER_Params_::systemFreq_MHz, _USER_Params_::trajFreq_Hz, USER_CTRL_FREQ_Hz, USER_CTRL_PERIOD_sec, USER_CURRENT_SF, USER_DCBUS_POLE_rps, USER_DIRECTION_POLE_rps, USER_EST_FREQ_Hz, USER_EST_KAPPAQ, USER_FLUX_FRACTION, USER_FLUX_POLE_rps, USER_FORCE_ANGLE_FREQ_Hz, USER_IDRATED_DELTA, USER_IDRATED_FRACTION_FOR_L_IDENT, USER_IDRATED_FRACTION_FOR_RATED_FLUX, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_FREQ_Hz, USER_IQ_FULL_SCALE_VOLTAGE_V, USER_MAX_ACCEL_EST_Hzps, USER_MAX_ACCEL_Hzps, USER_MAX_CURRENT_SLOPE, USER_MAX_CURRENT_SLOPE_POWERWARP, USER_MAX_NEGATIVE_ID_REF_CURRENT_A, USER_MAX_VS_MAG_PU, USER_MOTOR_FLUX_EST_FREQ_Hz, USER_MOTOR_IND_EST_CURRENT, USER_MOTOR_Ls_d, USER_MOTOR_Ls_q, USER_MOTOR_MAGNETIZING_CURRENT, USER_MOTOR_MAX_CURRENT, USER_MOTOR_NUM_POLE_PAIRS, USER_MOTOR_RATED_FLUX, USER_MOTOR_RES_EST_CURRENT, USER_MOTOR_Rr, USER_MOTOR_Rs, USER_MOTOR_TYPE, USER_NUM_CTRL_TICKS_PER_CURRENT_TICK, USER_NUM_CTRL_TICKS_PER_EST_TICK, USER_NUM_CTRL_TICKS_PER_SPEED_TICK, USER_NUM_CTRL_TICKS_PER_TRAJ_TICK, USER_NUM_CURRENT_SENSORS, USER_NUM_ISR_TICKS_PER_CTRL_TICK, USER_NUM_VOLTAGE_SENSORS, USER_OFFSET_POLE_rps, USER_POWERWARP_GAIN, USER_PWM_PERIOD_usec, USER_R_OVER_L_EST_FREQ_Hz, USER_SPEED_POLE_rps, USER_SPEEDMAX_FRACTION_FOR_L_IDENT, USER_SYSTEM_FREQ_MHz, USER_TRAJ_FREQ_Hz, USER_VOLTAGE_FILTER_POLE_rps, USER_VOLTAGE_SF, USER_ZEROSPEEDLIMIT, _USER_Params_::voltage_sf, _USER_Params_::voltageFilterPole_rps, and _USER_Params_::zeroSpeedLimit.

-+ -+

Referenced by main().

-+ -+
-+
-+ -+
-+
-+ -+ -+ -+ -+ -+ -+ -+ -+
void USER_softwareUpdate1p6 (CTRL_Handle handle)
-+
-+ -+

Recalculates Inductances with the correct Q Format.

-+
Parameters
-+ -+ -+
[in]handleThe controller (CTRL) handle
-+
-+
-+ -+

Definition at line 830 of file user.c.

-+ -+

References _IQ30, _IQ30toF(), EST_getLs_coarse_max_pu(), EST_setLs_d_pu(), EST_setLs_q_pu(), EST_setLs_qFmt(), _CTRL_Obj_::estHandle, _MOTOR_Params_::Ls_d_H, _MOTOR_Params_::Ls_q_H, _CTRL_Obj_::motorParams, USER_IQ_FULL_SCALE_CURRENT_A, USER_IQ_FULL_SCALE_VOLTAGE_V, and USER_VOLTAGE_FILTER_POLE_rps.

-+ -+

Referenced by main().

-+ -+
-+
-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/index.html motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/index.html -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/index.html 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/index.html 2017-06-08 10:42:12.604748300 +0200 -*************** -*** 0 **** ---- 1,54 ---- -+ -+ -+ -+ -+ -+ -+ instaspin_motion: MotorWare documentation the InstaSPIN_MOTION example projects -+ -+ -+ -+ -+ -+ -+
-+
-+ -+ -+ -+ -+ -+ -+
-+
instaspin_motion -+
-+
-+
-+ -+ -+ -+
-+
-+
-+
MotorWare documentation the InstaSPIN_MOTION example projects
-+
-+
-+

Please select the "Modules" tab to see the list of projects.

-+

Copyright 2012 Texas Instruments Incorporated. All rights reserved.

-+
-+ -+ -+ -+ -diff -crwN motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/jquery.js motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/jquery.js -*** motorware/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/jquery.js 1970-01-01 01:00:00.000000000 +0100 ---- motorware_alt_manuell_angepasst_patch/motorware_1_01_00_16/sw/solutions/instaspin_motion/boards/TAPAS__V1_0/f28x/f2806xM/docs/html/jquery.js 2017-06-08 10:42:12.604748300 +0200 -*************** -*** 0 **** ---- 1,68 ---- -+ /*! -+ * jQuery JavaScript Library v1.7.1 -+ * http://jquery.com/ -+ * -+ * Copyright 2011, John Resig -+ * Dual licensed under the MIT or GPL Version 2 licenses. -+ * http://jquery.org/license -+ * -+ * Includes Sizzle.js -+ * http://sizzlejs.com/ -+ * Copyright 2011, The Dojo Foundation -+ * Released under the MIT, BSD, and GPL Licenses. -+ * -+ * Date: Mon Nov 21 21:11:03 2011 -0500 -+ */ -+ (function(bb,L){var av=bb.document,bu=bb.navigator,bl=bb.location;var b=(function(){var bF=function(b0,b1){return new bF.fn.init(b0,b1,bD)},bU=bb.jQuery,bH=bb.$,bD,bY=/^(?:[^#<]*(<[\w\W]+>)[^>]*$|#([\w\-]*)$)/,bM=/\S/,bI=/^\s+/,bE=/\s+$/,bA=/^<(\w+)\s*\/?>(?:<\/\1>)?$/,bN=/^[\],:{}\s]*$/,bW=/\\(?:["\\\/bfnrt]|u[0-9a-fA-F]{4})/g,bP=/"[^"\\\n\r]*"|true|false|null|-?\d+(?:\.\d*)?(?:[eE][+\-]?\d+)?/g,bJ=/(?:^|:|,)(?:\s*\[)+/g,by=/(webkit)[ \/]([\w.]+)/,bR=/(opera)(?:.*version)?[ \/]([\w.]+)/,bQ=/(msie) ([\w.]+)/,bS=/(mozilla)(?:.*? rv:([\w.]+))?/,bB=/-([a-z]|[0-9])/ig,bZ=/^-ms-/,bT=function(b0,b1){return(b1+"").toUpperCase()},bX=bu.userAgent,bV,bC,e,bL=Object.prototype.toString,bG=Object.prototype.hasOwnProperty,bz=Array.prototype.push,bK=Array.prototype.slice,bO=String.prototype.trim,bv=Array.prototype.indexOf,bx={};bF.fn=bF.prototype={constructor:bF,init:function(b0,b4,b3){var b2,b5,b1,b6;if(!b0){return this}if(b0.nodeType){this.context=this[0]=b0;this.length=1;return this}if(b0==="body"&&!b4&&av.body){this.context=av;this[0]=av.body;this.selector=b0;this.length=1;return this}if(typeof b0==="string"){if(b0.charAt(0)==="<"&&b0.charAt(b0.length-1)===">"&&b0.length>=3){b2=[null,b0,null]}else{b2=bY.exec(b0)}if(b2&&(b2[1]||!b4)){if(b2[1]){b4=b4 instanceof bF?b4[0]:b4;b6=(b4?b4.ownerDocument||b4:av);b1=bA.exec(b0);if(b1){if(bF.isPlainObject(b4)){b0=[av.createElement(b1[1])];bF.fn.attr.call(b0,b4,true)}else{b0=[b6.createElement(b1[1])]}}else{b1=bF.buildFragment([b2[1]],[b6]);b0=(b1.cacheable?bF.clone(b1.fragment):b1.fragment).childNodes}return bF.merge(this,b0)}else{b5=av.getElementById(b2[2]);if(b5&&b5.parentNode){if(b5.id!==b2[2]){return b3.find(b0)}this.length=1;this[0]=b5}this.context=av;this.selector=b0;return this}}else{if(!b4||b4.jquery){return(b4||b3).find(b0)}else{return this.constructor(b4).find(b0)}}}else{if(bF.isFunction(b0)){return b3.ready(b0)}}if(b0.selector!==L){this.selector=b0.selector;this.context=b0.context}return bF.makeArray(b0,this)},selector:"",jquery:"1.7.1",length:0,size:function(){return this.length},toArray:function(){return bK.call(this,0)},get:function(b0){return b0==null?this.toArray():(b0<0?this[this.length+b0]:this[b0])},pushStack:function(b1,b3,b0){var b2=this.constructor();if(bF.isArray(b1)){bz.apply(b2,b1)}else{bF.merge(b2,b1)}b2.prevObject=this;b2.context=this.context;if(b3==="find"){b2.selector=this.selector+(this.selector?" ":"")+b0}else{if(b3){b2.selector=this.selector+"."+b3+"("+b0+")"}}return b2},each:function(b1,b0){return bF.each(this,b1,b0)},ready:function(b0){bF.bindReady();bC.add(b0);return this},eq:function(b0){b0=+b0;return b0===-1?this.slice(b0):this.slice(b0,b0+1)},first:function(){return this.eq(0)},last:function(){return this.eq(-1)},slice:function(){return this.pushStack(bK.apply(this,arguments),"slice",bK.call(arguments).join(","))},map:function(b0){return this.pushStack(bF.map(this,function(b2,b1){return b0.call(b2,b1,b2)}))},end:function(){return this.prevObject||this.constructor(null)},push:bz,sort:[].sort,splice:[].splice};bF.fn.init.prototype=bF.fn;bF.extend=bF.fn.extend=function(){var b9,b2,b0,b1,b6,b7,b5=arguments[0]||{},b4=1,b3=arguments.length,b8=false;if(typeof b5==="boolean"){b8=b5;b5=arguments[1]||{};b4=2}if(typeof b5!=="object"&&!bF.isFunction(b5)){b5={}}if(b3===b4){b5=this;--b4}for(;b40){return}bC.fireWith(av,[bF]);if(bF.fn.trigger){bF(av).trigger("ready").off("ready")}}},bindReady:function(){if(bC){return}bC=bF.Callbacks("once memory");if(av.readyState==="complete"){return setTimeout(bF.ready,1)}if(av.addEventListener){av.addEventListener("DOMContentLoaded",e,false);bb.addEventListener("load",bF.ready,false)}else{if(av.attachEvent){av.attachEvent("onreadystatechange",e);bb.attachEvent("onload",bF.ready);var b0=false;try{b0=bb.frameElement==null}catch(b1){}if(av.documentElement.doScroll&&b0){bw()}}}},isFunction:function(b0){return bF.type(b0)==="function"},isArray:Array.isArray||function(b0){return bF.type(b0)==="array"},isWindow:function(b0){return b0&&typeof b0==="object"&&"setInterval" in b0},isNumeric:function(b0){return !isNaN(parseFloat(b0))&&isFinite(b0)},type:function(b0){return b0==null?String(b0):bx[bL.call(b0)]||"object"},isPlainObject:function(b2){if(!b2||bF.type(b2)!=="object"||b2.nodeType||bF.isWindow(b2)){return false}try{if(b2.constructor&&!bG.call(b2,"constructor")&&!bG.call(b2.constructor.prototype,"isPrototypeOf")){return false}}catch(b1){return false}var b0;for(b0 in b2){}return b0===L||bG.call(b2,b0)},isEmptyObject:function(b1){for(var b0 in b1){return false}return true},error:function(b0){throw new Error(b0)},parseJSON:function(b0){if(typeof b0!=="string"||!b0){return null}b0=bF.trim(b0);if(bb.JSON&&bb.JSON.parse){return bb.JSON.parse(b0)}if(bN.test(b0.replace(bW,"@").replace(bP,"]").replace(bJ,""))){return(new Function("return "+b0))()}bF.error("Invalid JSON: "+b0)},parseXML:function(b2){var b0,b1;try{if(bb.DOMParser){b1=new DOMParser();b0=b1.parseFromString(b2,"text/xml")}else{b0=new ActiveXObject("Microsoft.XMLDOM");b0.async="false";b0.loadXML(b2)}}catch(b3){b0=L}if(!b0||!b0.documentElement||b0.getElementsByTagName("parsererror").length){bF.error("Invalid XML: "+b2)}return b0},noop:function(){},globalEval:function(b0){if(b0&&bM.test(b0)){(bb.execScript||function(b1){bb["eval"].call(bb,b1)})(b0)}},camelCase:function(b0){return b0.replace(bZ,"ms-").replace(bB,bT)},nodeName:function(b1,b0){return b1.nodeName&&b1.nodeName.toUpperCase()===b0.toUpperCase()},each:function(b3,b6,b2){var b1,b4=0,b5=b3.length,b0=b5===L||bF.isFunction(b3);if(b2){if(b0){for(b1 in b3){if(b6.apply(b3[b1],b2)===false){break}}}else{for(;b40&&b0[0]&&b0[b1-1])||b1===0||bF.isArray(b0));if(b3){for(;b21?aJ.call(arguments,0):bG;if(!(--bw)){bC.resolveWith(bC,bx)}}}function bz(bF){return function(bG){bB[bF]=arguments.length>1?aJ.call(arguments,0):bG;bC.notifyWith(bE,bB)}}if(e>1){for(;bv
a";bI=bv.getElementsByTagName("*");bF=bv.getElementsByTagName("a")[0];if(!bI||!bI.length||!bF){return{}}bG=av.createElement("select");bx=bG.appendChild(av.createElement("option"));bE=bv.getElementsByTagName("input")[0];bJ={leadingWhitespace:(bv.firstChild.nodeType===3),tbody:!bv.getElementsByTagName("tbody").length,htmlSerialize:!!bv.getElementsByTagName("link").length,style:/top/.test(bF.getAttribute("style")),hrefNormalized:(bF.getAttribute("href")==="/a"),opacity:/^0.55/.test(bF.style.opacity),cssFloat:!!bF.style.cssFloat,checkOn:(bE.value==="on"),optSelected:bx.selected,getSetAttribute:bv.className!=="t",enctype:!!av.createElement("form").enctype,html5Clone:av.createElement("nav").cloneNode(true).outerHTML!=="<:nav>",submitBubbles:true,changeBubbles:true,focusinBubbles:false,deleteExpando:true,noCloneEvent:true,inlineBlockNeedsLayout:false,shrinkWrapBlocks:false,reliableMarginRight:true};bE.checked=true;bJ.noCloneChecked=bE.cloneNode(true).checked;bG.disabled=true;bJ.optDisabled=!bx.disabled;try{delete bv.test}catch(bC){bJ.deleteExpando=false}if(!bv.addEventListener&&bv.attachEvent&&bv.fireEvent){bv.attachEvent("onclick",function(){bJ.noCloneEvent=false});bv.cloneNode(true).fireEvent("onclick")}bE=av.createElement("input");bE.value="t";bE.setAttribute("type","radio");bJ.radioValue=bE.value==="t";bE.setAttribute("checked","checked");bv.appendChild(bE);bD=av.createDocumentFragment();bD.appendChild(bv.lastChild);bJ.checkClone=bD.cloneNode(true).cloneNode(true).lastChild.checked;bJ.appendChecked=bE.checked;bD.removeChild(bE);bD.appendChild(bv);bv.innerHTML="";if(bb.getComputedStyle){bA=av.createElement("div");bA.style.width="0";bA.style.marginRight="0";bv.style.width="2px";bv.appendChild(bA);bJ.reliableMarginRight=(parseInt((bb.getComputedStyle(bA,null)||{marginRight:0}).marginRight,10)||0)===0}if(bv.attachEvent){for(by in {submit:1,change:1,focusin:1}){bB="on"+by;bw=(bB in bv);if(!bw){bv.setAttribute(bB,"return;");bw=(typeof bv[bB]==="function")}bJ[by+"Bubbles"]=bw}}bD.removeChild(bv);bD=bG=bx=bA=bv=bE=null;b(function(){var bM,bU,bV,bT,bN,bO,bL,bS,bR,e,bP,bQ=av.getElementsByTagName("body")[0];if(!bQ){return}bL=1;bS="position:absolute;top:0;left:0;width:1px;height:1px;margin:0;";bR="visibility:hidden;border:0;";e="style='"+bS+"border:5px solid #000;padding:0;'";bP="
";bM=av.createElement("div");bM.style.cssText=bR+"width:0;height:0;position:static;top:0;margin-top:"+bL+"px";bQ.insertBefore(bM,bQ.firstChild);bv=av.createElement("div");bM.appendChild(bv);bv.innerHTML="
t
";bz=bv.getElementsByTagName("td");bw=(bz[0].offsetHeight===0);bz[0].style.display="";bz[1].style.display="none";bJ.reliableHiddenOffsets=bw&&(bz[0].offsetHeight===0);bv.innerHTML="";bv.style.width=bv.style.paddingLeft="1px";b.boxModel=bJ.boxModel=bv.offsetWidth===2;if(typeof bv.style.zoom!=="undefined"){bv.style.display="inline";bv.style.zoom=1;bJ.inlineBlockNeedsLayout=(bv.offsetWidth===2);bv.style.display="";bv.innerHTML="
";bJ.shrinkWrapBlocks=(bv.offsetWidth!==2)}bv.style.cssText=bS+bR;bv.innerHTML=bP;bU=bv.firstChild;bV=bU.firstChild;bN=bU.nextSibling.firstChild.firstChild;bO={doesNotAddBorder:(bV.offsetTop!==5),doesAddBorderForTableAndCells:(bN.offsetTop===5)};bV.style.position="fixed";bV.style.top="20px";bO.fixedPosition=(bV.offsetTop===20||bV.offsetTop===15);bV.style.position=bV.style.top="";bU.style.overflow="hidden";bU.style.position="relative";bO.subtractsBorderForOverflowNotVisible=(bV.offsetTop===-5);bO.doesNotIncludeMarginInBodyOffset=(bQ.offsetTop!==bL);bQ.removeChild(bM);bv=bM=null;b.extend(bJ,bO)});return bJ})();var aS=/^(?:\{.*\}|\[.*\])$/,aA=/([A-Z])/g;b.extend({cache:{},uuid:0,expando:"jQuery"+(b.fn.jquery+Math.random()).replace(/\D/g,""),noData:{embed:true,object:"clsid:D27CDB6E-AE6D-11cf-96B8-444553540000",applet:true},hasData:function(e){e=e.nodeType?b.cache[e[b.expando]]:e[b.expando];return !!e&&!S(e)},data:function(bx,bv,bz,by){if(!b.acceptData(bx)){return}var bG,bA,bD,bE=b.expando,bC=typeof bv==="string",bF=bx.nodeType,e=bF?b.cache:bx,bw=bF?bx[bE]:bx[bE]&&bE,bB=bv==="events";if((!bw||!e[bw]||(!bB&&!by&&!e[bw].data))&&bC&&bz===L){return}if(!bw){if(bF){bx[bE]=bw=++b.uuid}else{bw=bE}}if(!e[bw]){e[bw]={};if(!bF){e[bw].toJSON=b.noop}}if(typeof bv==="object"||typeof bv==="function"){if(by){e[bw]=b.extend(e[bw],bv)}else{e[bw].data=b.extend(e[bw].data,bv)}}bG=bA=e[bw];if(!by){if(!bA.data){bA.data={}}bA=bA.data}if(bz!==L){bA[b.camelCase(bv)]=bz}if(bB&&!bA[bv]){return bG.events}if(bC){bD=bA[bv];if(bD==null){bD=bA[b.camelCase(bv)]}}else{bD=bA}return bD},removeData:function(bx,bv,by){if(!b.acceptData(bx)){return}var bB,bA,bz,bC=b.expando,bD=bx.nodeType,e=bD?b.cache:bx,bw=bD?bx[bC]:bC;if(!e[bw]){return}if(bv){bB=by?e[bw]:e[bw].data;if(bB){if(!b.isArray(bv)){if(bv in bB){bv=[bv]}else{bv=b.camelCase(bv);if(bv in bB){bv=[bv]}else{bv=bv.split(" ")}}}for(bA=0,bz=bv.length;bA-1){return true}}return false},val:function(bx){var e,bv,by,bw=this[0];if(!arguments.length){if(bw){e=b.valHooks[bw.nodeName.toLowerCase()]||b.valHooks[bw.type];if(e&&"get" in e&&(bv=e.get(bw,"value"))!==L){return bv}bv=bw.value;return typeof bv==="string"?bv.replace(aU,""):bv==null?"":bv}return}by=b.isFunction(bx);return this.each(function(bA){var bz=b(this),bB;if(this.nodeType!==1){return}if(by){bB=bx.call(this,bA,bz.val())}else{bB=bx}if(bB==null){bB=""}else{if(typeof bB==="number"){bB+=""}else{if(b.isArray(bB)){bB=b.map(bB,function(bC){return bC==null?"":bC+""})}}}e=b.valHooks[this.nodeName.toLowerCase()]||b.valHooks[this.type];if(!e||!("set" in e)||e.set(this,bB,"value")===L){this.value=bB}})}});b.extend({valHooks:{option:{get:function(e){var bv=e.attributes.value;return !bv||bv.specified?e.value:e.text}},select:{get:function(e){var bA,bv,bz,bx,by=e.selectedIndex,bB=[],bC=e.options,bw=e.type==="select-one";if(by<0){return null}bv=bw?by:0;bz=bw?by+1:bC.length;for(;bv=0});if(!e.length){bv.selectedIndex=-1}return e}}},attrFn:{val:true,css:true,html:true,text:true,data:true,width:true,height:true,offset:true},attr:function(bA,bx,bB,bz){var bw,e,by,bv=bA.nodeType;if(!bA||bv===3||bv===8||bv===2){return}if(bz&&bx in b.attrFn){return b(bA)[bx](bB)}if(typeof bA.getAttribute==="undefined"){return b.prop(bA,bx,bB)}by=bv!==1||!b.isXMLDoc(bA);if(by){bx=bx.toLowerCase();e=b.attrHooks[bx]||(ao.test(bx)?aY:be)}if(bB!==L){if(bB===null){b.removeAttr(bA,bx);return}else{if(e&&"set" in e&&by&&(bw=e.set(bA,bB,bx))!==L){return bw}else{bA.setAttribute(bx,""+bB);return bB}}}else{if(e&&"get" in e&&by&&(bw=e.get(bA,bx))!==null){return bw}else{bw=bA.getAttribute(bx);return bw===null?L:bw}}},removeAttr:function(bx,bz){var by,bA,bv,e,bw=0;if(bz&&bx.nodeType===1){bA=bz.toLowerCase().split(af);e=bA.length;for(;bw=0)}}})});var bd=/^(?:textarea|input|select)$/i,n=/^([^\.]*)?(?:\.(.+))?$/,J=/\bhover(\.\S+)?\b/,aO=/^key/,bf=/^(?:mouse|contextmenu)|click/,T=/^(?:focusinfocus|focusoutblur)$/,U=/^(\w*)(?:#([\w\-]+))?(?:\.([\w\-]+))?$/,Y=function(e){var bv=U.exec(e);if(bv){bv[1]=(bv[1]||"").toLowerCase();bv[3]=bv[3]&&new RegExp("(?:^|\\s)"+bv[3]+"(?:\\s|$)")}return bv},j=function(bw,e){var bv=bw.attributes||{};return((!e[1]||bw.nodeName.toLowerCase()===e[1])&&(!e[2]||(bv.id||{}).value===e[2])&&(!e[3]||e[3].test((bv["class"]||{}).value)))},bt=function(e){return b.event.special.hover?e:e.replace(J,"mouseenter$1 mouseleave$1")};b.event={add:function(bx,bC,bJ,bA,by){var bD,bB,bK,bI,bH,bF,e,bG,bv,bz,bw,bE;if(bx.nodeType===3||bx.nodeType===8||!bC||!bJ||!(bD=b._data(bx))){return}if(bJ.handler){bv=bJ;bJ=bv.handler}if(!bJ.guid){bJ.guid=b.guid++}bK=bD.events;if(!bK){bD.events=bK={}}bB=bD.handle;if(!bB){bD.handle=bB=function(bL){return typeof b!=="undefined"&&(!bL||b.event.triggered!==bL.type)?b.event.dispatch.apply(bB.elem,arguments):L};bB.elem=bx}bC=b.trim(bt(bC)).split(" ");for(bI=0;bI=0){bG=bG.slice(0,-1);bw=true}if(bG.indexOf(".")>=0){bx=bG.split(".");bG=bx.shift();bx.sort()}if((!bA||b.event.customEvent[bG])&&!b.event.global[bG]){return}bv=typeof bv==="object"?bv[b.expando]?bv:new b.Event(bG,bv):new b.Event(bG);bv.type=bG;bv.isTrigger=true;bv.exclusive=bw;bv.namespace=bx.join(".");bv.namespace_re=bv.namespace?new RegExp("(^|\\.)"+bx.join("\\.(?:.*\\.)?")+"(\\.|$)"):null;by=bG.indexOf(":")<0?"on"+bG:"";if(!bA){e=b.cache;for(bC in e){if(e[bC].events&&e[bC].events[bG]){b.event.trigger(bv,bD,e[bC].handle.elem,true)}}return}bv.result=L;if(!bv.target){bv.target=bA}bD=bD!=null?b.makeArray(bD):[];bD.unshift(bv);bF=b.event.special[bG]||{};if(bF.trigger&&bF.trigger.apply(bA,bD)===false){return}bB=[[bA,bF.bindType||bG]];if(!bJ&&!bF.noBubble&&!b.isWindow(bA)){bI=bF.delegateType||bG;bH=T.test(bI+bG)?bA:bA.parentNode;bz=null;for(;bH;bH=bH.parentNode){bB.push([bH,bI]);bz=bH}if(bz&&bz===bA.ownerDocument){bB.push([bz.defaultView||bz.parentWindow||bb,bI])}}for(bC=0;bCbA){bH.push({elem:this,matches:bz.slice(bA)})}for(bC=0;bC0?this.on(e,null,bx,bw):this.trigger(e)};if(b.attrFn){b.attrFn[e]=true}if(aO.test(e)){b.event.fixHooks[e]=b.event.keyHooks}if(bf.test(e)){b.event.fixHooks[e]=b.event.mouseHooks}}); -+ /*! -+ * Sizzle CSS Selector Engine -+ * Copyright 2011, The Dojo Foundation -+ * Released under the MIT, BSD, and GPL Licenses. -+ * More information: http://sizzlejs.com/ -+ */ -+ (function(){var bH=/((?:\((?:\([^()]+\)|[^()]+)+\)|\[(?:\[[^\[\]]*\]|['"][^'"]*['"]|[^\[\]'"]+)+\]|\\.|[^ >+~,(\[\\]+)+|[>+~])(\s*,\s*)?((?:.|\r|\n)*)/g,bC="sizcache"+(Math.random()+"").replace(".",""),bI=0,bL=Object.prototype.toString,bB=false,bA=true,bK=/\\/g,bO=/\r\n/g,bQ=/\W/;[0,0].sort(function(){bA=false;return 0});var by=function(bV,e,bY,bZ){bY=bY||[];e=e||av;var b1=e;if(e.nodeType!==1&&e.nodeType!==9){return[]}if(!bV||typeof bV!=="string"){return bY}var bS,b3,b6,bR,b2,b5,b4,bX,bU=true,bT=by.isXML(e),bW=[],b0=bV;do{bH.exec("");bS=bH.exec(b0);if(bS){b0=bS[3];bW.push(bS[1]);if(bS[2]){bR=bS[3];break}}}while(bS);if(bW.length>1&&bD.exec(bV)){if(bW.length===2&&bE.relative[bW[0]]){b3=bM(bW[0]+bW[1],e,bZ)}else{b3=bE.relative[bW[0]]?[e]:by(bW.shift(),e);while(bW.length){bV=bW.shift();if(bE.relative[bV]){bV+=bW.shift()}b3=bM(bV,b3,bZ)}}}else{if(!bZ&&bW.length>1&&e.nodeType===9&&!bT&&bE.match.ID.test(bW[0])&&!bE.match.ID.test(bW[bW.length-1])){b2=by.find(bW.shift(),e,bT);e=b2.expr?by.filter(b2.expr,b2.set)[0]:b2.set[0]}if(e){b2=bZ?{expr:bW.pop(),set:bF(bZ)}:by.find(bW.pop(),bW.length===1&&(bW[0]==="~"||bW[0]==="+")&&e.parentNode?e.parentNode:e,bT);b3=b2.expr?by.filter(b2.expr,b2.set):b2.set;if(bW.length>0){b6=bF(b3)}else{bU=false}while(bW.length){b5=bW.pop();b4=b5;if(!bE.relative[b5]){b5=""}else{b4=bW.pop()}if(b4==null){b4=e}bE.relative[b5](b6,b4,bT)}}else{b6=bW=[]}}if(!b6){b6=b3}if(!b6){by.error(b5||bV)}if(bL.call(b6)==="[object Array]"){if(!bU){bY.push.apply(bY,b6)}else{if(e&&e.nodeType===1){for(bX=0;b6[bX]!=null;bX++){if(b6[bX]&&(b6[bX]===true||b6[bX].nodeType===1&&by.contains(e,b6[bX]))){bY.push(b3[bX])}}}else{for(bX=0;b6[bX]!=null;bX++){if(b6[bX]&&b6[bX].nodeType===1){bY.push(b3[bX])}}}}}else{bF(b6,bY)}if(bR){by(bR,b1,bY,bZ);by.uniqueSort(bY)}return bY};by.uniqueSort=function(bR){if(bJ){bB=bA;bR.sort(bJ);if(bB){for(var e=1;e0};by.find=function(bX,e,bY){var bW,bS,bU,bT,bV,bR;if(!bX){return[]}for(bS=0,bU=bE.order.length;bS":function(bW,bR){var bV,bU=typeof bR==="string",bS=0,e=bW.length;if(bU&&!bQ.test(bR)){bR=bR.toLowerCase();for(;bS=0)){if(!bS){e.push(bV)}}else{if(bS){bR[bU]=false}}}}return false},ID:function(e){return e[1].replace(bK,"")},TAG:function(bR,e){return bR[1].replace(bK,"").toLowerCase()},CHILD:function(e){if(e[1]==="nth"){if(!e[2]){by.error(e[0])}e[2]=e[2].replace(/^\+|\s*/g,"");var bR=/(-?)(\d*)(?:n([+\-]?\d*))?/.exec(e[2]==="even"&&"2n"||e[2]==="odd"&&"2n+1"||!/\D/.test(e[2])&&"0n+"+e[2]||e[2]);e[2]=(bR[1]+(bR[2]||1))-0;e[3]=bR[3]-0}else{if(e[2]){by.error(e[0])}}e[0]=bI++;return e},ATTR:function(bU,bR,bS,e,bV,bW){var bT=bU[1]=bU[1].replace(bK,"");if(!bW&&bE.attrMap[bT]){bU[1]=bE.attrMap[bT]}bU[4]=(bU[4]||bU[5]||"").replace(bK,"");if(bU[2]==="~="){bU[4]=" "+bU[4]+" "}return bU},PSEUDO:function(bU,bR,bS,e,bV){if(bU[1]==="not"){if((bH.exec(bU[3])||"").length>1||/^\w/.test(bU[3])){bU[3]=by(bU[3],null,null,bR)}else{var bT=by.filter(bU[3],bR,bS,true^bV);if(!bS){e.push.apply(e,bT)}return false}}else{if(bE.match.POS.test(bU[0])||bE.match.CHILD.test(bU[0])){return true}}return bU},POS:function(e){e.unshift(true);return e}},filters:{enabled:function(e){return e.disabled===false&&e.type!=="hidden"},disabled:function(e){return e.disabled===true},checked:function(e){return e.checked===true},selected:function(e){if(e.parentNode){e.parentNode.selectedIndex}return e.selected===true},parent:function(e){return !!e.firstChild},empty:function(e){return !e.firstChild},has:function(bS,bR,e){return !!by(e[3],bS).length},header:function(e){return(/h\d/i).test(e.nodeName)},text:function(bS){var e=bS.getAttribute("type"),bR=bS.type;return bS.nodeName.toLowerCase()==="input"&&"text"===bR&&(e===bR||e===null)},radio:function(e){return e.nodeName.toLowerCase()==="input"&&"radio"===e.type},checkbox:function(e){return e.nodeName.toLowerCase()==="input"&&"checkbox"===e.type},file:function(e){return e.nodeName.toLowerCase()==="input"&&"file"===e.type},password:function(e){return e.nodeName.toLowerCase()==="input"&&"password"===e.type},submit:function(bR){var e=bR.nodeName.toLowerCase();return(e==="input"||e==="button")&&"submit"===bR.type},image:function(e){return e.nodeName.toLowerCase()==="input"&&"image"===e.type},reset:function(bR){var e=bR.nodeName.toLowerCase();return(e==="input"||e==="button")&&"reset"===bR.type},button:function(bR){var e=bR.nodeName.toLowerCase();return e==="input"&&"button"===bR.type||e==="button"},input:function(e){return(/input|select|textarea|button/i).test(e.nodeName)},focus:function(e){return e===e.ownerDocument.activeElement}},setFilters:{first:function(bR,e){return e===0},last:function(bS,bR,e,bT){return bR===bT.length-1},even:function(bR,e){return e%2===0},odd:function(bR,e){return e%2===1},lt:function(bS,bR,e){return bRe[3]-0},nth:function(bS,bR,e){return e[3]-0===bR},eq:function(bS,bR,e){return e[3]-0===bR}},filter:{PSEUDO:function(bS,bX,bW,bY){var e=bX[1],bR=bE.filters[e];if(bR){return bR(bS,bW,bX,bY)}else{if(e==="contains"){return(bS.textContent||bS.innerText||bw([bS])||"").indexOf(bX[3])>=0}else{if(e==="not"){var bT=bX[3];for(var bV=0,bU=bT.length;bV=0)}}},ID:function(bR,e){return bR.nodeType===1&&bR.getAttribute("id")===e},TAG:function(bR,e){return(e==="*"&&bR.nodeType===1)||!!bR.nodeName&&bR.nodeName.toLowerCase()===e},CLASS:function(bR,e){return(" "+(bR.className||bR.getAttribute("class"))+" ").indexOf(e)>-1},ATTR:function(bV,bT){var bS=bT[1],e=by.attr?by.attr(bV,bS):bE.attrHandle[bS]?bE.attrHandle[bS](bV):bV[bS]!=null?bV[bS]:bV.getAttribute(bS),bW=e+"",bU=bT[2],bR=bT[4];return e==null?bU==="!=":!bU&&by.attr?e!=null:bU==="="?bW===bR:bU==="*="?bW.indexOf(bR)>=0:bU==="~="?(" "+bW+" ").indexOf(bR)>=0:!bR?bW&&e!==false:bU==="!="?bW!==bR:bU==="^="?bW.indexOf(bR)===0:bU==="$="?bW.substr(bW.length-bR.length)===bR:bU==="|="?bW===bR||bW.substr(0,bR.length+1)===bR+"-":false},POS:function(bU,bR,bS,bV){var e=bR[2],bT=bE.setFilters[e];if(bT){return bT(bU,bS,bR,bV)}}}};var bD=bE.match.POS,bx=function(bR,e){return"\\"+(e-0+1)};for(var bz in bE.match){bE.match[bz]=new RegExp(bE.match[bz].source+(/(?![^\[]*\])(?![^\(]*\))/.source));bE.leftMatch[bz]=new RegExp(/(^(?:.|\r|\n)*?)/.source+bE.match[bz].source.replace(/\\(\d+)/g,bx))}var bF=function(bR,e){bR=Array.prototype.slice.call(bR,0);if(e){e.push.apply(e,bR);return e}return bR};try{Array.prototype.slice.call(av.documentElement.childNodes,0)[0].nodeType}catch(bP){bF=function(bU,bT){var bS=0,bR=bT||[];if(bL.call(bU)==="[object Array]"){Array.prototype.push.apply(bR,bU)}else{if(typeof bU.length==="number"){for(var e=bU.length;bS";e.insertBefore(bR,e.firstChild);if(av.getElementById(bS)){bE.find.ID=function(bU,bV,bW){if(typeof bV.getElementById!=="undefined"&&!bW){var bT=bV.getElementById(bU[1]);return bT?bT.id===bU[1]||typeof bT.getAttributeNode!=="undefined"&&bT.getAttributeNode("id").nodeValue===bU[1]?[bT]:L:[]}};bE.filter.ID=function(bV,bT){var bU=typeof bV.getAttributeNode!=="undefined"&&bV.getAttributeNode("id");return bV.nodeType===1&&bU&&bU.nodeValue===bT}}e.removeChild(bR);e=bR=null})();(function(){var e=av.createElement("div");e.appendChild(av.createComment(""));if(e.getElementsByTagName("*").length>0){bE.find.TAG=function(bR,bV){var bU=bV.getElementsByTagName(bR[1]);if(bR[1]==="*"){var bT=[];for(var bS=0;bU[bS];bS++){if(bU[bS].nodeType===1){bT.push(bU[bS])}}bU=bT}return bU}}e.innerHTML="";if(e.firstChild&&typeof e.firstChild.getAttribute!=="undefined"&&e.firstChild.getAttribute("href")!=="#"){bE.attrHandle.href=function(bR){return bR.getAttribute("href",2)}}e=null})();if(av.querySelectorAll){(function(){var e=by,bT=av.createElement("div"),bS="__sizzle__";bT.innerHTML="

";if(bT.querySelectorAll&&bT.querySelectorAll(".TEST").length===0){return}by=function(b4,bV,bZ,b3){bV=bV||av;if(!b3&&!by.isXML(bV)){var b2=/^(\w+$)|^\.([\w\-]+$)|^#([\w\-]+$)/.exec(b4);if(b2&&(bV.nodeType===1||bV.nodeType===9)){if(b2[1]){return bF(bV.getElementsByTagName(b4),bZ)}else{if(b2[2]&&bE.find.CLASS&&bV.getElementsByClassName){return bF(bV.getElementsByClassName(b2[2]),bZ)}}}if(bV.nodeType===9){if(b4==="body"&&bV.body){return bF([bV.body],bZ)}else{if(b2&&b2[3]){var bY=bV.getElementById(b2[3]);if(bY&&bY.parentNode){if(bY.id===b2[3]){return bF([bY],bZ)}}else{return bF([],bZ)}}}try{return bF(bV.querySelectorAll(b4),bZ)}catch(b0){}}else{if(bV.nodeType===1&&bV.nodeName.toLowerCase()!=="object"){var bW=bV,bX=bV.getAttribute("id"),bU=bX||bS,b6=bV.parentNode,b5=/^\s*[+~]/.test(b4);if(!bX){bV.setAttribute("id",bU)}else{bU=bU.replace(/'/g,"\\$&")}if(b5&&b6){bV=bV.parentNode}try{if(!b5||b6){return bF(bV.querySelectorAll("[id='"+bU+"'] "+b4),bZ)}}catch(b1){}finally{if(!bX){bW.removeAttribute("id")}}}}}return e(b4,bV,bZ,b3)};for(var bR in e){by[bR]=e[bR]}bT=null})()}(function(){var e=av.documentElement,bS=e.matchesSelector||e.mozMatchesSelector||e.webkitMatchesSelector||e.msMatchesSelector;if(bS){var bU=!bS.call(av.createElement("div"),"div"),bR=false;try{bS.call(av.documentElement,"[test!='']:sizzle")}catch(bT){bR=true}by.matchesSelector=function(bW,bY){bY=bY.replace(/\=\s*([^'"\]]*)\s*\]/g,"='$1']");if(!by.isXML(bW)){try{if(bR||!bE.match.PSEUDO.test(bY)&&!/!=/.test(bY)){var bV=bS.call(bW,bY);if(bV||!bU||bW.document&&bW.document.nodeType!==11){return bV}}}catch(bX){}}return by(bY,null,null,[bW]).length>0}}})();(function(){var e=av.createElement("div");e.innerHTML="
";if(!e.getElementsByClassName||e.getElementsByClassName("e").length===0){return}e.lastChild.className="e";if(e.getElementsByClassName("e").length===1){return}bE.order.splice(1,0,"CLASS");bE.find.CLASS=function(bR,bS,bT){if(typeof bS.getElementsByClassName!=="undefined"&&!bT){return bS.getElementsByClassName(bR[1])}};e=null})();function bv(bR,bW,bV,bZ,bX,bY){for(var bT=0,bS=bZ.length;bT0){bU=e;break}}}e=e[bR]}bZ[bT]=bU}}}if(av.documentElement.contains){by.contains=function(bR,e){return bR!==e&&(bR.contains?bR.contains(e):true)}}else{if(av.documentElement.compareDocumentPosition){by.contains=function(bR,e){return !!(bR.compareDocumentPosition(e)&16)}}else{by.contains=function(){return false}}}by.isXML=function(e){var bR=(e?e.ownerDocument||e:0).documentElement;return bR?bR.nodeName!=="HTML":false};var bM=function(bS,e,bW){var bV,bX=[],bU="",bY=e.nodeType?[e]:e;while((bV=bE.match.PSEUDO.exec(bS))){bU+=bV[0];bS=bS.replace(bE.match.PSEUDO,"")}bS=bE.relative[bS]?bS+"*":bS;for(var bT=0,bR=bY.length;bT0){for(bB=bA;bB=0:b.filter(e,this).length>0:this.filter(e).length>0)},closest:function(by,bx){var bv=[],bw,e,bz=this[0];if(b.isArray(by)){var bB=1;while(bz&&bz.ownerDocument&&bz!==bx){for(bw=0;bw-1:b.find.matchesSelector(bz,by)){bv.push(bz);break}else{bz=bz.parentNode;if(!bz||!bz.ownerDocument||bz===bx||bz.nodeType===11){break}}}}bv=bv.length>1?b.unique(bv):bv;return this.pushStack(bv,"closest",by)},index:function(e){if(!e){return(this[0]&&this[0].parentNode)?this.prevAll().length:-1}if(typeof e==="string"){return b.inArray(this[0],b(e))}return b.inArray(e.jquery?e[0]:e,this)},add:function(e,bv){var bx=typeof e==="string"?b(e,bv):b.makeArray(e&&e.nodeType?[e]:e),bw=b.merge(this.get(),bx);return this.pushStack(C(bx[0])||C(bw[0])?bw:b.unique(bw))},andSelf:function(){return this.add(this.prevObject)}});function C(e){return !e||!e.parentNode||e.parentNode.nodeType===11}b.each({parent:function(bv){var e=bv.parentNode;return e&&e.nodeType!==11?e:null},parents:function(e){return b.dir(e,"parentNode")},parentsUntil:function(bv,e,bw){return b.dir(bv,"parentNode",bw)},next:function(e){return b.nth(e,2,"nextSibling")},prev:function(e){return b.nth(e,2,"previousSibling")},nextAll:function(e){return b.dir(e,"nextSibling")},prevAll:function(e){return b.dir(e,"previousSibling")},nextUntil:function(bv,e,bw){return b.dir(bv,"nextSibling",bw)},prevUntil:function(bv,e,bw){return b.dir(bv,"previousSibling",bw)},siblings:function(e){return b.sibling(e.parentNode.firstChild,e)},children:function(e){return b.sibling(e.firstChild)},contents:function(e){return b.nodeName(e,"iframe")?e.contentDocument||e.contentWindow.document:b.makeArray(e.childNodes)}},function(e,bv){b.fn[e]=function(by,bw){var bx=b.map(this,bv,by);if(!ab.test(e)){bw=by}if(bw&&typeof bw==="string"){bx=b.filter(bw,bx)}bx=this.length>1&&!ay[e]?b.unique(bx):bx;if((this.length>1||a9.test(bw))&&aq.test(e)){bx=bx.reverse()}return this.pushStack(bx,e,P.call(arguments).join(","))}});b.extend({filter:function(bw,e,bv){if(bv){bw=":not("+bw+")"}return e.length===1?b.find.matchesSelector(e[0],bw)?[e[0]]:[]:b.find.matches(bw,e)},dir:function(bw,bv,by){var e=[],bx=bw[bv];while(bx&&bx.nodeType!==9&&(by===L||bx.nodeType!==1||!b(bx).is(by))){if(bx.nodeType===1){e.push(bx)}bx=bx[bv]}return e},nth:function(by,e,bw,bx){e=e||1;var bv=0;for(;by;by=by[bw]){if(by.nodeType===1&&++bv===e){break}}return by},sibling:function(bw,bv){var e=[];for(;bw;bw=bw.nextSibling){if(bw.nodeType===1&&bw!==bv){e.push(bw)}}return e}});function aG(bx,bw,e){bw=bw||0;if(b.isFunction(bw)){return b.grep(bx,function(bz,by){var bA=!!bw.call(bz,by,bz);return bA===e})}else{if(bw.nodeType){return b.grep(bx,function(bz,by){return(bz===bw)===e})}else{if(typeof bw==="string"){var bv=b.grep(bx,function(by){return by.nodeType===1});if(bp.test(bw)){return b.filter(bw,bv,!e)}else{bw=b.filter(bw,bv)}}}}return b.grep(bx,function(bz,by){return(b.inArray(bz,bw)>=0)===e})}function a(e){var bw=aR.split("|"),bv=e.createDocumentFragment();if(bv.createElement){while(bw.length){bv.createElement(bw.pop())}}return bv}var aR="abbr|article|aside|audio|canvas|datalist|details|figcaption|figure|footer|header|hgroup|mark|meter|nav|output|progress|section|summary|time|video",ag=/ jQuery\d+="(?:\d+|null)"/g,ar=/^\s+/,R=/<(?!area|br|col|embed|hr|img|input|link|meta|param)(([\w:]+)[^>]*)\/>/ig,d=/<([\w:]+)/,w=/",""],legend:[1,"
","
"],thead:[1,"","
"],tr:[2,"","
"],td:[3,"","
"],col:[2,"","
"],area:[1,"",""],_default:[0,"",""]},ac=a(av);ax.optgroup=ax.option;ax.tbody=ax.tfoot=ax.colgroup=ax.caption=ax.thead;ax.th=ax.td;if(!b.support.htmlSerialize){ax._default=[1,"div
","
"]}b.fn.extend({text:function(e){if(b.isFunction(e)){return this.each(function(bw){var bv=b(this);bv.text(e.call(this,bw,bv.text()))})}if(typeof e!=="object"&&e!==L){return this.empty().append((this[0]&&this[0].ownerDocument||av).createTextNode(e))}return b.text(this)},wrapAll:function(e){if(b.isFunction(e)){return this.each(function(bw){b(this).wrapAll(e.call(this,bw))})}if(this[0]){var bv=b(e,this[0].ownerDocument).eq(0).clone(true);if(this[0].parentNode){bv.insertBefore(this[0])}bv.map(function(){var bw=this;while(bw.firstChild&&bw.firstChild.nodeType===1){bw=bw.firstChild}return bw}).append(this)}return this},wrapInner:function(e){if(b.isFunction(e)){return this.each(function(bv){b(this).wrapInner(e.call(this,bv))})}return this.each(function(){var bv=b(this),bw=bv.contents();if(bw.length){bw.wrapAll(e)}else{bv.append(e)}})},wrap:function(e){var bv=b.isFunction(e);return this.each(function(bw){b(this).wrapAll(bv?e.call(this,bw):e)})},unwrap:function(){return this.parent().each(function(){if(!b.nodeName(this,"body")){b(this).replaceWith(this.childNodes)}}).end()},append:function(){return this.domManip(arguments,true,function(e){if(this.nodeType===1){this.appendChild(e)}})},prepend:function(){return this.domManip(arguments,true,function(e){if(this.nodeType===1){this.insertBefore(e,this.firstChild)}})},before:function(){if(this[0]&&this[0].parentNode){return this.domManip(arguments,false,function(bv){this.parentNode.insertBefore(bv,this)})}else{if(arguments.length){var e=b.clean(arguments);e.push.apply(e,this.toArray());return this.pushStack(e,"before",arguments)}}},after:function(){if(this[0]&&this[0].parentNode){return this.domManip(arguments,false,function(bv){this.parentNode.insertBefore(bv,this.nextSibling)})}else{if(arguments.length){var e=this.pushStack(this,"after",arguments);e.push.apply(e,b.clean(arguments));return e}}},remove:function(e,bx){for(var bv=0,bw;(bw=this[bv])!=null;bv++){if(!e||b.filter(e,[bw]).length){if(!bx&&bw.nodeType===1){b.cleanData(bw.getElementsByTagName("*"));b.cleanData([bw])}if(bw.parentNode){bw.parentNode.removeChild(bw)}}}return this},empty:function(){for(var e=0,bv;(bv=this[e])!=null;e++){if(bv.nodeType===1){b.cleanData(bv.getElementsByTagName("*"))}while(bv.firstChild){bv.removeChild(bv.firstChild)}}return this},clone:function(bv,e){bv=bv==null?false:bv;e=e==null?bv:e;return this.map(function(){return b.clone(this,bv,e)})},html:function(bx){if(bx===L){return this[0]&&this[0].nodeType===1?this[0].innerHTML.replace(ag,""):null}else{if(typeof bx==="string"&&!ae.test(bx)&&(b.support.leadingWhitespace||!ar.test(bx))&&!ax[(d.exec(bx)||["",""])[1].toLowerCase()]){bx=bx.replace(R,"<$1>");try{for(var bw=0,bv=this.length;bw1&&bw0?this.clone(true):this).get();b(bC[bA])[bv](by);bz=bz.concat(by)}return this.pushStack(bz,e,bC.selector)}}});function bg(e){if(typeof e.getElementsByTagName!=="undefined"){return e.getElementsByTagName("*")}else{if(typeof e.querySelectorAll!=="undefined"){return e.querySelectorAll("*")}else{return[]}}}function az(e){if(e.type==="checkbox"||e.type==="radio"){e.defaultChecked=e.checked}}function E(e){var bv=(e.nodeName||"").toLowerCase();if(bv==="input"){az(e)}else{if(bv!=="script"&&typeof e.getElementsByTagName!=="undefined"){b.grep(e.getElementsByTagName("input"),az)}}}function al(e){var bv=av.createElement("div");ac.appendChild(bv);bv.innerHTML=e.outerHTML;return bv.firstChild}b.extend({clone:function(by,bA,bw){var e,bv,bx,bz=b.support.html5Clone||!ah.test("<"+by.nodeName)?by.cloneNode(true):al(by);if((!b.support.noCloneEvent||!b.support.noCloneChecked)&&(by.nodeType===1||by.nodeType===11)&&!b.isXMLDoc(by)){ai(by,bz);e=bg(by);bv=bg(bz);for(bx=0;e[bx];++bx){if(bv[bx]){ai(e[bx],bv[bx])}}}if(bA){t(by,bz);if(bw){e=bg(by);bv=bg(bz);for(bx=0;e[bx];++bx){t(e[bx],bv[bx])}}}e=bv=null;return bz},clean:function(bw,by,bH,bA){var bF;by=by||av;if(typeof by.createElement==="undefined"){by=by.ownerDocument||by[0]&&by[0].ownerDocument||av}var bI=[],bB;for(var bE=0,bz;(bz=bw[bE])!=null;bE++){if(typeof bz==="number"){bz+=""}if(!bz){continue}if(typeof bz==="string"){if(!W.test(bz)){bz=by.createTextNode(bz)}else{bz=bz.replace(R,"<$1>");var bK=(d.exec(bz)||["",""])[1].toLowerCase(),bx=ax[bK]||ax._default,bD=bx[0],bv=by.createElement("div");if(by===av){ac.appendChild(bv)}else{a(by).appendChild(bv)}bv.innerHTML=bx[1]+bz+bx[2];while(bD--){bv=bv.lastChild}if(!b.support.tbody){var e=w.test(bz),bC=bK==="table"&&!e?bv.firstChild&&bv.firstChild.childNodes:bx[1]===""&&!e?bv.childNodes:[];for(bB=bC.length-1;bB>=0;--bB){if(b.nodeName(bC[bB],"tbody")&&!bC[bB].childNodes.length){bC[bB].parentNode.removeChild(bC[bB])}}}if(!b.support.leadingWhitespace&&ar.test(bz)){bv.insertBefore(by.createTextNode(ar.exec(bz)[0]),bv.firstChild)}bz=bv.childNodes}}var bG;if(!b.support.appendChecked){if(bz[0]&&typeof(bG=bz.length)==="number"){for(bB=0;bB=0){return bx+"px"}}else{return bx}}}});if(!b.support.opacity){b.cssHooks.opacity={get:function(bv,e){return au.test((e&&bv.currentStyle?bv.currentStyle.filter:bv.style.filter)||"")?(parseFloat(RegExp.$1)/100)+"":e?"1":""},set:function(by,bz){var bx=by.style,bv=by.currentStyle,e=b.isNumeric(bz)?"alpha(opacity="+bz*100+")":"",bw=bv&&bv.filter||bx.filter||"";bx.zoom=1;if(bz>=1&&b.trim(bw.replace(ak,""))===""){bx.removeAttribute("filter");if(bv&&!bv.filter){return}}bx.filter=ak.test(bw)?bw.replace(ak,e):bw+" "+e}}}b(function(){if(!b.support.reliableMarginRight){b.cssHooks.marginRight={get:function(bw,bv){var e;b.swap(bw,{display:"inline-block"},function(){if(bv){e=Z(bw,"margin-right","marginRight")}else{e=bw.style.marginRight}});return e}}}});if(av.defaultView&&av.defaultView.getComputedStyle){aI=function(by,bw){var bv,bx,e;bw=bw.replace(z,"-$1").toLowerCase();if((bx=by.ownerDocument.defaultView)&&(e=bx.getComputedStyle(by,null))){bv=e.getPropertyValue(bw);if(bv===""&&!b.contains(by.ownerDocument.documentElement,by)){bv=b.style(by,bw)}}return bv}}if(av.documentElement.currentStyle){aX=function(bz,bw){var bA,e,by,bv=bz.currentStyle&&bz.currentStyle[bw],bx=bz.style;if(bv===null&&bx&&(by=bx[bw])){bv=by}if(!bc.test(bv)&&bn.test(bv)){bA=bx.left;e=bz.runtimeStyle&&bz.runtimeStyle.left;if(e){bz.runtimeStyle.left=bz.currentStyle.left}bx.left=bw==="fontSize"?"1em":(bv||0);bv=bx.pixelLeft+"px";bx.left=bA;if(e){bz.runtimeStyle.left=e}}return bv===""?"auto":bv}}Z=aI||aX;function p(by,bw,bv){var bA=bw==="width"?by.offsetWidth:by.offsetHeight,bz=bw==="width"?an:a1,bx=0,e=bz.length;if(bA>0){if(bv!=="border"){for(;bx)<[^<]*)*<\/script>/gi,q=/^(?:select|textarea)/i,h=/\s+/,br=/([?&])_=[^&]*/,K=/^([\w\+\.\-]+:)(?:\/\/([^\/?#:]*)(?::(\d+))?)?/,A=b.fn.load,aa={},r={},aE,s,aV=["*/"]+["*"];try{aE=bl.href}catch(aw){aE=av.createElement("a");aE.href="";aE=aE.href}s=K.exec(aE.toLowerCase())||[];function f(e){return function(by,bA){if(typeof by!=="string"){bA=by;by="*"}if(b.isFunction(bA)){var bx=by.toLowerCase().split(h),bw=0,bz=bx.length,bv,bB,bC;for(;bw=0){var e=bw.slice(by,bw.length);bw=bw.slice(0,by)}var bx="GET";if(bz){if(b.isFunction(bz)){bA=bz;bz=L}else{if(typeof bz==="object"){bz=b.param(bz,b.ajaxSettings.traditional);bx="POST"}}}var bv=this;b.ajax({url:bw,type:bx,dataType:"html",data:bz,complete:function(bC,bB,bD){bD=bC.responseText;if(bC.isResolved()){bC.done(function(bE){bD=bE});bv.html(e?b("
").append(bD.replace(a6,"")).find(e):bD)}if(bA){bv.each(bA,[bD,bB,bC])}}});return this},serialize:function(){return b.param(this.serializeArray())},serializeArray:function(){return this.map(function(){return this.elements?b.makeArray(this.elements):this}).filter(function(){return this.name&&!this.disabled&&(this.checked||q.test(this.nodeName)||aZ.test(this.type))}).map(function(e,bv){var bw=b(this).val();return bw==null?null:b.isArray(bw)?b.map(bw,function(by,bx){return{name:bv.name,value:by.replace(bs,"\r\n")}}):{name:bv.name,value:bw.replace(bs,"\r\n")}}).get()}});b.each("ajaxStart ajaxStop ajaxComplete ajaxError ajaxSuccess ajaxSend".split(" "),function(e,bv){b.fn[bv]=function(bw){return this.on(bv,bw)}});b.each(["get","post"],function(e,bv){b[bv]=function(bw,by,bz,bx){if(b.isFunction(by)){bx=bx||bz;bz=by;by=L}return b.ajax({type:bv,url:bw,data:by,success:bz,dataType:bx})}});b.extend({getScript:function(e,bv){return b.get(e,L,bv,"script")},getJSON:function(e,bv,bw){return b.get(e,bv,bw,"json")},ajaxSetup:function(bv,e){if(e){am(bv,b.ajaxSettings)}else{e=bv;bv=b.ajaxSettings}am(bv,e);return bv},ajaxSettings:{url:aE,isLocal:aM.test(s[1]),global:true,type:"GET",contentType:"application/x-www-form-urlencoded",processData:true,async:true,accepts:{xml:"application/xml, text/xml",html:"text/html",text:"text/plain",json:"application/json, text/javascript","*":aV},contents:{xml:/xml/,html:/html/,json:/json/},responseFields:{xml:"responseXML",text:"responseText"},converters:{"* text":bb.String,"text html":true,"text json":b.parseJSON,"text xml":b.parseXML},flatOptions:{context:true,url:true}},ajaxPrefilter:f(aa),ajaxTransport:f(r),ajax:function(bz,bx){if(typeof bz==="object"){bx=bz;bz=L}bx=bx||{};var bD=b.ajaxSetup({},bx),bS=bD.context||bD,bG=bS!==bD&&(bS.nodeType||bS instanceof b)?b(bS):b.event,bR=b.Deferred(),bN=b.Callbacks("once memory"),bB=bD.statusCode||{},bC,bH={},bO={},bQ,by,bL,bE,bI,bA=0,bw,bK,bJ={readyState:0,setRequestHeader:function(bT,bU){if(!bA){var e=bT.toLowerCase();bT=bO[e]=bO[e]||bT;bH[bT]=bU}return this},getAllResponseHeaders:function(){return bA===2?bQ:null},getResponseHeader:function(bT){var e;if(bA===2){if(!by){by={};while((e=aD.exec(bQ))){by[e[1].toLowerCase()]=e[2]}}e=by[bT.toLowerCase()]}return e===L?null:e},overrideMimeType:function(e){if(!bA){bD.mimeType=e}return this},abort:function(e){e=e||"abort";if(bL){bL.abort(e)}bF(0,e);return this}};function bF(bZ,bU,b0,bW){if(bA===2){return}bA=2;if(bE){clearTimeout(bE)}bL=L;bQ=bW||"";bJ.readyState=bZ>0?4:0;var bT,b4,b3,bX=bU,bY=b0?bj(bD,bJ,b0):L,bV,b2;if(bZ>=200&&bZ<300||bZ===304){if(bD.ifModified){if((bV=bJ.getResponseHeader("Last-Modified"))){b.lastModified[bC]=bV}if((b2=bJ.getResponseHeader("Etag"))){b.etag[bC]=b2}}if(bZ===304){bX="notmodified";bT=true}else{try{b4=G(bD,bY);bX="success";bT=true}catch(b1){bX="parsererror";b3=b1}}}else{b3=bX;if(!bX||bZ){bX="error";if(bZ<0){bZ=0}}}bJ.status=bZ;bJ.statusText=""+(bU||bX);if(bT){bR.resolveWith(bS,[b4,bX,bJ])}else{bR.rejectWith(bS,[bJ,bX,b3])}bJ.statusCode(bB);bB=L;if(bw){bG.trigger("ajax"+(bT?"Success":"Error"),[bJ,bD,bT?b4:b3])}bN.fireWith(bS,[bJ,bX]);if(bw){bG.trigger("ajaxComplete",[bJ,bD]);if(!(--b.active)){b.event.trigger("ajaxStop")}}}bR.promise(bJ);bJ.success=bJ.done;bJ.error=bJ.fail;bJ.complete=bN.add;bJ.statusCode=function(bT){if(bT){var e;if(bA<2){for(e in bT){bB[e]=[bB[e],bT[e]]}}else{e=bT[bJ.status];bJ.then(e,e)}}return this};bD.url=((bz||bD.url)+"").replace(bq,"").replace(c,s[1]+"//");bD.dataTypes=b.trim(bD.dataType||"*").toLowerCase().split(h);if(bD.crossDomain==null){bI=K.exec(bD.url.toLowerCase());bD.crossDomain=!!(bI&&(bI[1]!=s[1]||bI[2]!=s[2]||(bI[3]||(bI[1]==="http:"?80:443))!=(s[3]||(s[1]==="http:"?80:443))))}if(bD.data&&bD.processData&&typeof bD.data!=="string"){bD.data=b.param(bD.data,bD.traditional)}aW(aa,bD,bx,bJ);if(bA===2){return false}bw=bD.global;bD.type=bD.type.toUpperCase();bD.hasContent=!aQ.test(bD.type);if(bw&&b.active++===0){b.event.trigger("ajaxStart")}if(!bD.hasContent){if(bD.data){bD.url+=(M.test(bD.url)?"&":"?")+bD.data;delete bD.data}bC=bD.url;if(bD.cache===false){var bv=b.now(),bP=bD.url.replace(br,"$1_="+bv);bD.url=bP+((bP===bD.url)?(M.test(bD.url)?"&":"?")+"_="+bv:"")}}if(bD.data&&bD.hasContent&&bD.contentType!==false||bx.contentType){bJ.setRequestHeader("Content-Type",bD.contentType)}if(bD.ifModified){bC=bC||bD.url;if(b.lastModified[bC]){bJ.setRequestHeader("If-Modified-Since",b.lastModified[bC])}if(b.etag[bC]){bJ.setRequestHeader("If-None-Match",b.etag[bC])}}bJ.setRequestHeader("Accept",bD.dataTypes[0]&&bD.accepts[bD.dataTypes[0]]?bD.accepts[bD.dataTypes[0]]+(bD.dataTypes[0]!=="*"?", "+aV+"; q=0.01":""):bD.accepts["*"]);for(bK in bD.headers){bJ.setRequestHeader(bK,bD.headers[bK])}if(bD.beforeSend&&(bD.beforeSend.call(bS,bJ,bD)===false||bA===2)){bJ.abort();return false}for(bK in {success:1,error:1,complete:1}){bJ[bK](bD[bK])}bL=aW(r,bD,bx,bJ);if(!bL){bF(-1,"No Transport")}else{bJ.readyState=1;if(bw){bG.trigger("ajaxSend",[bJ,bD])}if(bD.async&&bD.timeout>0){bE=setTimeout(function(){bJ.abort("timeout")},bD.timeout)}try{bA=1;bL.send(bH,bF)}catch(bM){if(bA<2){bF(-1,bM)}else{throw bM}}}return bJ},param:function(e,bw){var bv=[],by=function(bz,bA){bA=b.isFunction(bA)?bA():bA;bv[bv.length]=encodeURIComponent(bz)+"="+encodeURIComponent(bA)};if(bw===L){bw=b.ajaxSettings.traditional}if(b.isArray(e)||(e.jquery&&!b.isPlainObject(e))){b.each(e,function(){by(this.name,this.value)})}else{for(var bx in e){v(bx,e[bx],bw,by)}}return bv.join("&").replace(k,"+")}});function v(bw,by,bv,bx){if(b.isArray(by)){b.each(by,function(bA,bz){if(bv||ap.test(bw)){bx(bw,bz)}else{v(bw+"["+(typeof bz==="object"||b.isArray(bz)?bA:"")+"]",bz,bv,bx)}})}else{if(!bv&&by!=null&&typeof by==="object"){for(var e in by){v(bw+"["+e+"]",by[e],bv,bx)}}else{bx(bw,by)}}}b.extend({active:0,lastModified:{},etag:{}});function bj(bD,bC,bz){var bv=bD.contents,bB=bD.dataTypes,bw=bD.responseFields,by,bA,bx,e;for(bA in bw){if(bA in bz){bC[bw[bA]]=bz[bA]}}while(bB[0]==="*"){bB.shift();if(by===L){by=bD.mimeType||bC.getResponseHeader("content-type")}}if(by){for(bA in bv){if(bv[bA]&&bv[bA].test(by)){bB.unshift(bA);break}}}if(bB[0] in bz){bx=bB[0]}else{for(bA in bz){if(!bB[0]||bD.converters[bA+" "+bB[0]]){bx=bA;break}if(!e){e=bA}}bx=bx||e}if(bx){if(bx!==bB[0]){bB.unshift(bx)}return bz[bx]}}function G(bH,bz){if(bH.dataFilter){bz=bH.dataFilter(bz,bH.dataType)}var bD=bH.dataTypes,bG={},bA,bE,bw=bD.length,bB,bC=bD[0],bx,by,bF,bv,e;for(bA=1;bA=bw.duration+this.startTime){this.now=this.end;this.pos=this.state=1;this.update();bw.animatedProperties[this.prop]=true;for(bA in bw.animatedProperties){if(bw.animatedProperties[bA]!==true){e=false}}if(e){if(bw.overflow!=null&&!b.support.shrinkWrapBlocks){b.each(["","X","Y"],function(bC,bD){bz.style["overflow"+bD]=bw.overflow[bC]})}if(bw.hide){b(bz).hide()}if(bw.hide||bw.show){for(bA in bw.animatedProperties){b.style(bz,bA,bw.orig[bA]);b.removeData(bz,"fxshow"+bA,true);b.removeData(bz,"toggle"+bA,true)}}bv=bw.complete;if(bv){bw.complete=false;bv.call(bz)}}return false}else{if(bw.duration==Infinity){this.now=bx}else{bB=bx-this.startTime;this.state=bB/bw.duration;this.pos=b.easing[bw.animatedProperties[this.prop]](this.state,bB,0,1,bw.duration);this.now=this.start+((this.end-this.start)*this.pos)}this.update()}return true}};b.extend(b.fx,{tick:function(){var bw,bv=b.timers,e=0;for(;e").appendTo(e),bw=bv.css("display");bv.remove();if(bw==="none"||bw===""){if(!a8){a8=av.createElement("iframe");a8.frameBorder=a8.width=a8.height=0}e.appendChild(a8);if(!m||!a8.createElement){m=(a8.contentWindow||a8.contentDocument).document;m.write((av.compatMode==="CSS1Compat"?"":"")+"");m.close()}bv=m.createElement(bx);m.body.appendChild(bv);bw=b.css(bv,"display");e.removeChild(a8)}Q[bx]=bw}return Q[bx]}var V=/^t(?:able|d|h)$/i,ad=/^(?:body|html)$/i;if("getBoundingClientRect" in av.documentElement){b.fn.offset=function(bI){var by=this[0],bB;if(bI){return this.each(function(e){b.offset.setOffset(this,bI,e)})}if(!by||!by.ownerDocument){return null}if(by===by.ownerDocument.body){return b.offset.bodyOffset(by)}try{bB=by.getBoundingClientRect()}catch(bF){}var bH=by.ownerDocument,bw=bH.documentElement;if(!bB||!b.contains(bw,by)){return bB?{top:bB.top,left:bB.left}:{top:0,left:0}}var bC=bH.body,bD=aK(bH),bA=bw.clientTop||bC.clientTop||0,bE=bw.clientLeft||bC.clientLeft||0,bv=bD.pageYOffset||b.support.boxModel&&bw.scrollTop||bC.scrollTop,bz=bD.pageXOffset||b.support.boxModel&&bw.scrollLeft||bC.scrollLeft,bG=bB.top+bv-bA,bx=bB.left+bz-bE;return{top:bG,left:bx}}}else{b.fn.offset=function(bF){var bz=this[0];if(bF){return this.each(function(bG){b.offset.setOffset(this,bF,bG)})}if(!bz||!bz.ownerDocument){return null}if(bz===bz.ownerDocument.body){return b.offset.bodyOffset(bz)}var bC,bw=bz.offsetParent,bv=bz,bE=bz.ownerDocument,bx=bE.documentElement,bA=bE.body,bB=bE.defaultView,e=bB?bB.getComputedStyle(bz,null):bz.currentStyle,bD=bz.offsetTop,by=bz.offsetLeft;while((bz=bz.parentNode)&&bz!==bA&&bz!==bx){if(b.support.fixedPosition&&e.position==="fixed"){break}bC=bB?bB.getComputedStyle(bz,null):bz.currentStyle;bD-=bz.scrollTop;by-=bz.scrollLeft;if(bz===bw){bD+=bz.offsetTop;by+=bz.offsetLeft;if(b.support.doesNotAddBorder&&!(b.support.doesAddBorderForTableAndCells&&V.test(bz.nodeName))){bD+=parseFloat(bC.borderTopWidth)||0;by+=parseFloat(bC.borderLeftWidth)||0}bv=bw;bw=bz.offsetParent}if(b.support.subtractsBorderForOverflowNotVisible&&bC.overflow!=="visible"){bD+=parseFloat(bC.borderTopWidth)||0;by+=parseFloat(bC.borderLeftWidth)||0}e=bC}if(e.position==="relative"||e.position==="static"){bD+=bA.offsetTop;by+=bA.offsetLeft}if(b.support.fixedPosition&&e.position==="fixed"){bD+=Math.max(bx.scrollTop,bA.scrollTop);by+=Math.max(bx.scrollLeft,bA.scrollLeft)}return{top:bD,left:by}}}b.offset={bodyOffset:function(e){var bw=e.offsetTop,bv=e.offsetLeft;if(b.support.doesNotIncludeMarginInBodyOffset){bw+=parseFloat(b.css(e,"marginTop"))||0;bv+=parseFloat(b.css(e,"marginLeft"))||0}return{top:bw,left:bv}},setOffset:function(bx,bG,bA){var bB=b.css(bx,"position");if(bB==="static"){bx.style.position="relative"}var bz=b(bx),bv=bz.offset(),e=b.css(bx,"top"),bE=b.css(bx,"left"),bF=(bB==="absolute"||bB==="fixed")&&b.inArray("auto",[e,bE])>-1,bD={},bC={},bw,by;if(bF){bC=bz.position();bw=bC.top;by=bC.left}else{bw=parseFloat(e)||0;by=parseFloat(bE)||0}if(b.isFunction(bG)){bG=bG.call(bx,bA,bv)}if(bG.top!=null){bD.top=(bG.top-bv.top)+bw}if(bG.left!=null){bD.left=(bG.left-bv.left)+by}if("using" in bG){bG.using.call(bx,bD)}else{bz.css(bD)}}};b.fn.extend({position:function(){if(!this[0]){return null}var bw=this[0],bv=this.offsetParent(),bx=this.offset(),e=ad.test(bv[0].nodeName)?{top:0,left:0}:bv.offset();bx.top-=parseFloat(b.css(bw,"marginTop"))||0;bx.left-=parseFloat(b.css(bw,"marginLeft"))||0;e.top+=parseFloat(b.css(bv[0],"borderTopWidth"))||0;e.left+=parseFloat(b.css(bv[0],"borderLeftWidth"))||0;return{top:bx.top-e.top,left:bx.left-e.left}},offsetParent:function(){return this.map(function(){var e=this.offsetParent||av.body;while(e&&(!ad.test(e.nodeName)&&b.css(e,"position")==="static")){e=e.offsetParent}return e})}});b.each(["Left","Top"],function(bv,e){var bw="scroll"+e;b.fn[bw]=function(bz){var bx,by;if(bz===L){bx=this[0];if(!bx){return null}by=aK(bx);return by?("pageXOffset" in by)?by[bv?"pageYOffset":"pageXOffset"]:b.support.boxModel&&by.document.documentElement[bw]||by.document.body[bw]:bx[bw]}return this.each(function(){by=aK(this);if(by){by.scrollTo(!bv?bz:b(by).scrollLeft(),bv?bz:b(by).scrollTop())}else{this[bw]=bz}})}});function aK(e){return b.isWindow(e)?e:e.nodeType===9?e.defaultView||e.parentWindow:false}b.each(["Height","Width"],function(bv,e){var bw=e.toLowerCase();b.fn["inner"+e]=function(){var bx=this[0];return bx?bx.style?parseFloat(b.css(bx,bw,"padding")):this[bw]():null};b.fn["outer"+e]=function(by){var bx=this[0];return bx?bx.style?parseFloat(b.css(bx,bw,by?"margin":"border")):this[bw]():null};b.fn[bw]=function(bz){var bA=this[0];if(!bA){return bz==null?null:this}if(b.isFunction(bz)){return this.each(function(bE){var bD=b(this);bD[bw](bz.call(this,bE,bD[bw]()))})}if(b.isWindow(bA)){var bB=bA.document.documentElement["client"+e],bx=bA.document.body;return bA.document.compatMode==="CSS1Compat"&&bB||bx&&bx["client"+e]||bB}else{if(bA.nodeType===9){return Math.max(bA.documentElement["client"+e],bA.body["scroll"+e],bA.documentElement["scroll"+e],bA.body["offset"+e],bA.documentElement["offset"+e])}else{if(bz===L){var bC=b.css(bA,bw),by=parseFloat(bC);return b.isNumeric(by)?by:bC}else{return this.css(bw,typeof bz==="string"?bz:bz+"px")}}}}});bb.jQuery=bb.$=b;if(typeof define==="function"&&define.amd&&define.amd.jQuery){define("jquery",[],function(){return b})}})(window);/*! -+ * jQuery UI 1.8.18 -+ * -+ * Copyright 2011, AUTHORS.txt (http://jqueryui.com/about) -+ * Dual licensed under the MIT or GPL Version 2 licenses. -+ * http://jquery.org/license -+ * -+ * http://docs.jquery.com/UI -+ */ -+ (function(a,d){a.ui=a.ui||{};if(a.ui.version){return}a.extend(a.ui,{version:"1.8.18",keyCode:{ALT:18,BACKSPACE:8,CAPS_LOCK:20,COMMA:188,COMMAND:91,COMMAND_LEFT:91,COMMAND_RIGHT:93,CONTROL:17,DELETE:46,DOWN:40,END:35,ENTER:13,ESCAPE:27,HOME:36,INSERT:45,LEFT:37,MENU:93,NUMPAD_ADD:107,NUMPAD_DECIMAL:110,NUMPAD_DIVIDE:111,NUMPAD_ENTER:108,NUMPAD_MULTIPLY:106,NUMPAD_SUBTRACT:109,PAGE_DOWN:34,PAGE_UP:33,PERIOD:190,RIGHT:39,SHIFT:16,SPACE:32,TAB:9,UP:38,WINDOWS:91}});a.fn.extend({propAttr:a.fn.prop||a.fn.attr,_focus:a.fn.focus,focus:function(e,f){return typeof e==="number"?this.each(function(){var g=this;setTimeout(function(){a(g).focus();if(f){f.call(g)}},e)}):this._focus.apply(this,arguments)},scrollParent:function(){var e;if((a.browser.msie&&(/(static|relative)/).test(this.css("position")))||(/absolute/).test(this.css("position"))){e=this.parents().filter(function(){return(/(relative|absolute|fixed)/).test(a.curCSS(this,"position",1))&&(/(auto|scroll)/).test(a.curCSS(this,"overflow",1)+a.curCSS(this,"overflow-y",1)+a.curCSS(this,"overflow-x",1))}).eq(0)}else{e=this.parents().filter(function(){return(/(auto|scroll)/).test(a.curCSS(this,"overflow",1)+a.curCSS(this,"overflow-y",1)+a.curCSS(this,"overflow-x",1))}).eq(0)}return(/fixed/).test(this.css("position"))||!e.length?a(document):e},zIndex:function(h){if(h!==d){return this.css("zIndex",h)}if(this.length){var f=a(this[0]),e,g;while(f.length&&f[0]!==document){e=f.css("position");if(e==="absolute"||e==="relative"||e==="fixed"){g=parseInt(f.css("zIndex"),10);if(!isNaN(g)&&g!==0){return g}}f=f.parent()}}return 0},disableSelection:function(){return this.bind((a.support.selectstart?"selectstart":"mousedown")+".ui-disableSelection",function(e){e.preventDefault()})},enableSelection:function(){return this.unbind(".ui-disableSelection")}});a.each(["Width","Height"],function(g,e){var f=e==="Width"?["Left","Right"]:["Top","Bottom"],h=e.toLowerCase(),k={innerWidth:a.fn.innerWidth,innerHeight:a.fn.innerHeight,outerWidth:a.fn.outerWidth,outerHeight:a.fn.outerHeight};function j(m,l,i,n){a.each(f,function(){l-=parseFloat(a.curCSS(m,"padding"+this,true))||0;if(i){l-=parseFloat(a.curCSS(m,"border"+this+"Width",true))||0}if(n){l-=parseFloat(a.curCSS(m,"margin"+this,true))||0}});return l}a.fn["inner"+e]=function(i){if(i===d){return k["inner"+e].call(this)}return this.each(function(){a(this).css(h,j(this,i)+"px")})};a.fn["outer"+e]=function(i,l){if(typeof i!=="number"){return k["outer"+e].call(this,i)}return this.each(function(){a(this).css(h,j(this,i,true,l)+"px")})}});function c(g,e){var j=g.nodeName.toLowerCase();if("area"===j){var i=g.parentNode,h=i.name,f;if(!g.href||!h||i.nodeName.toLowerCase()!=="map"){return false}f=a("img[usemap=#"+h+"]")[0];return !!f&&b(f)}return(/input|select|textarea|button|object/.test(j)?!g.disabled:"a"==j?g.href||e:e)&&b(g)}function b(e){return !a(e).parents().andSelf().filter(function(){return a.curCSS(this,"visibility")==="hidden"||a.expr.filters.hidden(this)}).length}a.extend(a.expr[":"],{data:function(g,f,e){return !!a.data(g,e[3])},focusable:function(e){return c(e,!isNaN(a.attr(e,"tabindex")))},tabbable:function(g){var e=a.attr(g,"tabindex"),f=isNaN(e);return(f||e>=0)&&c(g,!f)}});a(function(){var e=document.body,f=e.appendChild(f=document.createElement("div"));f.offsetHeight;a.extend(f.style,{minHeight:"100px",height:"auto",padding:0,borderWidth:0});a.support.minHeight=f.offsetHeight===100;a.support.selectstart="onselectstart" in f;e.removeChild(f).style.display="none"});a.extend(a.ui,{plugin:{add:function(f,g,j){var h=a.ui[f].prototype;for(var e in j){h.plugins[e]=h.plugins[e]||[];h.plugins[e].push([g,j[e]])}},call:function(e,g,f){var j=e.plugins[g];if(!j||!e.element[0].parentNode){return}for(var h=0;h0){return true}h[e]=1;g=(h[e]>0);h[e]=0;return g},isOverAxis:function(f,e,g){return(f>e)&&(f<(e+g))},isOver:function(j,f,i,h,e,g){return a.ui.isOverAxis(j,i,e)&&a.ui.isOverAxis(f,h,g)}})})(jQuery);/*! -+ * jQuery UI Widget 1.8.18 -+ * -+ * Copyright 2011, AUTHORS.txt (http://jqueryui.com/about) -+ * Dual licensed under the MIT or GPL Version 2 licenses. -+ * http://jquery.org/license -+ * -+ * http://docs.jquery.com/UI/Widget -+ */ -+ (function(b,d){if(b.cleanData){var c=b.cleanData;b.cleanData=function(f){for(var g=0,h;(h=f[g])!=null;g++){try{b(h).triggerHandler("remove")}catch(j){}}c(f)}}else{var a=b.fn.remove;b.fn.remove=function(e,f){return this.each(function(){if(!f){if(!e||b.filter(e,[this]).length){b("*",this).add([this]).each(function(){try{b(this).triggerHandler("remove")}catch(g){}})}}return a.call(b(this),e,f)})}}b.widget=function(f,h,e){var g=f.split(".")[0],j;f=f.split(".")[1];j=g+"-"+f;if(!e){e=h;h=b.Widget}b.expr[":"][j]=function(k){return !!b.data(k,f)};b[g]=b[g]||{};b[g][f]=function(k,l){if(arguments.length){this._createWidget(k,l)}};var i=new h();i.options=b.extend(true,{},i.options);b[g][f].prototype=b.extend(true,i,{namespace:g,widgetName:f,widgetEventPrefix:b[g][f].prototype.widgetEventPrefix||f,widgetBaseClass:j},e);b.widget.bridge(f,b[g][f])};b.widget.bridge=function(f,e){b.fn[f]=function(i){var g=typeof i==="string",h=Array.prototype.slice.call(arguments,1),j=this;i=!g&&h.length?b.extend.apply(null,[true,i].concat(h)):i;if(g&&i.charAt(0)==="_"){return j}if(g){this.each(function(){var k=b.data(this,f),l=k&&b.isFunction(k[i])?k[i].apply(k,h):k;if(l!==k&&l!==d){j=l;return false}})}else{this.each(function(){var k=b.data(this,f);if(k){k.option(i||{})._init()}else{b.data(this,f,new e(i,this))}})}return j}};b.Widget=function(e,f){if(arguments.length){this._createWidget(e,f)}};b.Widget.prototype={widgetName:"widget",widgetEventPrefix:"",options:{disabled:false},_createWidget:function(f,g){b.data(g,this.widgetName,this);this.element=b(g);this.options=b.extend(true,{},this.options,this._getCreateOptions(),f);var e=this;this.element.bind("remove."+this.widgetName,function(){e.destroy()});this._create();this._trigger("create");this._init()},_getCreateOptions:function(){return b.metadata&&b.metadata.get(this.element[0])[this.widgetName]},_create:function(){},_init:function(){},destroy:function(){this.element.unbind("."+this.widgetName).removeData(this.widgetName);this.widget().unbind("."+this.widgetName).removeAttr("aria-disabled").removeClass(this.widgetBaseClass+"-disabled ui-state-disabled")},widget:function(){return this.element},option:function(f,g){var e=f;if(arguments.length===0){return b.extend({},this.options)}if(typeof f==="string"){if(g===d){return this.options[f]}e={};e[f]=g}this._setOptions(e);return this},_setOptions:function(f){var e=this;b.each(f,function(g,h){e._setOption(g,h)});return this},_setOption:function(e,f){this.options[e]=f;if(e==="disabled"){this.widget()[f?"addClass":"removeClass"](this.widgetBaseClass+"-disabled ui-state-disabled").attr("aria-disabled",f)}return this},enable:function(){return this._setOption("disabled",false)},disable:function(){return this._setOption("disabled",true)},_trigger:function(e,f,g){var j,i,h=this.options[e];g=g||{};f=b.Event(f);f.type=(e===this.widgetEventPrefix?e:this.widgetEventPrefix+e).toLowerCase();f.target=this.element[0];i=f.originalEvent;if(i){for(j in i){if(!(j in f)){f[j]=i[j]}}}this.element.trigger(f,g);return !(b.isFunction(h)&&h.call(this.element[0],f,g)===false||f.isDefaultPrevented())}}})(jQuery);/*! -+ * jQuery UI Mouse 1.8.18 -+ * -+ * Copyright 2011, AUTHORS.txt (http://jqueryui.com/about) -+ * Dual licensed under the MIT or GPL Version 2 licenses. -+ * http://jquery.org/license -+ * -+ * http://docs.jquery.com/UI/Mouse -+ * -+ * Depends: -+ * jquery.ui.widget.js -+ */ -+ (function(b,c){var a=false;b(document).mouseup(function(d){a=false});b.widget("ui.mouse",{options:{cancel:":input,option",distance:1,delay:0},_mouseInit:function(){var d=this;this.element.bind("mousedown."+this.widgetName,function(e){return d._mouseDown(e)}).bind("click."+this.widgetName,function(e){if(true===b.data(e.target,d.widgetName+".preventClickEvent")){b.removeData(e.target,d.widgetName+".preventClickEvent");e.stopImmediatePropagation();return false}});this.started=false},_mouseDestroy:function(){this.element.unbind("."+this.widgetName)},_mouseDown:function(f){if(a){return}(this._mouseStarted&&this._mouseUp(f));this._mouseDownEvent=f;var e=this,g=(f.which==1),d=(typeof this.options.cancel=="string"&&f.target.nodeName?b(f.target).closest(this.options.cancel).length:false);if(!g||d||!this._mouseCapture(f)){return true}this.mouseDelayMet=!this.options.delay;if(!this.mouseDelayMet){this._mouseDelayTimer=setTimeout(function(){e.mouseDelayMet=true},this.options.delay)}if(this._mouseDistanceMet(f)&&this._mouseDelayMet(f)){this._mouseStarted=(this._mouseStart(f)!==false);if(!this._mouseStarted){f.preventDefault();return true}}if(true===b.data(f.target,this.widgetName+".preventClickEvent")){b.removeData(f.target,this.widgetName+".preventClickEvent")}this._mouseMoveDelegate=function(h){return e._mouseMove(h)};this._mouseUpDelegate=function(h){return e._mouseUp(h)};b(document).bind("mousemove."+this.widgetName,this._mouseMoveDelegate).bind("mouseup."+this.widgetName,this._mouseUpDelegate);f.preventDefault();a=true;return true},_mouseMove:function(d){if(b.browser.msie&&!(document.documentMode>=9)&&!d.button){return this._mouseUp(d)}if(this._mouseStarted){this._mouseDrag(d);return d.preventDefault()}if(this._mouseDistanceMet(d)&&this._mouseDelayMet(d)){this._mouseStarted=(this._mouseStart(this._mouseDownEvent,d)!==false);(this._mouseStarted?this._mouseDrag(d):this._mouseUp(d))}return !this._mouseStarted},_mouseUp:function(d){b(document).unbind("mousemove."+this.widgetName,this._mouseMoveDelegate).unbind("mouseup."+this.widgetName,this._mouseUpDelegate);if(this._mouseStarted){this._mouseStarted=false;if(d.target==this._mouseDownEvent.target){b.data(d.target,this.widgetName+".preventClickEvent",true)}this._mouseStop(d)}return false},_mouseDistanceMet:function(d){return(Math.max(Math.abs(this._mouseDownEvent.pageX-d.pageX),Math.abs(this._mouseDownEvent.pageY-d.pageY))>=this.options.distance)},_mouseDelayMet:function(d){return this.mouseDelayMet},_mouseStart:function(d){},_mouseDrag:function(d){},_mouseStop:function(d){},_mouseCapture:function(d){return true}})})(jQuery);(function(c,d){c.widget("ui.resizable",c.ui.mouse,{widgetEventPrefix:"resize",options:{alsoResize:false,animate:false,animateDuration:"slow",animateEasing:"swing",aspectRatio:false,autoHide:false,containment:false,ghost:false,grid:false,handles:"e,s,se",helper:false,maxHeight:null,maxWidth:null,minHeight:10,minWidth:10,zIndex:1000},_create:function(){var f=this,k=this.options;this.element.addClass("ui-resizable");c.extend(this,{_aspectRatio:!!(k.aspectRatio),aspectRatio:k.aspectRatio,originalElement:this.element,_proportionallyResizeElements:[],_helper:k.helper||k.ghost||k.animate?k.helper||"ui-resizable-helper":null});if(this.element[0].nodeName.match(/canvas|textarea|input|select|button|img/i)){this.element.wrap(c('
').css({position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")}));this.element=this.element.parent().data("resizable",this.element.data("resizable"));this.elementIsWrapper=true;this.element.css({marginLeft:this.originalElement.css("marginLeft"),marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom")});this.originalElement.css({marginLeft:0,marginTop:0,marginRight:0,marginBottom:0});this.originalResizeStyle=this.originalElement.css("resize");this.originalElement.css("resize","none");this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"}));this.originalElement.css({margin:this.originalElement.css("margin")});this._proportionallyResize()}this.handles=k.handles||(!c(".ui-resizable-handle",this.element).length?"e,s,se":{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"});if(this.handles.constructor==String){if(this.handles=="all"){this.handles="n,e,s,w,se,sw,ne,nw"}var l=this.handles.split(",");this.handles={};for(var g=0;g
');if(/sw|se|ne|nw/.test(j)){h.css({zIndex:++k.zIndex})}if("se"==j){h.addClass("ui-icon ui-icon-gripsmall-diagonal-se")}this.handles[j]=".ui-resizable-"+j;this.element.append(h)}}this._renderAxis=function(q){q=q||this.element;for(var n in this.handles){if(this.handles[n].constructor==String){this.handles[n]=c(this.handles[n],this.element).show()}if(this.elementIsWrapper&&this.originalElement[0].nodeName.match(/textarea|input|select|button/i)){var o=c(this.handles[n],this.element),p=0;p=/sw|ne|nw|se|n|s/.test(n)?o.outerHeight():o.outerWidth();var m=["padding",/ne|nw|n/.test(n)?"Top":/se|sw|s/.test(n)?"Bottom":/^e$/.test(n)?"Right":"Left"].join("");q.css(m,p);this._proportionallyResize()}if(!c(this.handles[n]).length){continue}}};this._renderAxis(this.element);this._handles=c(".ui-resizable-handle",this.element).disableSelection();this._handles.mouseover(function(){if(!f.resizing){if(this.className){var i=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)}f.axis=i&&i[1]?i[1]:"se"}});if(k.autoHide){this._handles.hide();c(this.element).addClass("ui-resizable-autohide").hover(function(){if(k.disabled){return}c(this).removeClass("ui-resizable-autohide");f._handles.show()},function(){if(k.disabled){return}if(!f.resizing){c(this).addClass("ui-resizable-autohide");f._handles.hide()}})}this._mouseInit()},destroy:function(){this._mouseDestroy();var e=function(g){c(g).removeClass("ui-resizable ui-resizable-disabled ui-resizable-resizing").removeData("resizable").unbind(".resizable").find(".ui-resizable-handle").remove()};if(this.elementIsWrapper){e(this.element);var f=this.element;f.after(this.originalElement.css({position:f.css("position"),width:f.outerWidth(),height:f.outerHeight(),top:f.css("top"),left:f.css("left")})).remove()}this.originalElement.css("resize",this.originalResizeStyle);e(this.originalElement);return this},_mouseCapture:function(f){var g=false;for(var e in this.handles){if(c(this.handles[e])[0]==f.target){g=true}}return !this.options.disabled&&g},_mouseStart:function(g){var j=this.options,f=this.element.position(),e=this.element;this.resizing=true;this.documentScroll={top:c(document).scrollTop(),left:c(document).scrollLeft()};if(e.is(".ui-draggable")||(/absolute/).test(e.css("position"))){e.css({position:"absolute",top:f.top,left:f.left})}this._renderProxy();var k=b(this.helper.css("left")),h=b(this.helper.css("top"));if(j.containment){k+=c(j.containment).scrollLeft()||0;h+=c(j.containment).scrollTop()||0}this.offset=this.helper.offset();this.position={left:k,top:h};this.size=this._helper?{width:e.outerWidth(),height:e.outerHeight()}:{width:e.width(),height:e.height()};this.originalSize=this._helper?{width:e.outerWidth(),height:e.outerHeight()}:{width:e.width(),height:e.height()};this.originalPosition={left:k,top:h};this.sizeDiff={width:e.outerWidth()-e.width(),height:e.outerHeight()-e.height()};this.originalMousePosition={left:g.pageX,top:g.pageY};this.aspectRatio=(typeof j.aspectRatio=="number")?j.aspectRatio:((this.originalSize.width/this.originalSize.height)||1);var i=c(".ui-resizable-"+this.axis).css("cursor");c("body").css("cursor",i=="auto"?this.axis+"-resize":i);e.addClass("ui-resizable-resizing");this._propagate("start",g);return true},_mouseDrag:function(e){var h=this.helper,g=this.options,m={},q=this,j=this.originalMousePosition,n=this.axis;var r=(e.pageX-j.left)||0,p=(e.pageY-j.top)||0;var i=this._change[n];if(!i){return false}var l=i.apply(this,[e,r,p]),k=c.browser.msie&&c.browser.version<7,f=this.sizeDiff;this._updateVirtualBoundaries(e.shiftKey);if(this._aspectRatio||e.shiftKey){l=this._updateRatio(l,e)}l=this._respectSize(l,e);this._propagate("resize",e);h.css({top:this.position.top+"px",left:this.position.left+"px",width:this.size.width+"px",height:this.size.height+"px"});if(!this._helper&&this._proportionallyResizeElements.length){this._proportionallyResize()}this._updateCache(l);this._trigger("resize",e,this.ui());return false},_mouseStop:function(h){this.resizing=false;var i=this.options,m=this;if(this._helper){var g=this._proportionallyResizeElements,e=g.length&&(/textarea/i).test(g[0].nodeName),f=e&&c.ui.hasScroll(g[0],"left")?0:m.sizeDiff.height,k=e?0:m.sizeDiff.width;var n={width:(m.helper.width()-k),height:(m.helper.height()-f)},j=(parseInt(m.element.css("left"),10)+(m.position.left-m.originalPosition.left))||null,l=(parseInt(m.element.css("top"),10)+(m.position.top-m.originalPosition.top))||null;if(!i.animate){this.element.css(c.extend(n,{top:l,left:j}))}m.helper.height(m.size.height);m.helper.width(m.size.width);if(this._helper&&!i.animate){this._proportionallyResize()}}c("body").css("cursor","auto");this.element.removeClass("ui-resizable-resizing");this._propagate("stop",h);if(this._helper){this.helper.remove()}return false},_updateVirtualBoundaries:function(g){var j=this.options,i,h,f,k,e;e={minWidth:a(j.minWidth)?j.minWidth:0,maxWidth:a(j.maxWidth)?j.maxWidth:Infinity,minHeight:a(j.minHeight)?j.minHeight:0,maxHeight:a(j.maxHeight)?j.maxHeight:Infinity};if(this._aspectRatio||g){i=e.minHeight*this.aspectRatio;f=e.minWidth/this.aspectRatio;h=e.maxHeight*this.aspectRatio;k=e.maxWidth/this.aspectRatio;if(i>e.minWidth){e.minWidth=i}if(f>e.minHeight){e.minHeight=f}if(hl.width),s=a(l.height)&&i.minHeight&&(i.minHeight>l.height);if(h){l.width=i.minWidth}if(s){l.height=i.minHeight}if(t){l.width=i.maxWidth}if(m){l.height=i.maxHeight}var f=this.originalPosition.left+this.originalSize.width,p=this.position.top+this.size.height;var k=/sw|nw|w/.test(q),e=/nw|ne|n/.test(q);if(h&&k){l.left=f-i.minWidth}if(t&&k){l.left=f-i.maxWidth}if(s&&e){l.top=p-i.minHeight}if(m&&e){l.top=p-i.maxHeight}var n=!l.width&&!l.height;if(n&&!l.left&&l.top){l.top=null}else{if(n&&!l.top&&l.left){l.left=null}}return l},_proportionallyResize:function(){var k=this.options;if(!this._proportionallyResizeElements.length){return}var g=this.helper||this.element;for(var f=0;f');var e=c.browser.msie&&c.browser.version<7,g=(e?1:0),h=(e?2:-1);this.helper.addClass(this._helper).css({width:this.element.outerWidth()+h,height:this.element.outerHeight()+h,position:"absolute",left:this.elementOffset.left-g+"px",top:this.elementOffset.top-g+"px",zIndex:++i.zIndex});this.helper.appendTo("body").disableSelection()}else{this.helper=this.element}},_change:{e:function(g,f,e){return{width:this.originalSize.width+f}},w:function(h,f,e){var j=this.options,g=this.originalSize,i=this.originalPosition;return{left:i.left+f,width:g.width-f}},n:function(h,f,e){var j=this.options,g=this.originalSize,i=this.originalPosition;return{top:i.top+e,height:g.height-e}},s:function(g,f,e){return{height:this.originalSize.height+e}},se:function(g,f,e){return c.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[g,f,e]))},sw:function(g,f,e){return c.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[g,f,e]))},ne:function(g,f,e){return c.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[g,f,e]))},nw:function(g,f,e){return c.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[g,f,e]))}},_propagate:function(f,e){c.ui.plugin.call(this,f,[e,this.ui()]);(f!="resize"&&this._trigger(f,e,this.ui()))},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}});c.extend(c.ui.resizable,{version:"1.8.18"});c.ui.plugin.add("resizable","alsoResize",{start:function(f,g){var e=c(this).data("resizable"),i=e.options;var h=function(j){c(j).each(function(){var k=c(this);k.data("resizable-alsoresize",{width:parseInt(k.width(),10),height:parseInt(k.height(),10),left:parseInt(k.css("left"),10),top:parseInt(k.css("top"),10)})})};if(typeof(i.alsoResize)=="object"&&!i.alsoResize.parentNode){if(i.alsoResize.length){i.alsoResize=i.alsoResize[0];h(i.alsoResize)}else{c.each(i.alsoResize,function(j){h(j)})}}else{h(i.alsoResize)}},resize:function(g,i){var f=c(this).data("resizable"),j=f.options,h=f.originalSize,l=f.originalPosition;var k={height:(f.size.height-h.height)||0,width:(f.size.width-h.width)||0,top:(f.position.top-l.top)||0,left:(f.position.left-l.left)||0},e=function(m,n){c(m).each(function(){var q=c(this),r=c(this).data("resizable-alsoresize"),p={},o=n&&n.length?n:q.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];c.each(o,function(s,u){var t=(r[u]||0)+(k[u]||0);if(t&&t>=0){p[u]=t||null}});q.css(p)})};if(typeof(j.alsoResize)=="object"&&!j.alsoResize.nodeType){c.each(j.alsoResize,function(m,n){e(m,n)})}else{e(j.alsoResize)}},stop:function(e,f){c(this).removeData("resizable-alsoresize")}});c.ui.plugin.add("resizable","animate",{stop:function(i,n){var p=c(this).data("resizable"),j=p.options;var h=p._proportionallyResizeElements,e=h.length&&(/textarea/i).test(h[0].nodeName),f=e&&c.ui.hasScroll(h[0],"left")?0:p.sizeDiff.height,l=e?0:p.sizeDiff.width;var g={width:(p.size.width-l),height:(p.size.height-f)},k=(parseInt(p.element.css("left"),10)+(p.position.left-p.originalPosition.left))||null,m=(parseInt(p.element.css("top"),10)+(p.position.top-p.originalPosition.top))||null;p.element.animate(c.extend(g,m&&k?{top:m,left:k}:{}),{duration:j.animateDuration,easing:j.animateEasing,step:function(){var o={width:parseInt(p.element.css("width"),10),height:parseInt(p.element.css("height"),10),top:parseInt(p.element.css("top"),10),left:parseInt(p.element.css("left"),10)};if(h&&h.length){c(h[0]).css({width:o.width,height:o.height})}p._updateCache(o);p._propagate("resize",i)}})}});c.ui.plugin.add("resizable","containment",{start:function(f,r){var t=c(this).data("resizable"),j=t.options,l=t.element;var g=j.containment,k=(g instanceof c)?g.get(0):(/parent/.test(g))?l.parent().get(0):g;if(!k){return}t.containerElement=c(k);if(/document/.test(g)||g==document){t.containerOffset={left:0,top:0};t.containerPosition={left:0,top:0};t.parentData={element:c(document),left:0,top:0,width:c(document).width(),height:c(document).height()||document.body.parentNode.scrollHeight}}else{var n=c(k),i=[];c(["Top","Right","Left","Bottom"]).each(function(p,o){i[p]=b(n.css("padding"+o))});t.containerOffset=n.offset();t.containerPosition=n.position();t.containerSize={height:(n.innerHeight()-i[3]),width:(n.innerWidth()-i[1])};var q=t.containerOffset,e=t.containerSize.height,m=t.containerSize.width,h=(c.ui.hasScroll(k,"left")?k.scrollWidth:m),s=(c.ui.hasScroll(k)?k.scrollHeight:e);t.parentData={element:k,left:q.left,top:q.top,width:h,height:s}}},resize:function(g,q){var t=c(this).data("resizable"),i=t.options,f=t.containerSize,p=t.containerOffset,m=t.size,n=t.position,r=t._aspectRatio||g.shiftKey,e={top:0,left:0},h=t.containerElement;if(h[0]!=document&&(/static/).test(h.css("position"))){e=p}if(n.left<(t._helper?p.left:0)){t.size.width=t.size.width+(t._helper?(t.position.left-p.left):(t.position.left-e.left));if(r){t.size.height=t.size.width/i.aspectRatio}t.position.left=i.helper?p.left:0}if(n.top<(t._helper?p.top:0)){t.size.height=t.size.height+(t._helper?(t.position.top-p.top):t.position.top);if(r){t.size.width=t.size.height*i.aspectRatio}t.position.top=t._helper?p.top:0}t.offset.left=t.parentData.left+t.position.left;t.offset.top=t.parentData.top+t.position.top;var l=Math.abs((t._helper?t.offset.left-e.left:(t.offset.left-e.left))+t.sizeDiff.width),s=Math.abs((t._helper?t.offset.top-e.top:(t.offset.top-p.top))+t.sizeDiff.height);var k=t.containerElement.get(0)==t.element.parent().get(0),j=/relative|absolute/.test(t.containerElement.css("position"));if(k&&j){l-=t.parentData.left}if(l+t.size.width>=t.parentData.width){t.size.width=t.parentData.width-l;if(r){t.size.height=t.size.width/t.aspectRatio}}if(s+t.size.height>=t.parentData.height){t.size.height=t.parentData.height-s;if(r){t.size.width=t.size.height*t.aspectRatio}}},stop:function(f,n){var q=c(this).data("resizable"),g=q.options,l=q.position,m=q.containerOffset,e=q.containerPosition,i=q.containerElement;var j=c(q.helper),r=j.offset(),p=j.outerWidth()-q.sizeDiff.width,k=j.outerHeight()-q.sizeDiff.height;if(q._helper&&!g.animate&&(/relative/).test(i.css("position"))){c(this).css({left:r.left-e.left-m.left,width:p,height:k})}if(q._helper&&!g.animate&&(/static/).test(i.css("position"))){c(this).css({left:r.left-e.left-m.left,width:p,height:k})}}});c.ui.plugin.add("resizable","ghost",{start:function(g,h){var e=c(this).data("resizable"),i=e.options,f=e.size;e.ghost=e.originalElement.clone();e.ghost.css({opacity:0.25,display:"block",position:"relative",height:f.height,width:f.width,margin:0,left:0,top:0}).addClass("ui-resizable-ghost").addClass(typeof i.ghost=="string"?i.ghost:"");e.ghost.appendTo(e.helper)},resize:function(f,g){var e=c(this).data("resizable"),h=e.options;if(e.ghost){e.ghost.css({position:"relative",height:e.size.height,width:e.size.width})}},stop:function(f,g){var e=c(this).data("resizable"),h=e.options;if(e.ghost&&e.helper){e.helper.get(0).removeChild(e.ghost.get(0))}}});c.ui.plugin.add("resizable","grid",{resize:function(e,m){var p=c(this).data("resizable"),h=p.options,k=p.size,i=p.originalSize,j=p.originalPosition,n=p.axis,l=h._aspectRatio||e.shiftKey;h.grid=typeof h.grid=="number"?[h.grid,h.grid]:h.grid;var g=Math.round((k.width-i.width)/(h.grid[0]||1))*(h.grid[0]||1),f=Math.round((k.height-i.height)/(h.grid[1]||1))*(h.grid[1]||1);if(/^(se|s|e)$/.test(n)){p.size.width=i.width+g;p.size.height=i.height+f}else{if(/^(ne)$/.test(n)){p.size.width=i.width+g;p.size.height=i.height+f;p.position.top=j.top-f}else{if(/^(sw)$/.test(n)){p.size.width=i.width+g;p.size.height=i.height+f;p.position.left=j.left-g}else{p.size.width=i.width+g;p.size.height=i.height+f;p.position.top=j.top-f;p.position.left=j.left-g}}}}});var b=function(e){return parseInt(e,10)||0};var a=function(e){return !isNaN(parseInt(e,10))}})(jQuery);/*! -+ * jQuery hashchange event - v1.3 - 7/21/2010 -+ * http://benalman.com/projects/jquery-hashchange-plugin/ -+ * -+ * Copyright (c) 2010 "Cowboy" Ben Alman -+ * Dual licensed under the MIT and GPL licenses. -+ * http://benalman.com/about/license/ -+ */ -+ (function($,e,b){var c="hashchange",h=document,f,g=$.event.special,i=h.documentMode,d="on"+c in e&&(i===b||i>7);function a(j){j=j||location.href;return"#"+j.replace(/^[^#]*#?(.*)$/,"$1")}$.fn[c]=function(j){return j?this.bind(c,j):this.trigger(c)};$.fn[c].delay=50;g[c]=$.extend(g[c],{setup:function(){if(d){return false}$(f.start)},teardown:function(){if(d){return false}$(f.stop)}});f=(function(){var j={},p,m=a(),k=function(q){return q},l=k,o=k;j.start=function(){p||n()};j.stop=function(){p&&clearTimeout(p);p=b};function n(){var r=a(),q=o(m);if(r!==m){l(m=r,q);$(e).trigger(c)}else{if(q!==m){location.href=location.href.replace(/#.*/,"")+q}}p=setTimeout(n,$.fn[c].delay)}$.browser.msie&&!d&&(function(){var q,r;j.start=function(){if(!q){r=$.fn[c].src;r=r&&r+a();q=$('