This thread has been locked.

If you have a related question, please click the "Ask a related question" button in the top right corner. The newly created question will be automatically linked to this question.

Motor SDK - PerUnit (PU) values for FOC algorithm

Other Parts Discussed in Thread: MOTORWARE, DRV8301

Hi,

In the Motor SDK, I see that PerUnit (PU) values are not used when dealing with PI controllers. This is a change from the implementation in motorware. Any reason for the change?

Personally, I do not see any benefit in using PU values anyways. But I would like to know if there is any benefit? And what is the reason for the change in Motor SDK? 

Thanks

  • Right. MC-SDK only supports floating point controllers, so MC-SDK uses SI unit that is more robustness, wide range, higher precision, and easier interface. Per unit (OU) is often used on the fixed point controller that has higher code efficiency than using floating point on a fixed point controller.
  • Hi Yanming,

    Thanks for answering. Now I understand the use of pu values. But I clearly see the advantages of using floating point controller and floating point code.

    I am planning to shift from motorware to motor SDK and shift from F28069M to F280049C. But I have DRV8301-HC-EVM-RevD kit and motor SDK does not support this kit. Is there any reason for that? I hope TI is planning to release Motor SDK for DRV8301 kit as well.

    It feels like a big task to get the MotorSDK code working correctly for the DRV8301 kit hardware board. Is there any possibility in TI helping out with this task?

    Thanks  

  • Hi Yanming,

    I am looking forward to your reply. I am sure that I will be going forward with F280049 and motor SDK as the code base. I have DRV8301 EVM RevD kit. I have also purchased the F280049C control card as well as DIMM100 to HSEC 180pin connector so that I connect it to the kit.

    The only thing remaining is the code which is not available on Motor SDK for DRV8301 kit. Please let me know if there is a plan to do it or I will have to do it myself? Also, is there any way in which TI can help me out? I am not an expert in embedded system and hence it will be difficult and time consuming to do it all alone.
  • The DRV8301-HC-Kit will not be supported in motor Control SDK for public release, we could make a package external to support the DRV8301-HC-Kit for motor control SDK, and post it on E2E. Or you might try to do this by yourself, just need to add the DRV8301 drive file in the project, and change the hal.c as well.

  • Thanks, Yanming for the reply. 

    It would be great if you can make a package external to support the DRV8301-HC-Kit for motor control SDK. It should give me a good start and I can take it from there. 

    I am more of a hardware engineer with some knowledge of C language. I have already tried to do it myself but failed at some steps from where I could not debug/resolve the error. It would be great if TI team can help me out. 

    Thanks 

  • Hi Yanming,

    Any update on this? 

  • Hi Yanming,

    Please let me know the status. I am waiting for the support from your end. 

  • Hi Yanming,

    I have mapped the pins from F28069M to F280049C for the DRVkit. I am not sure about configurations of some pins and I have added comments for that in the attached excel. Can you please help me out with the doubts? 

    I have taken up this task again on myself but I am not sure I will be able to successfully do it. It would be great if you can help me change the hal.c file.

    ThanksPinMapping_F28069toF280049C.xlsx 

  • You may refer to below files that should be ok for DRV8301-Kit with F280049C controlCard, and you need to connect the J5-Pin6 to J12-Pin1 since there is not a GPIO map to the EN_GATE of drv8301.

    4682.hal.c
    //#############################################################################
    // $TI Release: MotorControl SDK v0.02.00.00 $
    // $Release Date: Fri Jun  8 14:48:41 CDT 2018 $
    // $Copyright:
    // Copyright (C) 2017-2018 Texas Instruments Incorporated - http://www.ti.com/
    //
    // 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.
    // $
    //#############################################################################
    
    //! \file   solutions/drv8301_hc_c2_kit/f28004x/drivers/hal.c
    //! \brief  Contains the various functions related to the HAL object
    //!
    // **************************************************************************
    // the includes
    
    // drivers
    
    // modules
    #include "user.h"
    
    // platforms
    #include "hal.h"
    #include "hal_obj.h"
    
    // libraries
    #include "libraries/datalog/source/datalog.h"
    
    #ifdef _FLASH
    #pragma CODE_SECTION(Flash_initModule, ".TI.ramfunc");
    #endif
    
    // **************************************************************************
    // the defines
    
    
    // **************************************************************************
    // the globals
    
    
    // **************************************************************************
    // the functions
    void HAL_cal(HAL_Handle handle)
    {
    
      return;
    } // end of HAL_cal() function
    
    void HAL_disableGlobalInts(HAL_Handle handle)
    {
    
      // disable global interrupts
      Interrupt_disableMaster();
    
      return;
    } // end of HAL_disableGlobalInts() function
    
    void HAL_disableWdog(HAL_Handle halHandle)
    {
    
      // disable watchdog
      SysCtl_disableWatchdog();
    
      return;
    } // end of HAL_disableWdog() function
    
    void HAL_enableAdcInts(HAL_Handle handle)
    {
        HAL_Obj *obj = (HAL_Obj *)handle;
    
        // enable the PIE interrupts associated with the ADC interrupts
        Interrupt_enable(INT_ADCB1);        //B2
    
        // enable the ADC interrupts
        ADC_enableInterrupt(obj->adcHandle[1], ADC_INT_NUMBER1);
    
        // enable the cpu interrupt for ADC interrupts
        Interrupt_enableInCPU(INTERRUPT_CPU_INT1);
    
        return;
    } // end of HAL_enableAdcInts() function
    
    void HAL_enableAdcIntsToTriggerCLA(HAL_Handle handle)
    {
        HAL_Obj *obj = (HAL_Obj *)handle;
    
        // enable the ADC interrupts
        // RC2/C1
        ADC_enableInterrupt(obj->adcHandle[2], ADC_INT_NUMBER1);
    
        return;
    } // end of HAL_enableAdcIntsToTriggerCLA() function
    
    
    void HAL_enableDebugInt(HAL_Handle handle)
    {
    
        // enable debug events
        ERTM;
    
        return;
    } // end of HAL_enableDebugInt() function
    
    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)
    {
    
        // enable global interrupts
        Interrupt_enableMaster();
    
        return;
    } // end of HAL_enableGlobalInts() function
    
    // TODO: HAL_init
    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;
    
      // disable watchdog
      SysCtl_disableWatchdog();
    
      // initialize the ADC handles
      obj->adcHandle[0] = ADCA_BASE;
      obj->adcHandle[1] = ADCB_BASE;
      obj->adcHandle[2] = ADCC_BASE;
    
      // initialize the ADC results
      obj->adcResult[0] = ADCARESULT_BASE;
      obj->adcResult[1] = ADCBRESULT_BASE;
      obj->adcResult[2] = ADCCRESULT_BASE;
    
      // initialize CLA handle
      obj->claHandle = CLA1_BASE;
    
      // initialize SCI handle
      obj->sciHandle[0] = SCIA_BASE;        //!< the SCIA handle
      obj->sciHandle[1] = SCIB_BASE;        //!< the SCIB handle
    
      // initialize SPI handle
      obj->spiHandle[0] = SPIA_BASE;        //!< the SPIA handle
      obj->spiHandle[1] = SPIB_BASE;        //!< the SPIB handle
    
      // initialize DMA handle
      obj->dmaHandle = DMA_BASE;            //!< the DMA handle
    
      // initialize DMA channel handle
      obj->dmaChHandle[0] = DMA_CH1_BASE;   //!< the DMA Channel handle
      obj->dmaChHandle[1] = DMA_CH2_BASE;   //!< the DMA Channel handle
      obj->dmaChHandle[2] = DMA_CH3_BASE;   //!< the DMA Channel handle
      obj->dmaChHandle[3] = DMA_CH4_BASE;   //!< the DMA Channel handle
    
      // initialize PWM handles for Motor 1
      obj->pwmHandle[0] = EPWM1_BASE;
      obj->pwmHandle[1] = EPWM2_BASE;
      obj->pwmHandle[2] = EPWM3_BASE;
    
      // initialize PGA handle
      obj->pgaHandle[0] = PGA1_BASE;        //!< the PGA handle
      obj->pgaHandle[1] = PGA3_BASE;        //!< the PGA handle
      obj->pgaHandle[2] = PGA5_BASE;        //!< the PGA handle
    
      // initialize CMPSS handle
      obj->cmpssHandle[0] = CMPSS1_BASE;    //!< the CMPSS handle
      obj->cmpssHandle[1] = CMPSS3_BASE;    //!< the CMPSS handle
      obj->cmpssHandle[2] = CMPSS5_BASE;    //!< the CMPSS handle
    
      // initialize DAC handle
      obj->dacHandle[0] = DACA_BASE;        //!< the DAC handle
      obj->dacHandle[1] = DACB_BASE;        //!< the DAC handle
    
      // initialize timer handles
      obj->timerHandle[0] = CPUTIMER0_BASE;
      obj->timerHandle[1] = CPUTIMER1_BASE;
      obj->timerHandle[2] = CPUTIMER2_BASE;
    
      // initialize pwmdac handles
      obj->pwmDacHandle[0] = EPWM8_BASE;
      obj->pwmDacHandle[1] = EPWM8_BASE;
      obj->pwmDacHandle[2] = EPWM7_BASE;
      obj->pwmDacHandle[3] = EPWM4_BASE;
    
      // initialize drv8301 interface
      obj->drv8301Handle = DRV8301_init(&obj->drv8301);
    
      return(handle);
    } // end of HAL_init() function
    
    // TODO: HAL_setParams
    void HAL_setParams(HAL_Handle handle)
    {
      HAL_setNumCurrentSensors(handle,USER_NUM_CURRENT_SENSORS);
      HAL_setNumVoltageSensors(handle,USER_NUM_VOLTAGE_SENSORS);
    
      // disable global interrupts
      Interrupt_disableMaster();
    
      // Disable the watchdog
      SysCtl_disableWatchdog();
    
    #ifdef _FLASH
      //
      // Copy time critical code and flash setup code to RAM. This includes the
      // following functions: InitFlash();
      //
      // The RamfuncsLoadStart, RamfuncsLoadSize, and RamfuncsRunStart symbols
      // are created by the linker. Refer to the device .cmd file.
      //
      memcpy(&RamfuncsRunStart, &RamfuncsLoadStart, (size_t)&RamfuncsLoadSize);
    #endif
    
      // Disable DC-DC controller
      ASysCtl_disableDCDC();
    
      // Enable temperature sensor
      ASysCtl_enableTemperatureSensor();
    
      // initialize the interrupt controller
      Interrupt_initModule();
    
      // init vector table
      Interrupt_initVectorTable();
    
      // Set up PLL control and clock dividers
      // PLLSYSCLK = 20MHz (XTAL_OSC) * 10 (IMULT) * 1 (FMULT) / 2 (PLLCLK_BY_2)
      SysCtl_setClock(SYSCTL_OSCSRC_XTAL |
                      SYSCTL_IMULT(10) |
                      SYSCTL_FMULT_NONE |
                      SYSCTL_SYSDIV(2) |
                      SYSCTL_PLL_ENABLE);
    
      // These asserts will check that the #defines for the clock rates in
      // device.h match the actual rates that have been configured. If they do
      // not match, check that the calculations of DEVICE_SYSCLK_FREQ and
      // DEVICE_LSPCLK_FREQ are accurate. Some examples will not perform as
      // expected if these are not correct.
      //
      ASSERT(SysCtl_getClock(DEVICE_OSCSRC_FREQ) == DEVICE_SYSCLK_FREQ);
      ASSERT(SysCtl_getLowSpeedClock(DEVICE_OSCSRC_FREQ) == DEVICE_LSPCLK_FREQ);
    
    
      // run the device calibration
      HAL_cal(handle);
    
      // setup the peripheral clocks
      HAL_setupPeripheralClks(handle);
    
    #ifdef CLA
      // setup CLA
      HAL_setupCLA(handle);
    #endif
    
      // setup the GPIOs
      HAL_setupGpios(handle);
    
    #ifdef _FLASH
      //
      // Call Flash Initialization to setup flash waitstates. This function must
      // reside in RAM.
      Flash_initModule(FLASH0CTRL_BASE, FLASH0ECC_BASE, DEVICE_FLASH_WAITSTATES);
    #endif
    
      // setup the PWM DACs
      HAL_setupPwmDacs(handle, USER_SYSTEM_FREQ_MHz);
    
      // setup the ADCs
      HAL_setupAdcs(handle);        //
    
      // setup the PGAs
      HAL_setupPGAs(handle);        //
    
      // setup the Dacs
      HAL_setupDACs(handle);        //
    
      // setup the CMPSSs
      HAL_setupCMPSSs(handle);      //
    
      // setup the PWMs
      HAL_setupPwms(handle,
                    USER_SYSTEM_FREQ_MHz,
                    USER_PWM_PERIOD_usec,
                    USER_NUM_PWM_TICKS_PER_ISR_TICK);
    
      // set the current scale factor
      HAL_setCurrentScaleFactor(handle,USER_CURRENT_SF);
    
      // set the voltage scale factor
      HAL_setVoltageScaleFactor(handle,USER_VOLTAGE_SF);
    
      // setup the timers
      HAL_setupTimers(handle, USER_SYSTEM_FREQ_MHz);
    
      // setup the sci
      HAL_setupSciA(handle);        //
    
      // setup the spiB for DRV8301_Kit_RevD
      HAL_setupSpiB(handle);        //
    
      // setup the drv8301 interface
      HAL_setupGate(handle);
    
      return;
    } // end of HAL_setParams() function
    
    // TODO: HAL_setupAdcs
    void HAL_setupAdcs(HAL_Handle handle)
    {
      HAL_Obj *obj = (HAL_Obj *)handle;
    
      SysCtl_delay(100U);
      ADC_setVREF(obj->adcHandle[2], ADC_REFERENCE_INTERNAL, ADC_REFERENCE_3_3V);
      ADC_setVREF(obj->adcHandle[1], ADC_REFERENCE_INTERNAL, ADC_REFERENCE_3_3V);
      ADC_setVREF(obj->adcHandle[0], ADC_REFERENCE_INTERNAL, ADC_REFERENCE_3_3V);
      SysCtl_delay(100U);
    
      // Configure internal reference as 1.65*2 = 3.3
      ASysCtl_setAnalogReference1P65(ASYSCTL_VREFHIA |
                                     ASYSCTL_VREFHIB |
                                     ASYSCTL_VREFHIC);
    
      // Enable internal voltage reference
      ASysCtl_setAnalogReferenceInternal(ASYSCTL_VREFHIA |
                                         ASYSCTL_VREFHIB |
                                         ASYSCTL_VREFHIC);
    
    
      // Set main clock scaling factor (50MHz max clock for the ADC module)
      ADC_setPrescaler(obj->adcHandle[0], ADC_CLK_DIV_2_0);
      ADC_setPrescaler(obj->adcHandle[1], ADC_CLK_DIV_2_0);
      ADC_setPrescaler(obj->adcHandle[2], ADC_CLK_DIV_2_0);
    
      // set the ADC interrupt pulse generation to end of conversion
      ADC_setInterruptPulseMode(obj->adcHandle[0], ADC_PULSE_END_OF_CONV);
      ADC_setInterruptPulseMode(obj->adcHandle[1], ADC_PULSE_END_OF_CONV);
      ADC_setInterruptPulseMode(obj->adcHandle[2], ADC_PULSE_END_OF_CONV);
    
      // enable the ADCs
      ADC_enableConverter(obj->adcHandle[0]);
      ADC_enableConverter(obj->adcHandle[1]);
      ADC_enableConverter(obj->adcHandle[2]);
    
      // set priority of SOCs
      ADC_setSOCPriority(obj->adcHandle[0], ADC_PRI_ALL_HIPRI);
      ADC_setSOCPriority(obj->adcHandle[1], ADC_PRI_ALL_HIPRI);
      ADC_setSOCPriority(obj->adcHandle[2], ADC_PRI_ALL_HIPRI);
    
      // delay to allow ADCs to power up
      SysCtl_delay(1000U);
    
      // configure the interrupt sources
      // RB2/B2
      ADC_setInterruptSource(obj->adcHandle[1], ADC_INT_NUMBER1, ADC_SOC_NUMBER2);
    
      // configure the SOCs for hvkit_rev1p1
      // IA-FB - A6->RA0
      ADC_setupSOC(obj->adcHandle[0], ADC_SOC_NUMBER0, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN6, 14);
    
      // IB-FB - C1->RC0
      ADC_setupSOC(obj->adcHandle[2], ADC_SOC_NUMBER0, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN1, 14);
    
      // IC-FB - B15->RB0
      ADC_setupSOC(obj->adcHandle[1], ADC_SOC_NUMBER0, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN15, 14);
    
      // ADC-Vhb1 - C2->RC1
      ADC_setupSOC(obj->adcHandle[2], ADC_SOC_NUMBER1, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN2, 14);
    
      // ADC-Vhb2 - A9->RA1
      ADC_setupSOC(obj->adcHandle[0], ADC_SOC_NUMBER1, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN9, 14);
    
      // ADC-Vhb3 - B4->RB1
      ADC_setupSOC(obj->adcHandle[1], ADC_SOC_NUMBER1, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN4, 14);
    
      // VDCBUS -   B2->RB2. hvkit board has capacitor on Vbus feedback, so
      // the sampling doesn't need to be very long to get an accurate value
      ADC_setupSOC(obj->adcHandle[1], ADC_SOC_NUMBER2, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN2, 14);
    
      // Tspeed -   C4->RC2
      ADC_setupSOC(obj->adcHandle[2], ADC_SOC_NUMBER2, ADC_TRIGGER_EPWM1_SOCA,
                   ADC_CH_ADCIN4, 14);
    
      return;
    } // end of HAL_setupAdcs() function
    
    //uint16_t AdcOffsetMean=0;
    //uint32_t Sum=0;
    //uint16_t index=0,SampleSize=512;
    
    //
    void HAL_adcZeroOffsetCalibration(uint32_t base)
    {
        uint16_t AdcOffsetMean;
        uint32_t Sum;
        uint16_t index,SampleSize;
    
        // Adc Zero Offset Calibration
        // This is not typically necessary
        //      to achieve datasheet specified performance
        ADC_setupSOC(base, ADC_SOC_NUMBER0, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER1, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER2, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER3, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER4, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER5, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER6, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
        ADC_setupSOC(base, ADC_SOC_NUMBER7, ADC_TRIGGER_SW_ONLY,
                     ADC_CH_ADCIN13, 10);
    
        EALLOW;
        HWREGH(base + ADC_O_OFFTRIM) = 96;
        EDIS;
    //    ADC_setOffTrim(base, 96);
    
        //
        // Set SOC1 to set the interrupt 1 flag. Enable the interrupt and make
        // sure its flag is cleared.
        //
        ADC_setInterruptSource(base, ADC_INT_NUMBER1, ADC_SOC_NUMBER7);
        ADC_enableInterrupt(base, ADC_INT_NUMBER1);
        ADC_clearInterruptStatus(base, ADC_INT_NUMBER1);
    
        AdcOffsetMean=0;
        Sum=0;
        index=0;
        SampleSize=512;
    
        while( index < SampleSize)
        {
            ADC_forceSOC(base, ADC_SOC_NUMBER0);
            ADC_forceSOC(base, ADC_SOC_NUMBER1);
            ADC_forceSOC(base, ADC_SOC_NUMBER2);
            ADC_forceSOC(base, ADC_SOC_NUMBER3);
            ADC_forceSOC(base, ADC_SOC_NUMBER4);
            ADC_forceSOC(base, ADC_SOC_NUMBER5);
            ADC_forceSOC(base, ADC_SOC_NUMBER6);
            ADC_forceSOC(base, ADC_SOC_NUMBER7);
    
            SysCtl_delay(2000U);
    
            while(ADC_getInterruptStatus(base, ADC_INT_NUMBER1) == false)
            {
            }
    
            SysCtl_delay(100U);
    
            Sum += ADC_readResult(base, ADC_SOC_NUMBER0);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER1);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER2);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER3);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER4);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER5);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER6);
            Sum += ADC_readResult(base, ADC_SOC_NUMBER7);
    
            index += 8;
    
            ADC_clearInterruptStatus(base, ADC_INT_NUMBER1);
        }
    
        ADC_clearInterruptStatus(base, ADC_INT_NUMBER1);
    
        //Calculate average ADC sample value
        AdcOffsetMean = Sum / SampleSize;
    
        // delay to allow ADCs to power up
        SysCtl_delay(100U);
    
        EALLOW;
        HWREGH(base + ADC_O_OFFTRIM) = 96-AdcOffsetMean;
        EDIS;
    //    ADC_setOffTrim(base, 96-AdcOffsetMean);
    
        // delay to allow ADCs to power up
        SysCtl_delay(100U);
    
        return;
    }
    
    
    void HAL_setupPGAs(HAL_Handle handle)
    {
        return;
    } // end of HAL_setupPGAs() function
    
    // HAL_setupCMPSSs
    void HAL_setupCMPSSs(HAL_Handle handle)
    {
        return;
    } // end of HAL_setupCMPSSs() function
    
    void HAL_setupDACs(HAL_Handle handle)
    {
        return;
    } // end of HAL_setupDACs() function
    
    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
    
    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
    
      // configure the input x bar for TZ2 to pin 10, where Over Current is connected
      // this requires S2 of 180 to 100 Adapter card to be in the up position
      // connecting HSEC_60 with CCARD_83
      XBAR_setInputPin(XBAR_INPUT2, 10);
      XBAR_lockInput(XBAR_INPUT2);
    
      // configure the input x bar for TZ3 to pin 39, where Over Current is connected
      // this requires S3 of 180 to 100 Adapter card to be in the up position
      // connecting HSEC_60 with CCARD_83
      XBAR_setInputPin(XBAR_INPUT3, 39);
      XBAR_lockInput(XBAR_INPUT3);
    
      for(cnt=0;cnt<3;cnt++)
        {
          EPWM_enableTripZoneSignals(obj->pwmHandle[cnt],
                                     EPWM_TZ_SIGNAL_CBC6);
    
          EPWM_enableTripZoneSignals(obj->pwmHandle[cnt],
                                     EPWM_TZ_SIGNAL_OSHT2);
    
          EPWM_enableTripZoneSignals(obj->pwmHandle[cnt],
                                     EPWM_TZ_SIGNAL_OSHT3);
    
          // What do we want the OST/CBC events to do?
          // TZA events can force EPWMxA
          // TZB events can force EPWMxB
    
          EPWM_setTripZoneAction(obj->pwmHandle[cnt],
                                 EPWM_TZ_ACTION_EVENT_TZA,
                                 EPWM_TZ_ACTION_LOW);
          EPWM_setTripZoneAction(obj->pwmHandle[cnt],
                                 EPWM_TZ_ACTION_EVENT_TZB,
                                 EPWM_TZ_ACTION_LOW);
    
          // Clear any spurious fault
          EPWM_clearTripZoneFlag(obj->pwmHandle[cnt],
                                          EPWM_TZ_INTERRUPT_ALL);
        }
    
      return;
    } // end of HAL_setupFaults() function
    
    void HAL_setupGate(HAL_Handle handle)
    {
      HAL_Obj *obj = (HAL_Obj *)handle;
    
      DRV8301_setSpiHandle(obj->drv8301Handle,obj->spiHandle[1]);
      DRV8301_setGpioNumber(obj->drv8301Handle,DRV83XX_EN_GATE_GPIO);
    
      return;
    } // HAL_setupGate() function
    
    void HAL_setupGpios(HAL_Handle handle)
    {
        // EPWM1A->UH
        GPIO_setMasterCore(0, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_0_EPWM1A);
        GPIO_setDirectionMode(0, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(0, GPIO_PIN_TYPE_STD);
    
        // EPWM1B->UL
        GPIO_setMasterCore(1, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_1_EPWM1B);
        GPIO_setDirectionMode(1, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(1, GPIO_PIN_TYPE_STD);
    
        // EPWM2A->VH
        GPIO_setMasterCore(2, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_2_EPWM2A);
        GPIO_setDirectionMode(2, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(2, GPIO_PIN_TYPE_STD);
    
        // EPWM2B->VL
        GPIO_setMasterCore(3, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_3_EPWM2B);
        GPIO_setDirectionMode(3, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(3, GPIO_PIN_TYPE_STD);
    
        // EPWM3A->WH
        GPIO_setMasterCore(4, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_4_EPWM3A);
        GPIO_setDirectionMode(4, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(4, GPIO_PIN_TYPE_STD);
    
        // EPWM3B->WL
        GPIO_setMasterCore(5, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_5_EPWM3B);
        GPIO_setDirectionMode(5, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(5, GPIO_PIN_TYPE_STD);
    
        // EPWM4A->PWMDAC4
        GPIO_setMasterCore(6, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_6_EPWM4A);
    //    GPIO_setPinConfig(GPIO_6_GPIO6);
    //    GPIO_writePin(6, 0);
        GPIO_setDirectionMode(6, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(6, GPIO_PIN_TYPE_STD);
    
        // GPIO07->INPUT->STOP
        GPIO_setMasterCore(7, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_7_GPIO7);
        GPIO_setDirectionMode(7, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(7, GPIO_PIN_TYPE_STD);
    
        // GPIO08->Reserve
        GPIO_setMasterCore(8, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_8_GPIO8);
        GPIO_writePin(8, 1);
        GPIO_setDirectionMode(8, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(8, GPIO_PIN_TYPE_STD);
    
        // GPIO09->INPUT->Hall
        GPIO_setMasterCore(9, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_9_GPIO9);
        GPIO_setDirectionMode(9, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(9, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO10->INPUTXBAR->OCTW
        GPIO_setMasterCore(10, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_10_GPIO10);
        GPIO_setDirectionMode(10, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(10, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO11->INPUT->Hall
        GPIO_setMasterCore(11, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_11_GPIO11);
        GPIO_setDirectionMode(11, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(11, GPIO_PIN_TYPE_PULLUP);
    
        // EPWM8B->PWM-DAC3
        GPIO_setMasterCore(12, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_12_EPWM7A);
    //    GPIO_setPinConfig(GPIO_12_GPIO12);
    //    GPIO_writePin(12, 1);
        GPIO_setDirectionMode(12, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(12, GPIO_PIN_TYPE_STD);
    
        // GPIO13->INPUT->START
        GPIO_setMasterCore(13, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_13_GPIO13);
    //    GPIO_writePin(13, 0);
        GPIO_setDirectionMode(13, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(13, GPIO_PIN_TYPE_PULLUP);
    
        // EPWM8A->PWM-DAC1
        GPIO_setMasterCore(14, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_14_EPWM8A);
        GPIO_setDirectionMode(14, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(14, GPIO_PIN_TYPE_STD);
    
        // EPWM8B->PWM-DAC2
        GPIO_setMasterCore(15, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_15_EPWM8B);
        GPIO_setDirectionMode(15, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(15, GPIO_PIN_TYPE_STD);
    
        // GPIO16->INPUT->Hall
        GPIO_setMasterCore(16, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_16_GPIO16);
        GPIO_setDirectionMode(16, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(16, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO17->INPUT->Hall
        GPIO_setMasterCore(17, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_17_GPIO17);
        GPIO_setDirectionMode(17, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(17, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO18->Reserve (N/A for GPIO)
        GPIO_setMasterCore(18, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_18_GPIO18);
    //    GPIO_writePin(18, 1);
        GPIO_setDirectionMode(18, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(18, GPIO_PIN_TYPE_STD);
    
        // GPIO19->Reserve (N/A)
        GPIO_setMasterCore(19, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_19_GPIO19);
    //    GPIO_writePin(19, 1);
        GPIO_setDirectionMode(19, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(19, GPIO_PIN_TYPE_STD);
    
        // GPIO22->OUTPUT->STATUS/EN_GATE
        GPIO_setMasterCore(22, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_22_GPIO22);
        GPIO_writePin(22, 1);
        GPIO_setDirectionMode(22, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(22, GPIO_PIN_TYPE_STD);
    
        // GPIO23->OUTPUT->DC_CAL
        GPIO_setMasterCore(23, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_23_GPIO23);
        GPIO_writePin(23, 1);
        GPIO_setDirectionMode(23, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(23, GPIO_PIN_TYPE_STD);
    
        // GPIO24->SPISIMOB->SDI
        GPIO_setMasterCore(24, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_24_SPISIMOB);
        GPIO_setDirectionMode(24, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(24, GPIO_PIN_TYPE_STD);
    
        // GPIO25->SPISOMIB->SDO
        GPIO_setMasterCore(25, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_25_SPISOMIB);
        GPIO_setDirectionMode(25, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(25, GPIO_PIN_TYPE_STD);
    
        // GPIO26->SPICLKB->SCLK
        GPIO_setMasterCore(26, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_26_SPICLKB);
        GPIO_setDirectionMode(26, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(26, GPIO_PIN_TYPE_STD);
    
        // GPIO27->SPISTEB->SCS
        GPIO_setMasterCore(27, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_27_SPISTEB);
        GPIO_setDirectionMode(27, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(27, GPIO_PIN_TYPE_STD);
    
        // GPIO28->SCIRXDA
        GPIO_setMasterCore(28, GPIO_CORE_CPU1);
    //    GPIO_setPinConfig(GPIO_28_SCIRXDA);
    //    GPIO_setDirectionMode(28, GPIO_DIR_MODE_IN);
        GPIO_setPinConfig(GPIO_28_GPIO28);
        GPIO_writePin(28, 0);
        GPIO_setDirectionMode(28, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(28, GPIO_PIN_TYPE_STD);
        GPIO_writePin(28, 1);
    
        // GPIO29->SCITXDA
        GPIO_setMasterCore(29, GPIO_CORE_CPU1);
    //    GPIO_setPinConfig(GPIO_29_SCITXDA);
    //    GPIO_setDirectionMode(29, GPIO_DIR_MODE_OUT);
        GPIO_setPinConfig(GPIO_29_GPIO29);
        GPIO_writePin(29, 0);
        GPIO_setDirectionMode(29, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(29, GPIO_PIN_TYPE_STD);
        GPIO_writePin(29, 1);
    
        // GPIO30->CANRXA
        GPIO_setMasterCore(30, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_30_CANRXA);
        GPIO_setDirectionMode(30, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(30, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO31->EQEP1I
        GPIO_setMasterCore(31, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_31_EQEP1I);
        GPIO_setDirectionMode(31, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(31, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO32->CANTXA
        GPIO_setMasterCore(32, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_32_CANTXA);
        GPIO_setDirectionMode(31, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(32, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO33->Reserve
        GPIO_setMasterCore(33, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_33_GPIO33);
        GPIO_setDirectionMode(33, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(33, GPIO_PIN_TYPE_STD);
    
        // Control Card LED2
        GPIO_setMasterCore(34, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_34_GPIO34);
        GPIO_writePin(34, 1);
        GPIO_setDirectionMode(34, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(34, GPIO_PIN_TYPE_STD);
    
        // TDI
        GPIO_setMasterCore(35, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_35_TDI);
    
        // TDO
        GPIO_setMasterCore(37, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_37_TDO);
    
        // GPIO39->XBAR_IN->FAULT
        GPIO_setMasterCore(39, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_39_GPIO39);
        GPIO_setDirectionMode(39, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(39, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO40->EQEP1A
        GPIO_setMasterCore(40, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_40_EQEP1A);
        GPIO_setDirectionMode(40, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(40, GPIO_PIN_TYPE_STD);
    
        // GPIO41->Reserve
        GPIO_setMasterCore(41, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_41_GPIO41);
        GPIO_writePin(41, 1);
        GPIO_setDirectionMode(41, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(41, GPIO_PIN_TYPE_STD);
    
        // GPIO42->Reserve
        GPIO_setMasterCore(42, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_42_GPIO42);
        GPIO_writePin(42, 1);
        GPIO_setDirectionMode(42, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(42, GPIO_PIN_TYPE_STD);
    
        // GPIO43->Reserve
        GPIO_setMasterCore(43, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_43_GPIO43);
        GPIO_writePin(43, 1);
        GPIO_setDirectionMode(43, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(43, GPIO_PIN_TYPE_STD);
    
        // GPIO44->Reserve
        GPIO_setMasterCore(44, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_44_GPIO44);
        GPIO_writePin(44, 1);
        GPIO_setDirectionMode(44, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(44, GPIO_PIN_TYPE_STD);
    
        // GPIO45->Reserve
        GPIO_setMasterCore(45, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_45_GPIO45);
        GPIO_writePin(45, 1);
        GPIO_setDirectionMode(45, GPIO_DIR_MODE_OUT);
        GPIO_setPadConfig(45, GPIO_PIN_TYPE_STD);
    
        // GPIO46->Reserve
        GPIO_setMasterCore(46, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_46_GPIO46);
        GPIO_setDirectionMode(46, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(46, GPIO_PIN_TYPE_STD);
    
        // GPIO47->Reserve
        GPIO_setMasterCore(47, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_47_GPIO47);
        GPIO_setDirectionMode(47, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(47, GPIO_PIN_TYPE_STD);
    
        // GPIO48->Reserve
        GPIO_setMasterCore(48, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_48_GPIO48);
        GPIO_setDirectionMode(48, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(48, GPIO_PIN_TYPE_STD);
    
        // GPIO49->Reserve
        GPIO_setMasterCore(49, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_49_GPIO49);
        GPIO_setDirectionMode(49, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(49, GPIO_PIN_TYPE_STD);
    
        // GPIO50->Reserve
        GPIO_setMasterCore(50, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_50_GPIO50);
        GPIO_setDirectionMode(50, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(50, GPIO_PIN_TYPE_STD);
    
        // GPIO51->Reserve
        GPIO_setMasterCore(51, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_51_GPIO51);
        GPIO_setDirectionMode(51, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(51, GPIO_PIN_TYPE_STD);
    
        // GPIO52->Reserve
        GPIO_setMasterCore(52, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_52_GPIO52);
        GPIO_setDirectionMode(52, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(52, GPIO_PIN_TYPE_STD);
    
        // GPIO53->Reserve
        GPIO_setMasterCore(53, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_53_GPIO53);
        GPIO_setDirectionMode(53, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(53, GPIO_PIN_TYPE_STD);
    
        // GPIO54->Reserve
        GPIO_setMasterCore(54, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_54_GPIO54);
        GPIO_setDirectionMode(54, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(54, GPIO_PIN_TYPE_STD);
    
        // GPIO55->Reserve
        GPIO_setMasterCore(55, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_55_GPIO55);
        GPIO_setDirectionMode(55, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(55, GPIO_PIN_TYPE_STD);
    
        // GPIO56->Reserve
        GPIO_setMasterCore(56, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_56_GPIO56);
        GPIO_setDirectionMode(56, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(56, GPIO_PIN_TYPE_STD);
    
        // GPIO57->EQEP1B
        GPIO_setMasterCore(57, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_57_EQEP1B);
        GPIO_setDirectionMode(57, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(57, GPIO_PIN_TYPE_PULLUP);
    
        // GPIO58->Reserve
        GPIO_setMasterCore(58, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_58_GPIO58);
        GPIO_setDirectionMode(58, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(58, GPIO_PIN_TYPE_STD);
    
        // GPIO59->Reserve
        GPIO_setMasterCore(59, GPIO_CORE_CPU1);
        GPIO_setPinConfig(GPIO_59_GPIO59);
        GPIO_setDirectionMode(59, GPIO_DIR_MODE_IN);
        GPIO_setPadConfig(59, GPIO_PIN_TYPE_STD);
    
        return;
    }  // end of HAL_setupGpios() function
    
    #ifdef CLA
    void HAL_setupCLA(HAL_Handle handle)
    {
        HAL_Obj  *obj = (HAL_Obj *)handle;
        uint32_t tmp_vec;
    
        //Enable CLA1 clock
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CLA1);
    
        // configure LS memory through LSxMSEL register to allow sharing between CPU and CLA
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS0, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS1, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS2, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS3, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS4, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS5, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS6, MEMCFG_LSRAMMASTER_CPU_CLA1);
        MemCfg_setLSRAMMasterSel(MEMCFG_SECT_LS7, MEMCFG_LSRAMMASTER_CPU_CLA1);
    
        // configure what memory is for CLA program through the LSxCLAPGM register
        MemCfg_setCLAMemType(MEMCFG_SECT_LS0, MEMCFG_CLA_MEM_DATA);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS1, MEMCFG_CLA_MEM_DATA);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS2, MEMCFG_CLA_MEM_PROGRAM);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS3, MEMCFG_CLA_MEM_DATA);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS4, MEMCFG_CLA_MEM_PROGRAM);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS5, MEMCFG_CLA_MEM_PROGRAM);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS6, MEMCFG_CLA_MEM_PROGRAM);
        MemCfg_setCLAMemType(MEMCFG_SECT_LS7, MEMCFG_CLA_MEM_PROGRAM);
    
        tmp_vec = (uint32_t)(&task_initModules);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_1, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&task_mainISR);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_2, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&task_mainLoop);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_3, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&cla1Task4);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_4, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&cla1Task5);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_5, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&cla1Task6);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_6, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&cla1Task7);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_7, (uint16_t)tmp_vec);
    
        tmp_vec = (uint32_t)(&cla1Task8);
        CLA_mapTaskVector(obj->claHandle, CLA_MVECT_8, (uint16_t)tmp_vec);
    
        CLA_enableTasks(obj->claHandle, CLA_TASKFLAG_ALL);
    
        CLA_enableBackgroundTask(obj->claHandle);
    
        CLA_disableHardwareTrigger(obj->claHandle);
    
        tmp_vec = (uint32_t)(&cla_EST_run_BackgroundTask);
        CLA_mapBackgroundTaskVector(obj->claHandle, (uint16_t)tmp_vec);
    
        CLA_setTriggerSource(CLA_TASK_2, CLA_TRIGGER_SOFTWARE);
    
        return;
    } // end of HAL_setupCLA() function
    #endif
    
    void HAL_setupPeripheralClks(HAL_Handle handle)
    {
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CLA1);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_DMA);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_TIMER0);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_TIMER1);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_TIMER2);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_HRPWM);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_TBCLKSYNC);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM1);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM2);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM3);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM4);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM5);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM6);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM7);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EPWM8);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP1);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP2);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP3);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP4);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP5);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP6);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_ECAP7);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EQEP1);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_EQEP2);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_SD1);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_SCIA);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_SCIB);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_SPIA);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_SPIB);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_I2CA);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CANA);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CANB);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_ADCA);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_ADCB);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_ADCC);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS1);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS2);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS3);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS4);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS5);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS6);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_CMPSS7);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA1);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA2);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA3);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA4);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA5);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA6);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_PGA7);
    
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_DACA);
        SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_DACB);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_FSITXA);
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_FSIRXA);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_LINA);
    
        SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_PMBUSA);
    
        return;
    } // end of HAL_setupPeripheralClks() 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 / (float_t)2.0);
      uint_least8_t  cnt;
    
      // disable the ePWM module time base clock sync signal
      // to synchronize all of the PWMs
      SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_TBCLKSYNC);
    
      // turns off the outputs of the EPWM peripherals which will put the power
      // switches into a high impedance state.
    //  EPWM_forceTripZoneEvent(obj->pwmHandle[0], EPWM_TZ_FORCE_EVENT_OST);
    //  EPWM_forceTripZoneEvent(obj->pwmHandle[1], EPWM_TZ_FORCE_EVENT_OST);
    //  EPWM_forceTripZoneEvent(obj->pwmHandle[2], EPWM_TZ_FORCE_EVENT_OST);
    
      for(cnt=0;cnt<3;cnt++)
        {
          // setup the Time-Base Control Register (TBCTL)
          EPWM_setTimeBaseCounterMode(obj->pwmHandle[cnt],
                                      EPWM_COUNTER_MODE_UP_DOWN);
          EPWM_disablePhaseShiftLoad(obj->pwmHandle[cnt]);
          EPWM_setPeriodLoadMode(obj->pwmHandle[cnt], EPWM_PERIOD_DIRECT_LOAD);
          EPWM_setSyncOutPulseMode(obj->pwmHandle[cnt],
                                   EPWM_SYNC_OUT_PULSE_ON_SOFTWARE);
          EPWM_setClockPrescaler(obj->pwmHandle[cnt], EPWM_CLOCK_DIVIDER_1,
                                   EPWM_HSCLOCK_DIVIDER_1);
          EPWM_setCountModeAfterSync(obj->pwmHandle[cnt],
                                     EPWM_COUNT_MODE_UP_AFTER_SYNC);
          EPWM_setEmulationMode(obj->pwmHandle[cnt], EPWM_EMULATION_FREE_RUN);
    
          // setup the Timer-Based Phase Register (TBPHS)
          EPWM_setPhaseShift(obj->pwmHandle[cnt], 0);
    
          // setup the Time-Base Counter Register (TBCTR)
          EPWM_setTimeBaseCounter(obj->pwmHandle[cnt], 0);
    
          // setup the Time-Base Period Register (TBPRD)
          // set to zero initially
          EPWM_setTimeBasePeriod(obj->pwmHandle[cnt], 0);
    
          // setup the Counter-Compare Control Register (CMPCTL)
          EPWM_setCounterCompareShadowLoadMode(obj->pwmHandle[cnt],
                                               EPWM_COUNTER_COMPARE_A,
                                               EPWM_COMP_LOAD_ON_CNTR_ZERO);
    
          EPWM_disableCounterCompareShadowLoadMode(obj->pwmHandle[cnt],
                                               EPWM_COUNTER_COMPARE_B);
    
    										         //
          EPWM_disableCounterCompareShadowLoadMode(obj->pwmHandle[cnt],
                                               EPWM_COUNTER_COMPARE_C);
    
          //
          EPWM_disableCounterCompareShadowLoadMode(obj->pwmHandle[cnt],
                                               EPWM_COUNTER_COMPARE_D);
    										   
          // setup the Action-Qualifier Output A Register (AQCTLA)
          EPWM_setActionQualifierAction(obj->pwmHandle[cnt],
                                        EPWM_AQ_OUTPUT_A,
                                        EPWM_AQ_OUTPUT_HIGH,
                                        EPWM_AQ_OUTPUT_ON_TIMEBASE_UP_CMPA);
    
          EPWM_setActionQualifierAction(obj->pwmHandle[cnt],
                                        EPWM_AQ_OUTPUT_A,
                                        EPWM_AQ_OUTPUT_LOW,
                                        EPWM_AQ_OUTPUT_ON_TIMEBASE_DOWN_CMPA);
    
          // setup the Action-qualifier Continuous Software Force Register
          // (AQCSFRC)
          EPWM_setActionQualifierContSWForceAction(obj->pwmHandle[cnt],
                                                   EPWM_AQ_OUTPUT_B,
                                                   EPWM_AQ_SW_OUTPUT_HIGH);
    
          // setup the Dead-Band Generator Control Register (DBCTL)
          EPWM_setDeadBandDelayMode(obj->pwmHandle[cnt], EPWM_DB_RED, true);
          EPWM_setDeadBandDelayMode(obj->pwmHandle[cnt], EPWM_DB_FED, true);
    
          // select EPWMA as the input to the dead band generator
          EPWM_setRisingEdgeDeadBandDelayInput(obj->pwmHandle[cnt],
                                               EPWM_DB_INPUT_EPWMA);
    
          // configure the right polarity for active high complementary config.
          EPWM_setDeadBandDelayPolarity(obj->pwmHandle[cnt],
                                        EPWM_DB_RED,
                                        EPWM_DB_POLARITY_ACTIVE_HIGH);
          EPWM_setDeadBandDelayPolarity(obj->pwmHandle[cnt],
                                        EPWM_DB_FED,
                                        EPWM_DB_POLARITY_ACTIVE_LOW);
    
          // setup the Dead-Band Rising Edge Delay Register (DBRED)
          EPWM_setRisingEdgeDelayCount(obj->pwmHandle[cnt],HAL_PWM_DBRED_CNT);
    
          // setup the Dead-Band Falling Edge Delay Register (DBFED)
          EPWM_setFallingEdgeDelayCount(obj->pwmHandle[cnt],HAL_PWM_DBFED_CNT);
    
          // setup the PWM-Chopper Control Register (PCCTL)
          EPWM_disableChopper(obj->pwmHandle[cnt]);
    
          // setup the Trip Zone Select Register (TZSEL)
          EPWM_disableTripZoneSignals(obj->pwmHandle[cnt],
                                      EPWM_TZ_SIGNAL_CBC1 |
                                      EPWM_TZ_SIGNAL_CBC2 |
                                      EPWM_TZ_SIGNAL_CBC3 |
                                      EPWM_TZ_SIGNAL_CBC4 |
                                      EPWM_TZ_SIGNAL_CBC5 |
                                      EPWM_TZ_SIGNAL_CBC6 |
                                      EPWM_TZ_SIGNAL_DCAEVT2 |
                                      EPWM_TZ_SIGNAL_DCBEVT2 |
                                      EPWM_TZ_SIGNAL_OSHT1 |
                                      EPWM_TZ_SIGNAL_OSHT2 |
                                      EPWM_TZ_SIGNAL_OSHT3 |
                                      EPWM_TZ_SIGNAL_OSHT4 |
                                      EPWM_TZ_SIGNAL_OSHT5 |
                                      EPWM_TZ_SIGNAL_OSHT6 |
                                      EPWM_TZ_SIGNAL_DCAEVT1 |
                                      EPWM_TZ_SIGNAL_DCBEVT1);
        }
    
      // setup the Event Trigger Selection Register (ETSEL)
      EPWM_disableInterrupt(obj->pwmHandle[0]);
      EPWM_setADCTriggerSource(obj->pwmHandle[0],
                               EPWM_SOC_A,
                               EPWM_SOC_TBCTR_D_CMPC);
    
      EPWM_enableADCTrigger(obj->pwmHandle[0], EPWM_SOC_A);
    
      // setup the Event Trigger Prescale Register (ETPS)
      if(numPwmTicksPerIsrTick > 15)
        {
          EPWM_setInterruptEventCount(obj->pwmHandle[0], 15);
          EPWM_setADCTriggerEventPrescale(obj->pwmHandle[0], EPWM_SOC_A, 15);
        }
      else if(numPwmTicksPerIsrTick < 1)
        {
          EPWM_setInterruptEventCount(obj->pwmHandle[0], 1);
          EPWM_setADCTriggerEventPrescale(obj->pwmHandle[0], EPWM_SOC_A, 1);
        }
      else
        {
          EPWM_setInterruptEventCount(obj->pwmHandle[0], numPwmTicksPerIsrTick);
          EPWM_setADCTriggerEventPrescale(obj->pwmHandle[0],
                                          EPWM_SOC_A,
                                          numPwmTicksPerIsrTick);
        }
    
      // setup the Event Trigger Clear Register (ETCLR)
      EPWM_clearEventTriggerInterruptFlag(obj->pwmHandle[0]);
      EPWM_clearADCTriggerFlag(obj->pwmHandle[0], EPWM_SOC_A);
    
      // since the PWM is configured as an up/down counter, the period register is
      // set to one-half of the desired PWM period
      EPWM_setTimeBasePeriod(obj->pwmHandle[0], halfPeriod_cycles);
      EPWM_setTimeBasePeriod(obj->pwmHandle[1], halfPeriod_cycles);
      EPWM_setTimeBasePeriod(obj->pwmHandle[2], halfPeriod_cycles);
    
        // write the PWM data value  for ADC trigger
      EPWM_setCounterCompareValue(obj->pwmHandle[0],
                                  EPWM_COUNTER_COMPARE_C,
                                  5);
    							  
      // enable the ePWM module time base clock sync signal
      SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_TBCLKSYNC);
    
      return;
    }  // end of HAL_setupPwms() function
    
    void HAL_setupPwmDacs(HAL_Handle handle,
                       const float_t systemFreq_MHz)
    {
      HAL_Obj       *obj = (HAL_Obj *)handle;
      uint16_t       halfPeriod_cycles = (uint16_t)(systemFreq_MHz*(float_t)(1000.0/100.0/2.0));    //100kHz
      uint_least8_t  cnt;
    
      // disable the ePWM module time base clock sync signal
      // to synchronize all of the PWMs
      SysCtl_disablePeripheral(SYSCTL_PERIPH_CLK_TBCLKSYNC);
    
      for(cnt=0;cnt<4;cnt++)
        {
          // setup the Time-Base Control Register (TBCTL)
          EPWM_setTimeBaseCounterMode(obj->pwmDacHandle[cnt],
                                      EPWM_COUNTER_MODE_UP_DOWN);
          EPWM_disablePhaseShiftLoad(obj->pwmDacHandle[cnt]);
          EPWM_setPeriodLoadMode(obj->pwmDacHandle[cnt], EPWM_PERIOD_DIRECT_LOAD);
          EPWM_setSyncOutPulseMode(obj->pwmDacHandle[cnt],
                                   EPWM_SYNC_OUT_PULSE_ON_SOFTWARE);
          EPWM_setClockPrescaler(obj->pwmDacHandle[cnt], EPWM_CLOCK_DIVIDER_1,
                                   EPWM_HSCLOCK_DIVIDER_1);
          EPWM_setCountModeAfterSync(obj->pwmDacHandle[cnt],
                                     EPWM_COUNT_MODE_UP_AFTER_SYNC);
          EPWM_setEmulationMode(obj->pwmDacHandle[cnt], EPWM_EMULATION_FREE_RUN);
    
          // setup the Timer-Based Phase Register (TBPHS)
          EPWM_setPhaseShift(obj->pwmDacHandle[cnt], 0);
    
          // setup the Time-Base Counter Register (TBCTR)
          EPWM_setTimeBaseCounter(obj->pwmDacHandle[cnt], 0);
    
          // setup the Time-Base Period Register (TBPRD)
          // set to zero initially
          EPWM_setTimeBasePeriod(obj->pwmDacHandle[cnt], 0);
    
          // setup the Counter-Compare Control Register (CMPCTL)
          EPWM_setCounterCompareShadowLoadMode(obj->pwmDacHandle[cnt],
                                               EPWM_COUNTER_COMPARE_A,
                                               EPWM_COMP_LOAD_ON_CNTR_ZERO);
    
          // setup the Action-Qualifier Output A Register (AQCTLA)
          EPWM_setActionQualifierAction(obj->pwmDacHandle[cnt],
                                        EPWM_AQ_OUTPUT_A,
                                        EPWM_AQ_OUTPUT_HIGH,
                                        EPWM_AQ_OUTPUT_ON_TIMEBASE_UP_CMPA);
    
          EPWM_setActionQualifierAction(obj->pwmDacHandle[cnt],
                                        EPWM_AQ_OUTPUT_A,
                                        EPWM_AQ_OUTPUT_LOW,
                                        EPWM_AQ_OUTPUT_ON_TIMEBASE_DOWN_CMPA);
    
    
          // setup the Action-Qualifier Output B Register (AQCTLB)
          EPWM_setActionQualifierAction(obj->pwmDacHandle[cnt],
                                        EPWM_AQ_OUTPUT_B,
                                        EPWM_AQ_OUTPUT_HIGH,
                                        EPWM_AQ_OUTPUT_ON_TIMEBASE_UP_CMPB);
    
          EPWM_setActionQualifierAction(obj->pwmDacHandle[cnt],
                                        EPWM_AQ_OUTPUT_B,
                                        EPWM_AQ_OUTPUT_LOW,
                                        EPWM_AQ_OUTPUT_ON_TIMEBASE_DOWN_CMPB);
    
    
          // setup the Dead-Band Generator Control Register (DBCTL)
          EPWM_setDeadBandDelayMode(obj->pwmDacHandle[cnt], EPWM_DB_RED, false);
          EPWM_setDeadBandDelayMode(obj->pwmDacHandle[cnt], EPWM_DB_FED, false);
    
          // setup the PWM-Chopper Control Register (PCCTL)
          EPWM_disableChopper(obj->pwmDacHandle[cnt]);
    
          // setup the Trip Zone Select Register (TZSEL)
          EPWM_disableTripZoneSignals(obj->pwmDacHandle[cnt],
                                      EPWM_TZ_SIGNAL_CBC1 |
                                      EPWM_TZ_SIGNAL_CBC2 |
                                      EPWM_TZ_SIGNAL_CBC3 |
                                      EPWM_TZ_SIGNAL_CBC4 |
                                      EPWM_TZ_SIGNAL_CBC5 |
                                      EPWM_TZ_SIGNAL_CBC6 |
                                      EPWM_TZ_SIGNAL_DCAEVT2 |
                                      EPWM_TZ_SIGNAL_DCBEVT2 |
                                      EPWM_TZ_SIGNAL_OSHT1 |
                                      EPWM_TZ_SIGNAL_OSHT2 |
                                      EPWM_TZ_SIGNAL_OSHT3 |
                                      EPWM_TZ_SIGNAL_OSHT4 |
                                      EPWM_TZ_SIGNAL_OSHT5 |
                                      EPWM_TZ_SIGNAL_OSHT6 |
                                      EPWM_TZ_SIGNAL_DCAEVT1 |
                                      EPWM_TZ_SIGNAL_DCBEVT1);
    
          // since the PWM is configured as an up/down counter, the period register is
          // set to one-half of the desired PWM period
          EPWM_setTimeBasePeriod(obj->pwmDacHandle[cnt], halfPeriod_cycles);
        }
    
      // enable the ePWM module time base clock sync signal
      SysCtl_enablePeripheral(SYSCTL_PERIPH_CLK_TBCLKSYNC);
    
      return;
    }  // end of HAL_setupPwms() function
    
    #ifdef _EQEP_EN_
    void HAL_setupQEP(HAL_Handle handle, HAL_QepSelect_e qep)
    {
      HAL_Obj   *obj = (HAL_Obj *)handle;
    
      //
      // Configure the decoder for quadrature count mode
      //
      EQEP_setDecoderConfig(obj->qepHandle[qep], (EQEP_CONFIG_1X_RESOLUTION |
                                         EQEP_CONFIG_QUADRATURE |
                                         EQEP_CONFIG_NO_SWAP));
    
      EQEP_setEmulationMode(obj->qepHandle[qep], EQEP_EMULATIONMODE_RUNFREE);
    
      //
      // Configure the position counter to reset on an index event
      //
      EQEP_setPositionCounterConfig(obj->qepHandle[qep], EQEP_POSITION_RESET_IDX,
                                    0xFFFFFFFF);
    
      //
      // Enable the unit timer, setting the frequency to 100 Hz
      //
      EQEP_enableUnitTimer(obj->qepHandle[qep], (DEVICE_SYSCLK_FREQ / 100));
    
      //
      // Configure the position counter to be latched on a unit time out
      //
      EQEP_setLatchMode(obj->qepHandle[qep], EQEP_LATCH_UNIT_TIME_OUT);
    
      //
      // Enable the eQEP module
      //
      EQEP_enableModule(obj->qepHandle[qep]);
    
      //
      // Configure and enable the edge-capture unit. The capture clock divider is
      // SYSCLKOUT/64. The unit-position event divider is QCLK/32.
      //
      EQEP_setCaptureConfig(obj->qepHandle[qep], EQEP_CAPTURE_CLK_DIV_64,
                            EQEP_UNIT_POS_EVNT_DIV_32);
    
      EQEP_enableCapture(obj->qepHandle[qep]);
    
      return;
    }
    #endif
    
    
    void HAL_setupSciA(HAL_Handle halHandle)
    {
      HAL_Obj *obj = (HAL_Obj *)halHandle;
    
      // Initialize SCIA and its FIFO.
      SCI_performSoftwareReset(obj->sciHandle[0]);
    
      // Configure SCIA for echoback.
      SCI_setConfig(obj->sciHandle[0], DEVICE_LSPCLK_FREQ, 9600, (SCI_CONFIG_WLEN_8 |
                                                          SCI_CONFIG_STOP_ONE |
                                                          SCI_CONFIG_PAR_NONE));
      SCI_resetChannels(obj->sciHandle[0]);
    
      SCI_resetRxFIFO(obj->sciHandle[0]);
    
      SCI_resetTxFIFO(obj->sciHandle[0]);
    
      SCI_clearInterruptStatus(obj->sciHandle[0], SCI_INT_TXFF | SCI_INT_RXFF);
    
      SCI_enableFIFO(obj->sciHandle[0]);
    
      SCI_enableModule(obj->sciHandle[0]);
    
      SCI_performSoftwareReset(obj->sciHandle[0]);
    
    }  // end of DRV_setupSci() function
    
    void HAL_setupSpiA(HAL_Handle handle)
    {
      HAL_Obj   *obj = (HAL_Obj *)handle;
    
      // Must put SPI into reset before configuring it
      SPI_disableModule(obj->spiHandle[0]);
    
      // SPI configuration. Use a 1MHz SPICLK and 16-bit word size.
      SPI_setConfig(obj->spiHandle[0], DEVICE_LSPCLK_FREQ, SPI_PROT_POL0PHA0,
                    SPI_MODE_MASTER, 1000000, 16);
    
      SPI_enableLoopback(obj->spiHandle[0]);
    
      SPI_setEmulationMode(obj->spiHandle[0], SPI_EMULATION_STOP_AFTER_TRANSMIT);
    
      // Configuration complete. Enable the module.
      SPI_enableModule(obj->spiHandle[0]);
    
      return;
    }  // end of HAL_setupSpiA() function
    
    void HAL_setupSpiB(HAL_Handle handle)
    {
      HAL_Obj   *obj = (HAL_Obj *)handle;
    
      // Must put SPI into reset before configuring it
      SPI_disableModule(obj->spiHandle[1]);
    
      // SPI configuration. Use a 1MHz SPICLK and 16-bit word size.
      SPI_setConfig(obj->spiHandle[1], DEVICE_LSPCLK_FREQ, SPI_PROT_POL0PHA0,
                    SPI_MODE_MASTER, 500000, 16);
    
      SPI_disableLoopback(obj->spiHandle[1]);
    
      SPI_setEmulationMode(obj->spiHandle[1], SPI_EMULATION_FREE_RUN);
    
      SPI_enableFIFO(obj->spiHandle[1]);
    //SPI_setTxDelay(obj->spiHandle[1], 0x0018);
      HWREGH((obj->spiHandle[1])+SPI_O_FFCT) = 0x0018;
    
      SPI_clearInterruptStatus(obj->spiHandle[1], SPI_INT_TXFF);
    //  SPI_setFIFOInterruptLevel(obj->spiHandle[1], SPI_FIFO_TX2, SPI_FIFO_RX2);
    //  SPI_enableInterrupt(obj->spiHandle[1], SPI_INT_TXFF);
    
      // Configuration complete. Enable the module.
      SPI_enableModule(obj->spiHandle[1]);
    
      return;
    }  // end of HAL_setupSpiB() function
    
    void HAL_setupTimers(HAL_Handle handle, const float_t systemFreq_MHz)
    {
      HAL_Obj  *obj = (HAL_Obj *)handle;
    
      //1ms
      uint32_t timerPeriod_1ms = (uint32_t)(systemFreq_MHz *
                                  (float_t)1000.0) - 1;
    
      // use timer 0 for CPU usage diagnostics
      CPUTimer_setPreScaler(obj->timerHandle[0], 0);
      CPUTimer_setEmulationMode(obj->timerHandle[0],
                                CPUTIMER_EMULATIONMODE_RUNFREE);
      CPUTimer_setPeriod(obj->timerHandle[0], timerPeriod_1ms);
    
      //10ms
      uint32_t timerPeriod_10ms = (uint32_t)(systemFreq_MHz *
                                  (float_t)10000.0) - 1;
    
      // use timer 1 for CPU usage diagnostics
      CPUTimer_setPreScaler(obj->timerHandle[1], 0);
      CPUTimer_setEmulationMode(obj->timerHandle[1],
                                CPUTIMER_EMULATIONMODE_RUNFREE);
      CPUTimer_setPeriod(obj->timerHandle[1], timerPeriod_10ms);
    
      // use timer 2 for CPU usage diagnostics
      CPUTimer_setPreScaler(obj->timerHandle[2], 0);
      CPUTimer_setEmulationMode(obj->timerHandle[2],
                                CPUTIMER_EMULATIONMODE_RUNFREE);
      CPUTimer_setPeriod(obj->timerHandle[2], 0xFFFFFFFF);
    
      return;
    }  // end of HAL_setupTimers() function
    
    
    //------------------------------------------------------------------
    bool HAL_getTimerStatus(HAL_Handle halHandle, const uint16_t CPUTimerNumber)
    {
       HAL_Obj   *obj = (HAL_Obj *)halHandle;
       bool CPUTimerStatus;
    
       CPUTimerStatus = CPUTimer_getTimerOverflowStatus(obj->timerHandle[CPUTimerNumber]);
       return CPUTimerStatus;
    }   // end of HAL_getTimerStatus() function
    
    
    void HAL_clearTimerFlag(HAL_Handle halHandle, const uint16_t CPUTimerNumber)
    {
       HAL_Obj   *obj = (HAL_Obj *)halHandle;
    
       CPUTimer_clearOverflowFlag(obj->timerHandle[CPUTimerNumber]);
    }   // end of HAL_clearTimerFlag() function
    
    void HAL_setPwmDacParameters(HAL_Handle handle, HAL_PwmDacData_t *pPwmDacData)
    {
        HAL_Obj *obj = (HAL_Obj *)handle;
    
        pPwmDacData->PeriodMax = PWMDAC_getPeriod(obj->pwmDacHandle[PWMDAC_Number_1]);
    
        pPwmDacData->offset[0] = 0.0;
        pPwmDacData->offset[1] = 0.0;
        pPwmDacData->offset[2] = 0.0;
        pPwmDacData->offset[3] = 0.0;
    
        pPwmDacData->gain[0] = 1.0/2.0/3.14159265359;
        pPwmDacData->gain[1] = 1.0/2.0/3.14159265359;
        pPwmDacData->gain[2] = 1.0/2.0/3.14159265359;
        pPwmDacData->gain[3] = 1.0/2.0/3.14159265359;
    
        return;
    }   //end of HAL_setDacParameters() function
    
    
    void HAL_setupDlogDMA(HAL_Handle handle, const uint16_t DMAChannel, const void *dlogDestAddr, const void *dlogSrcAddr)
    {
        HAL_Obj *obj = (HAL_Obj *)handle;
    
        const void *destAddr;
        const void *srcAddr;
        destAddr = (const void *)dlogDestAddr;
        srcAddr  = (const void *)dlogSrcAddr;
    
        //
        // configure DMA Channel
        //
        DMA_configAddresses(obj->dmaChHandle[DMAChannel], destAddr, srcAddr);
        DMA_configBurst(obj->dmaChHandle[DMAChannel],DLOG_BURST,2,2);
        DMA_configTransfer(obj->dmaChHandle[DMAChannel],DLOG_TRANSFER,1,1);
        DMA_configMode(obj->dmaChHandle[DMAChannel],DMA_TRIGGER_SOFTWARE,
                       DMA_CFG_ONESHOT_ENABLE+DMA_CFG_CONTINUOUS_ENABLE+DMA_CFG_SIZE_32BIT);
        DMA_setInterruptMode(obj->dmaChHandle[DMAChannel],DMA_INT_AT_END);
        DMA_enableTrigger(obj->dmaChHandle[DMAChannel]);
        DMA_disableInterrupt(obj->dmaChHandle[DMAChannel]);
    
        return;
    }    //end of HAL_initDlogDMA() function
    
    void HAL_ClearDataRAM(void *pMemory, uint16_t lengthMemory)
    {
        uint16_t *pMemoryStart;
        uint16_t LoopCount, LoopLength;
    
        pMemoryStart = pMemory;
        LoopLength = lengthMemory;
    
        for(LoopCount=0; LoopCount<LoopLength; LoopCount++)
            *(pMemoryStart+LoopCount) = 0x0000;
    }   //end of HAL_ClearDataRAM() function
    
    //*****************************************************************************
    //
    // Error handling function to be called when an ASSERT is violated
    //
    //*****************************************************************************
    void __error__(char *filename, uint32_t line)
    {
        //
        // An ASSERT condition was evaluated as false. You can use the filename and
        // line parameters to determine what went wrong.
        //
        ESTOP0;
    }
    // end of file
    
    8267.hal.h1884.user.h

  • Hi Yanming,

    Thanks for sending the files. But they seem to throw up error while building.

    Compiler cannot find this file. #include "libraries/user/source/userParams.h". I changed it to #include "userParams.h" (like in Motor Control SDK solution files). It then shows error with 

    #include "libraries/svgen/source/svgen_current.h". I again changed it to #include "svgen_current.h". But now it shows a lot of errors. 

    Can you check and let me know what is going wrong?

  • Hi Yanming,

    Errors are due to the function name being different in hal.h file.

    The file you have chosen to convert the code to DRV8301 kit compatible is having a different format for function names than what is used in Motor Control SDK. (for example, Motor Control SDK uses DAC and the file that you have sent used Dac).

    I will manage and make the corrections wherever needed.

    Thanks for your support.

  • OK. You might follow the building message to fix the related error that should be not difficult for you. Thanks.