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.

Multiple MCUs Bricked in DRV8301 Kit with Custom Instaspin BLDC

Other Parts Discussed in Thread: TMS570LS1227, INSTASPIN-BLDC, DRV8301

Hello,

I had posted on this forum before regarding using the DRV8301 Kit with the Instaspin-BLDC solution and avoiding the use of a GUI. However, I have gone through two different TMS570LS1227 control cards, both of which have become unresponsive () and am wondering whether the issue is with my modified code or some other factor. 

Essentially what I had done in the code is modify it to remove the gGUIObj object and graphing modules, and in all instances where the the GUI object values are assigned to DRV object values, I have replaced this with hardcoded values to simulate a specific configuration of the GUI that a user could select. 

The files I modified were Sys_main.c, drv.c, and drv.h. 

One thing I suspect (but cannot test as I don't have any working MCU with me yet) is that in DRV_init, commenting out the while loop that waits for the TPS flag might have affected the TPS65381 power supply, but as the code did not brick the device during the debug session itself, this may not be the case. 

The most notable change was replacing the DRV_run function with the GUI_run function with a custom_run function that is defined the drv.h file. 

I also changed the adc_notification interrupt so that it calls custom_run instead of gui_run.

I have attached all three files here with comments regarding changes and would greatly appreciate any insights about obvious errors or oversights that may be breaking the TMS570 boards. I would go through and uncomment various lines to test again myself, but as each board is quite expensive it would be best to have another opinion on what the issue could be before I try again. 

   

/*
 *
 * Omkar Version 7/7/16
*
*   This file contains the main function, for FOC motor control
*/

/* (c) Texas Instruments 2009-2012, All rights reserved. */

/* USER CODE BEGIN (0) */

//! \file   ~/solutions/instaspin_bldc/boards/drv8301kit_revD/hercules/tms570ls1227/projects/ccs5/project01/src/sys_main.c
//!
//! \brief  Main system file for the three phase sensored speed SMO project
//!
//! (C) Copyright 2012, Texas Instruments, Inc.

// **************************************************************************
// the includes

#include "sys_main.h"
/* USER CODE END */

#include "sys_common.h"
#include "system.h"

/* USER CODE BEGIN (1) */


// **************************************************************************
// the globals

DRV_Handle drvHandle;				// Handle to the Inverter driver object

//GUI_Handle guiHandle;				// Handle to the GUI object //***

//GRAPH_DATA	graph; //Omkar
//GRAPH_Handle graphHandle = &graph;//Omkar
//float32_t DlogCh1 = 0;//Omkar
//float32_t DlogCh2 = 0;//Omkar
//float32_t DlogCh3 = 0;//Omkar
//float32_t DlogCh4 = 0;//Omkar
//int32_t GraphInput = 0;//Omkar

/* USER CODE END */


/** @fn void main(void)
*   @brief Application main function
*   @note This function is empty by default.
*
*   This function is called after startup.
*   The user can use this function to implement the application.
*/

/* USER CODE BEGIN (2) */

// **************************************************************************
// the functions

/* USER CODE END */

void main(void)
	{
/* USER CODE BEGIN (3) */
	_mpuInit_();
	(*(volatile unsigned int *)(0xFFFFEA38))=0x83E70B13;
    (*(volatile unsigned int *)(0xFFFFEA3C))=0x95A4F1E0;
    (*(volatile unsigned int *)(0xFFFFEB88))=0x00000002;//ADC Alternate Trigger

    //enable all ePWM s + TZ + ECAP1,2,3,4 + EQEP1+EQEP2
    *(volatile unsigned int *) 0xFFFFEBA4 = 0x01010102; // Enable TBCLK 37[1]
    *(volatile unsigned int *) 0xFFFFEB10 = 0x08010801; // nTZ1 0[19], nTZ2 0[27],
    *(volatile unsigned int *) 0xFFFFEB18 = 0x04010110; // ETPWM1A 2[26], EQEP2I 2[4]
    *(volatile unsigned int *) 0xFFFFEB1C = 0x01040101; // ETPWM1B 3[18]
    *(volatile unsigned int *) 0xFFFFEB20 = 0x20200104; // ETPWM2A 4[2], EQEP2A 4[21], EQEP2B 4[29]
    *(volatile unsigned int *) 0xFFFFEB24 = 0x01080404; // ETPWM2B 5[2], ETPWM3A 5[10], ETPWM3B 5[19]
    *(volatile unsigned int *) 0xFFFFEB2C = 0x01040101; // ETPWM5A 7[18]
    *(volatile unsigned int *) 0xFFFFEB30 = 0x01040104; // ETPWM5B 8[2], ECAP1 8[18]
    *(volatile unsigned int *) 0xFFFFEB34 = 0x01010801; //EQEP1B 9[11], SPI3CS0/EQEP1I 9[16/19]
    *(volatile unsigned int *) 0xFFFFEB40 = 0x20100101; // ECAP4 12[20],ECAP5 12[29]
    *(volatile unsigned int *) 0xFFFFEB40 = 0x04010101; // ECAP6 13[26]
    *(volatile unsigned int *) 0xFFFFEB54 = 0x01010110; // nTZ3 17[4]
    *(volatile unsigned int *) 0xFFFFEB5C = 0x01010801; // EQEP2S 19[11]
    *(volatile unsigned int *) 0xFFFFEB60 = 0x01100101; // EQEP1S 20[20]
    *(volatile unsigned int *) 0xFFFFEB7C = 0x01010104; // ETPWM4A 27[2]
    *(volatile unsigned int *) 0xFFFFEB94 = 0x01010102; // ETPWM4B 33[1], SPI3SOMI/ECAP2 33[8/10], SPI3SIMO/ECAP3 33[16/18],SPI3CLK/EQEP1A 33[24/26]
    *(volatile unsigned int *) 0xFFFFEB98 = 0x01020201; // ETPWM6A 34[9], ETPWM6B 34[17]
    *(volatile unsigned int *) 0xFFFFEB8C =0x01010102;//SRC=110, A2 31[1]
    (*(volatile unsigned int *)(0xFFFFEA38))=0x0;
    (*(volatile unsigned int *)(0xFFFFEA3C))=0x0;

 //   guiHandle = GUI_init(&gGUIObj,sizeof(gGUIObj)); //***

	// initialize the driver
	drvHandle = DRV_init(&drv,sizeof(drv), T);

	// initialize the graph module (data logger)
//	graph.ch1Ptr = &DlogCh1; //***
//	graph.ch2Ptr = &DlogCh2;//***
//	graph.ch3Ptr = &DlogCh3;//***
//	graph.ch4Ptr = &DlogCh4;//***
//	graph.trigValue = 0.0;//***
//	graph.size = 0x00FF;//***
//	graph.holdoff = 3;//***
//	graph.prescalar = 5;//***
//	Graph_Data_Init(graphHandle); //***

	// initialize the gui

//	GUI_setup(guiHandle, drvHandle) //	GUI_setup(guiHandle, drvHandle, graphHandle); //***

	// Send SPI commands to DRV8301 to set it up
	spiREG3->DAT1 = 0x13D0;
    while((spiREG3->FLG & 0x100)!=0x100);
    drv.SPI3_RXDATA[0] = (spiREG3->BUF) & 0xFF;

    spiREG3->DAT1 = 0x8000;
    while((spiREG3->FLG & 0x100)!=0x100);
    drv.SPI3_RXDATA[1] = (spiREG3->BUF) & 0xFF;

    spiREG3->DAT1 = 0x180D;
    while((spiREG3->FLG & 0x100)!=0x100);
    drv.SPI3_RXDATA[2] = (spiREG3->BUF) & 0xFF;

    spiREG3->DAT1 = 0x8000;
    while((spiREG3->FLG & 0x100)!=0x100);
    drv.SPI3_RXDATA[3] = (spiREG3->BUF) & 0xFF;

    while((GetChar(drv.ecmpHandle) != '2') && (!drv.tpsFlag));

    drv.enableFlag = 1; //*** modified to skip the if statement
    /* if(!gGUIObj.TPSFlag) //***
    {
    	gGUIObj.DutyCmd = 0;
    	gGUIObj.TorqueCmd = 0;
    	gGUIObj.SpdCmd = 0;
    	gGUIObj.EnableFlg = 1;
    	PutText(drv.ecmpHandle, "Motor Enabled\r\n");
    } *

	// Endless loop to wait for start command from either GUI or button
	//while(DRV_get_Enable(drvHandle) != 1){ //*** commented in order to allow automation and avoid need for GUI or button command

		//custom_run(drvHandle); // GUI_run((GUI_Handle)&gGUIObj, drvHandle); //GUI_run((GUI_Handle)&gGUIObj, drvHandle, graphHandle); //***
	//}

	// Start the PWMs and Interrupt
	DRV_Motor_start(drvHandle);

	// Enable the peripheral interrupt notifications
	gioEnableNotification(0);
	gioEnableNotification(1);
	adcEnableNotification(adcREG1, adcGROUP1);	
	adcEnableNotification(adcREG1, adcGROUP2);

	// Drop into main while loop
	drv.ADC_INT_ENA=1; // this is where the interrupts are enabled
	while(1)
	{
		drv.SCI_Command = '3'; //drv.SCI_Command = GetChar(drv.ecmpHandle); ////*** modified such that the switch statement will default to voltage mode
		switch (drv.SCI_Command)
		{
			case '3':
				drv.controlMode = 0; // gGUIObj.CtrlType = 0; //***
				drv.ref = 0.5; // gGUIObj.DutyCmd = 0.3; //***
				PutText(drv.ecmpHandle, "Duty Cycle Mode Enabled\r\n");
				break;
			/*case '4':
				gGUIObj.CtrlType = 1;
				gGUIObj.TorqueCmd = 0.3;
				PutText(drv.ecmpHandle, "Current Mode Enabled\r\n");
				break;
			case '5':
				gGUIObj.CtrlType = 2;
				gGUIObj.SpdCmd = 0.3;
				PutText(drv.ecmpHandle, "Velocity Mode Enabled\r\n");
				break;
			case '6':
				gGUIObj.CtrlType = 3;
				gGUIObj.SpdCmd = 0.3;
				PutText(drv.ecmpHandle, "Cascade (Current + Velocity) Mode Enabled\r\n");
				break;
			case '7':
				gGUIObj.DutyCmd = 0;
				gGUIObj.CtrlType = 0;
				gGUIObj.SpdCmd = 0;
				gGUIObj.TorqueCmd = 0;
				PutText(drv.ecmpHandle, "Motor Stopped\r\n");
				break;
			case '8':
				drv.ecmpHandle->DiagFlag = !drv.ecmpHandle->DiagFlag;
				PutText(drv.ecmpHandle, "Watchdog Diagnostics Flag Toggled\r\n");
				break;*/
		}
		if(drv.Process_WDA==1)
		{
			ecmpWdQaSendAnswer(drv.ecmpHandle, 0, 0, 0);
	    	drv.Process_WDA = 0;
		}
		// Run the GUI interface
		custom_run(drvHandle); // GUI_run((GUI_Handle)&gGUIObj, drvHandle);// GUI_run((GUI_Handle)&gGUIObj, drvHandle, graphHandle); //***
	} 
/* USER CODE END */
}


/* USER CODE BEGIN (4) */
/********************************************************************************
	ADC Notification
********************************************************************************/			                           
void adcNotification(adcBASE_t *adc, uint32_t group)
{
	//Run the Motor
	DRV_EnableMotor(drvHandle);
	custom_run(drvHandle); //*** modified to replace GUI_run

	//Log data
/*	switch (GraphInput) {
	case 0:
	default:
		DlogCh1 = (float) drv.mod6Handle->counter;
		DlogCh2 = (float) drv.instaHandle->vInt;
		DlogCh3 = (float) drv.iqVaIn;
		DlogCh4 = (float) drv.iDCFdbk;


	// ------------------------------------------------------------------------------
	// Update data logger
	// ------------------------------------------------------------------------------
//	Graph_Data_Update(graphHandle);
*/
} 	// end of the interrupt

// Here are dummy functions for the HALCoGen generated drivers
/********************************************************************************
	RTI Notification	(a dummy-function for the compiler, no affects)
********************************************************************************/			                           
void rtiNotification(uint32_t notification)
{
	switch(notification)
    {
        case 4 :
        	if(drv.ADC_INT_ENA==0)
        	{
        		ecmpWdQaSendAnswer(drv.ecmpHandle, 0, 0, 0);
        	}
        	else
        	{
        		drv.Process_WDA = 1;
        	}

        break;
    }
    return;
}
/********************************************************************************
	ESM Notification	(a dummy-function for the compiler, no affects)
********************************************************************************/
void esmGroup1Notification(uint32_t channel){return;}
void esmGroup2Notification(uint32_t channel){return;}
void hetNotification(hetBASE_t *het, uint32_t offset){return;}
/* USER CODE END */

 
/* --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_bldc/boards/drv8301kit_revD/hercules/tms570ls1227/src/drv.c
//! \brief  Contains the various functions related to the DRV object
//!
//! (C) Copyright 2011, Texas Instruments, Inc.


// **************************************************************************
// the includes

#include "solutions/instaspin_bldc/boards/drv8301kit_revD/hercules/src/drv.h"
//#include "solutions/instaspin_bldc/boards/drv8301kit_revD/hercules/src/gui.h"

// **************************************************************************
// the defines


// **************************************************************************
// the globals

DRV_Obj drv;
MOD6CNT gMod6;
RMP3 gRMP3;
SPEED_MEAS_CAP gSpeed;
INSTASPIN_BLDC gInstaSPIN;
IMPULSE gImpulse;
PID_Obj gPIDSpd;
PID_Obj gPIDIDC;
RMPCNTL_Obj gRMPCntl;
STATEFILTER gStateFilter;
ECMP_Obj gECMP;


// **************************************************************************
// the functions

//! \brief     Initializes the driver (DRV) object
//! \param[in] pMemory     A pointer to the memory for the driver object
//! \param[in] numBytes    The number of bytes allocated for the driver object, bytes
//! \param[in] period	   interrupt period
//! \return    The driver (DRV) object handle
DRV_Handle DRV_init(void *pMemory,const size_t numBytes, const float32_t period)
{
	DRV_Handle drvHandle;
	DRV_Obj *drv;

	if(numBytes < sizeof(DRV_Obj))
	return((DRV_Handle)NULL);

	// assign the handle
	drvHandle = (DRV_Handle)pMemory;

	// assign the object
	drv = (DRV_Obj *)drvHandle;

	// Initializations
	gioInit();	//Initialize GIO module
	spiInit();  //Initialize SPI module
	adcInit();	//Initialize ADC module
	rtiInit();	//Initialize RTI module

	//delay 50ms while HET starts up
	rtiResetCounter(rtiCOUNTER_BLOCK0);
	rtiStartCounter(rtiCOUNTER_BLOCK0);
	while(rtiGetCurrentTick(rtiCOMPARE0) < 50000);
	rtiStopCounter(rtiCOUNTER_BLOCK0);

	drv->ecmpHandle = ECMPInit(&gECMP, sizeof(gECMP));
	ECMPSetup(drv->ecmpHandle);
	(*(volatile unsigned int *)(0xFFFFFF0C))=1;
	(*(volatile unsigned int *)(0xFFFFFF04))=1;
	/* avoid TPS65381 to transit to ACTIVE operating state */
	while(!ecmpStayinDIAGState(drv->ecmpHandle));
	// while(wait); /* set cursor to next line to continue - prevents reset chain */
	while(!ecmpGetWriteAccess(drv->ecmpHandle));
	sciInit();
	if(ecmpReadRegister(drv->ecmpHandle, RD_SAFETY_STAT5) == 0x04)
	{
		PutText(drv->ecmpHandle, "TPS65381 is NOT in DIAG state, toggle IGN!\n\r");
	    while(1);
	}
	PutText(drv->ecmpHandle, "1 - Enable Watchdog\n\r");
	PutText(drv->ecmpHandle, "2 - Enable Motor\n\r");
	PutText(drv->ecmpHandle, "3 - Start Motor in Duty Cycle Mode\n\r");
	PutText(drv->ecmpHandle, "4 - Start Motor in Current Mode\n\r");
	PutText(drv->ecmpHandle, "5 - Start Motor in Velocity Mode\n\r");
	PutText(drv->ecmpHandle, "6 - Start Motor in Cascade (Current + Velocity) Mode\n\r");
	PutText(drv->ecmpHandle, "7 - Stop Motor\n\r");
	PutText(drv->ecmpHandle, "8 - Toggle Watchdog Diagnostics Flag\n\r");

	//delay 50ms
	rtiResetCounter(rtiCOUNTER_BLOCK0);
	rtiStartCounter(rtiCOUNTER_BLOCK0);
	while(rtiGetCurrentTick(rtiCOMPARE0) < 500000);
	rtiStopCounter(rtiCOUNTER_BLOCK0);

	// Set IO to enable DRV8301
	gioSetDirection(gioPORTA, 0x00000010U);
	gioSetBit(gioPORTA, 4, 1); 

	//wait until a command from HyperTermal to force the TPS65381 device into active mode
	//while((GetChar(drv->ecmpHandle)!='1') && (!drv.tpsFlag));// *** commented because there is no manual toggling of the TPS Flag in automatic mode. The TPS flag is set to 1 in the run function. This is the code I suspect may be causing an issue. 

	PutText(drv->ecmpHandle, "Start Watchdog\r\n");
	//delay 50ms
	rtiResetCounter(rtiCOUNTER_BLOCK0);
	rtiStartCounter(rtiCOUNTER_BLOCK0);
	while(rtiGetCurrentTick(rtiCOMPARE0) < 500000);
	rtiStopCounter(rtiCOUNTER_BLOCK0);
	/* select desired WD mode - time in mu seconds */
	ecmpWdQaInit(drv->ecmpHandle, 45000, 18000);
	ecmpWdStart(drv->ecmpHandle);
	//delay 50ms
	rtiResetCounter(rtiCOUNTER_BLOCK0);
	rtiStartCounter(rtiCOUNTER_BLOCK0);
	while(rtiGetCurrentTick(rtiCOMPARE0) < 500000);
	rtiStopCounter(rtiCOUNTER_BLOCK0);
	while(gioGetBit(gioPORTA, 4)==0);


	(*(volatile unsigned int *)(0xFFFFFF0C))=0;
	//delay 50ms while DRV8301 powers up
	rtiResetCounter(rtiCOUNTER_BLOCK0);
	rtiStartCounter(rtiCOUNTER_BLOCK0);
	while(rtiGetCurrentTick(rtiCOMPARE0) < 500000);
	rtiStopCounter(rtiCOUNTER_BLOCK0);
	drv->ecmpHandle->DiagFlag = 0;
	// initialize connection between the CTRL and PWM modules
	drv->gPwmData.Tabc.value[0] = 0;
	drv->gPwmData.Tabc.value[1] = 0;
	drv->gPwmData.Tabc.value[2] = 0;

	// initialize pwm module
	drv->pwmHandle[0] = PWM_init((void *)PWM_ePWM2_BASE_ADDR,sizeof(PWM_Obj));
	drv->pwmHandle[1] = PWM_init((void *)PWM_ePWM3_BASE_ADDR,sizeof(PWM_Obj));
	drv->pwmHandle[2] = PWM_init((void *)PWM_ePWM4_BASE_ADDR,sizeof(PWM_Obj));

	// Setup drv object
	DRV_setup(drvHandle, period);

	return(drvHandle);
} // end of DRV_init() function


//! \brief     Setup the driver module to default values
//! \param[in] handle  	   The driver (DRV) handle
//! \param[in] period	   FOC, period
void DRV_setup(DRV_Handle handle, const float32_t period)
{
	DRV_Obj *drv = (DRV_Obj *) handle;

	// setup the PWMs
	DRV_setupPwms(handle, T, vCNT_SCALE);

//	// Setup current calibration constants
	drv->cal_offset_A = 0x7FF0;
	drv->cal_offset_B = 0x7FF0;

	drv->ref = 0.3;
	drv->currentDisplay = 0.0;
	drv->dFuncStartup = 0.1;
	drv->currentStartup = 0.1;
	drv->threshold = 0.10;
	drv->currentKp = 0.08982;
	drv->velocityKp = 0.75;
	drv->iMax = 0.95;
	drv->rampUpTime = 25;
	drv->commErrorMax = 1.0;
	drv->tripCnt = 3;
	drv->advancedStartup = 0;

	drv->speedRPM = 0;
	drv->beginStartRPM = 50;
	drv->endStartRPM = 100;

	drv->currentMode = 0;
	drv->velocityMode = 0;
	drv->controlMode = drv->currentMode + drv->velocityMode;
	drv->resetFault = 0;
	drv->poles = 8;
	drv->currentKi = 100;
	drv->velocityKi = 3;
	drv->currentKd = 0;
	drv->velocityKd = 0;
	drv->prescaler = 1;
	drv->runBLDCInt = 0;
	drv->overVoltage = 0;
	drv->drvFaultFlag = 0;
	drv->drvOTWFlag = 0;
	drv->enableFlag = FALSE;
	drv->vDCBus = 0;
	drv->maxVDC = 2880; //1302
	drv->minVDC = 1920;
	drv->floatCounter = 0.0;

	drv->baseFreq =  200;			// Base electrical frequency (Hz)
	drv->rampStartRate = (PWM_FREQUENCY*1000)*60.0/drv->beginStartRPM/COMMUTATES_PER_E_REV/(drv->poles/2.0);
	drv->rampEndRate = (PWM_FREQUENCY*1000)*60.0/drv->endStartRPM/COMMUTATES_PER_E_REV/(drv->poles/2.0);
	drv->cmtnPeriodTarget = drv->rampEndRate;
	drv->cmtnPeriodSetpt = drv->rampStartRate;

	drv->virtualTimer = 0;
	drv->speedLoopFlag = FALSE;
	drv->rampDelay = 1;
	drv->speedRef= 0.0;
	drv->iDCOffset = 0.5;
	drv->iRef = 0.0;
	drv->isrTicker = 0;
	drv->calibrateFlag = 0;
	drv->calibrateTime = 0x7FFF;
	drv->dLogCurrElementIndex = 0;
	drv->bemfTrigCnt = 0;
	drv->bemfLastTrigCnt = 0;
	drv->goodTrigCnt = 0;
	drv->goodTrigCntTrip = 20;
	drv->closedCommutationFlag = 0;

	drv->mod6Handle = &gMod6;
	drv->rmp3Handle = &gRMP3;
	drv->impulseHandle = &gImpulse;
	drv->pidSpdHandle = &gPIDSpd;
	drv->pidIDCHandle = &gPIDIDC;
	drv->instaHandle = &gInstaSPIN;
	drv->speedHandle = &gSpeed;
	drv->rmpCntlHandle = &gRMPCntl;
	drv->instaHandle->stateFilter = &gStateFilter;
	drv->ecmpHandle = &gECMP;


	MOD6CNT_Setup(drv->mod6Handle);

	PID_setGains(drv->pidIDCHandle, drv->currentKp, (drv->currentKi * T), (drv->currentKd / T));
	PID_setMinMax(drv->pidIDCHandle, -0.95, 0.95);

	PID_setGains(drv->pidSpdHandle, drv->velocityKp, (drv->velocityKi * T), (drv->velocityKd / T));
	PID_setMinMax(drv->pidSpdHandle, -0.71, 0.71);

	RMP3_Setup(drv->rmp3Handle);
	IMPULSE_Setup(drv->impulseHandle);
	INSTASPIN_Setup(drv->instaHandle);
	SPEED_MEAS_CAP_Setup(drv->speedHandle);
	RMPCNTL_Setup(drv->rmpCntlHandle);

	// Initialize the SPEED_PR module
	drv->speedHandle->inputSelect = 0;
	drv->speedHandle->baseRPM = 120*(drv->baseFreq / drv->poles);
	drv->speedHandle->speedScaler = (uint32_t)(PWM_FREQUENCY / (1 * (float32_t)drv->baseFreq * 0.001));
	SPEED_MEAS_CAP_Calc(drv->speedHandle);

	// Initialize RMPCNTL module
	drv->rmpCntlHandle->rampDelayMax = 1;
	drv->rmpCntlHandle->rampLowLimit = -1.0;
	drv->rmpCntlHandle->rampHighLimit = 1.0;
	RMPCNTL_Calc(drv->rmpCntlHandle);

	// Initialize RMP3 module
	drv->rmp3Handle->desiredInput = drv->cmtnPeriodTarget;
	drv->rmp3Handle->ramp3Delay = (uint32_t)(((float32_t)drv->rampUpTime * 0.001)/((float32_t)(drv->cmtnPeriodSetpt - drv->cmtnPeriodTarget) * T));
	drv->rmp3Handle->out = drv->cmtnPeriodSetpt;
	drv->rmp3Handle->ramp3Min = drv->cmtnPeriodTarget;
	RMP3_Calc(drv->rmp3Handle);

	//Initialize the INSTASPIN_BLDC module
	drv->instaHandle->vaOffset = 0;
	drv->instaHandle->vbOffset = 0;
	drv->instaHandle->vcOffset = 0;
	drv->instaHandle->intThreshold = drv->threshold;

	drv->pidIDCHandle->refValue = drv->ref;
	drv->pidSpdHandle->refValue = drv->ref;

	// Initialize the current offset calibration filter
	drv->calFiltGain = (T / (T + TC_CAL));
	drv->spdFiltGain = (T / (T + TC_SPD));


}

//void DRV_setupPwms(DRV_Handle handle,const uint_least16_t systemFreq_MHz,const float32_t pwmPeriod_usec)
void DRV_setupPwms(DRV_Handle handle, const float32_t ISRperiod, const int32_t het_vCNT_SCALE)
{
  DRV_Obj   *obj = (DRV_Obj *)handle;
  uint16_t   halfPeriod_cycles = ((ISRperiod*het_vCNT_SCALE)/2)*128;
  uint8_t    cnt;

	PWM_setOneShotTrip(obj->pwmHandle[0]);// Disable PWM A leg
	PWM_setOneShotTrip(obj->pwmHandle[1]);// Disable PWM B leg
	PWM_setOneShotTrip(obj->pwmHandle[2]);// Disable PWM C leg

  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_Shadow);

      // 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],DRV_PWM_DBRED_CNT);

      // setup the Dead-Band Falling Edge Delay Register (DBFED)
      PWM_setDeadBandFallingEdgeDelay(obj->pwmHandle[cnt],DRV_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[0]);
  PWM_setSocAPulseSrc(obj->pwmHandle[0],PWM_SocPulseSrc_CounterEqualZero);
  PWM_enableSocAPulse(obj->pwmHandle[0]);


  // setup the Event Trigger Prescale Register (ETPS)
  PWM_setSocAPeriod(obj->pwmHandle[0],PWM_SocPeriod_FirstEvent);


  // setup the Event Trigger Clear Register (ETCLR)
  PWM_clearIntFlag(obj->pwmHandle[0]);
  PWM_clearSocAFlag(obj->pwmHandle[0]);


  // 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[0],halfPeriod_cycles);
  PWM_setPeriod(obj->pwmHandle[1],halfPeriod_cycles);
  PWM_setPeriod(obj->pwmHandle[2],halfPeriod_cycles);

  return;
}  // end of DRV_setupPwms() function
// end of file
             
/* --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--*/

//NEW WORKSPACE VERSION- SANS GUI

#ifndef _DRV_H_
#define _DRV_H_

//! \file   ~/solutions/instaspin_bldc/boards/drv8301kit_revD/hercules/tms570ls1227/src/drv.h
//! \brief  Contains public interface to various functions related
//!         to the DRV object
//!
//! (C) Copyright 2011, Texas Instruments, Inc.

// **************************************************************************
// the includes

// **************************************************************************
// the modules
#include "modules/types/src/32b/controller_data_types.h"
#include "modules/instaspin_bldc/src/float32/hercules/champion/InstaSPIN_BLDC.h"
#include "modules/mod6/src/float32/hercules/mod6_cnt.h"
#include "modules/rmp3/src/float32/hercules/rmp3cntl.h"
#include "modules/speed_pr/src/float32/hercules/speed_pr.h"
#include "modules/impulse/src/float32/hercules/impulse.h"
#include "modules/rmpcntl/src/float32/hercules/rmp_cntl.h"
#include "modules/dlog/src/float32/hercules/DLOG.h"
#include "modules/pid/src/float32/hercules/pid.h"
#include "modules/ecmp/src/float32/champion/ecmp.h"

// **************************************************************************
// the drivers

#include "drivers/gio/src/32b/hercules/champion/gio.h"
#include "drivers/adc/adc_bldc/src/32b/hercules/champion/adc.h"
#include "drivers/rti/src/32b/hercules/champion/rti.h"
#include "drivers/pwm/pwm_bldc/src/32b/hercules/champion/epwm.h"
#include "drivers/het/pwm_bldc/src/32b/hercules/champion/het.h"
#include "drivers/spi/src/32b/hercules/champion/spi.h"



//!
//! \defgroup DRV

//!
//! \ingroup DRV
//@{

#ifdef __cplusplus
extern "C"
{
#endif

// **************************************************************************
// the defines


#define VOLTAGE         0           //open-loop volage mode only
#define CURRENT         1           //closed-loop current control
#define VELOCITY        2           //closed-loop velocity control
#define CASCADE         3           //cascaded closed-loop velocity->current control
#define DISABLED		4			//disabled mode, all PWMs off
#define fs              20000.0		//Interrupt
#define PWM_FREQUENCY   20			//PWM Frequency
#define COMMUTATES_PER_E_REV 6.0	//Commutations per electrical revolution
#define T               1.0/fs		//Interrupt period
#define WC_CAL          100.0		//Calibration filter cutoff
#define TC_CAL          1/WC_CAL	//Time constant for cutoff
#define WC_SPD  1200.0				//Cutoff for speed display filter
#define TC_SPD  1/WC_SPD			//Time constant for speed display filter
#define vCNT_SCALE 	610000			//scaling constant based on system clock divided by 128

// HET States for PWM logic
#define ALL_PHASES_OFF	0x401BA000
#define PHASE_A_OFF		0x401BA550
#define PHASE_B_OFF		0x401BA505
#define PHASE_C_OFF		0x401BA055

//! \brief Defines the PWM deadband falling edge delay count (system clocks)
//!
#define DRV_PWM_DBFED_CNT         10        //


//! \brief Defines the PWM deadband rising edge delay count (system clocks)
//!
#define DRV_PWM_DBRED_CNT         10        //

// **************************************************************************
// the typedefs


//! \brief Defines the PWM data
//!
typedef struct _DRV_PwmData_t_
{
    MATH_vec3 Tabc;      //!< the PWM time-durations for each motor phase

} DRV_PwmData_t;

//! \brief Defines the driver (DRV) object
//!
typedef struct _DRV_Obj_
{
    //PWM_Handle 			pwmISync;

    PWM_Handle 			pwmHandle[3];

    //PWM_SYNC_Handle 	pwmSyncHandle;

    float32_t 			currentSync;

    uint32_t 			hetIOstate;

    DRV_PwmData_t 		gPwmData;

    ADC_Data_t 			adcData;
    adcData_t 			AdcResults1[16];
    adcData_t 			AdcResults2[16];

    int32_t 			cal_offset_A;
    int32_t 			cal_offset_B;

    float32_t 			iqVaIn;
    float32_t 			iqVbIn;
    float32_t 			iqVcIn;
    float32_t 			iDCFdbk;

    uint32_t 			rtiCounterValue;
    float32_t 			rtiBenchmarkTime;

    uint32_t			gdFaultStatus;
    uint32_t			bridgeFaultFlg;
    uint32_t			overVoltageFlg;
    uint32_t			overTempFlg;
    uint32_t			firstFaultRstEval;
    uint32_t			faultDisableFlag;

    H_MOD6CNT 			mod6Handle;
    RMP3_handle 		rmp3Handle;
    SPEED_MEAS_CAP_handle speedHandle;
    H_INSTASPIN_BLDC 	instaHandle;
    IMPULSE_handle 		impulseHandle;
    PID_Handle 			pidSpdHandle;
    PID_Handle 			pidIDCHandle;
    RMPCNTL_handle 		rmpCntlHandle;
    ECMP_handle			ecmpHandle;

    int8_t				SCI_Command;
    int32_t				ADC_INT_ENA;
    int32_t				Process_WDA;
    uint16_t			SPI3_RXDATA[4];

    int32_t 			isrTicker;
    uint32_t 			virtualTimer;
    uint16_t 			previousState;
    uint16_t 			speedLoopFlag;
    uint32_t 			cmtnPeriodTarget;
    uint32_t 			cmtnPeriodSetpt;
    uint32_t 			rampDelay;
    uint16_t 			closedCommutationFlag;
    uint32_t 			bemfTrigCnt;
    uint32_t 			bemfLastTrigCnt;
    uint16_t 			goodTrigCnt;
    uint16_t 			goodTrigCntTrip;
    uint16_t 			controlMode;
    uint16_t 			currCtrlType;
    uint16_t 			prevCtrlType;
    uint16_t 			calibrateFlag;
    uint16_t 			calibrateTime;
    uint16_t 			runBLDCInt;
    float32_t 			rampStartRate;
    float32_t 			rampEndRate;
    int16_t 			dLogCurrElementIndex;
    float32_t			iDCOffset;
    float32_t 			speedRef;
    float32_t 			calFiltGain;
    float32_t 			spdFiltGain;
    float32_t 			dFuncTesting;
    float32_t 			iqDuty;
    float32_t 			iRef;
    float32_t 			dFuncRun;
    float32_t 			commErrorMax;
    float32_t 			ref;
    float32_t 			currentDisplay;
    float32_t 			dFuncStartup;
    float32_t		 	currentStartup;
    float32_t 			threshold;
    float32_t 			currentKp;
    float32_t 			velocityKp;
    float32_t 			iMax;
    float32_t 			speed;
    int32_t 			speedRPM;
    int32_t 			beginStartRPM;
    int32_t 			endStartRPM;
    uint16_t 			currentMode;
    uint16_t 			velocityMode;
    uint16_t 			resetFault;
    uint16_t 			poles;
    uint16_t 			currentKi;
    uint16_t 			velocityKi;
    uint16_t 			currentKd;
    uint16_t 			velocityKd;
    uint16_t 			prescaler;
    uint16_t 			baseFreq;
    uint16_t 			rampUpTime;
    uint16_t 			tripCnt;
    uint16_t 			advancedStartup;
    int16_t 			overVoltage;
    int16_t 			drvFaultFlag;
    int16_t 			drvOTWFlag;
    int16_t 			enableFlag;
    float32_t 			vDCBus;
    float32_t 			maxVDC;
    float32_t 			minVDC;
    float32_t 			floatCounter;
    float32_t 			pidSpdValue;
    float32_t 			pidIDCValue;
    int16_t				tpsFlag;

} DRV_Obj;

//! \brief Defines the DRV handle
//!
typedef struct DRV_Obj *DRV_Handle;

// **************************************************************************
// the globals

//! \brief Defines the DRV object
//!
extern DRV_Obj drv;

// **************************************************************************
// the function prototypes

//! \brief     Initializes the driver (DRV) object
//! \param[in] pMemory     A pointer to the memory for the driver object
//! \param[in] numBytes    The number of bytes allocated for the driver object, bytes
//! \param[in] period	   FOC, period
//! \return    The driver (DRV) object handle
DRV_Handle DRV_init(void *pMemory, const size_t numBytes, const float32_t period);

//! \brief     Sets up the driver module to default values
//! \param[in] handle  	   The driver (DRV) handle
//! \param[in] period	   FOC, period
void DRV_setup(DRV_Handle handle, const float32_t period);

/*!
 * @ingroup         Generate_Outputs
 * @fn              void Generate_Outputs(DRV_Handle drvHandle)
 * @brief           Function to determine the duty cycle and output necessary PWMs
 * @param [in]  drvHandle	The Handler for the DRV System
 * @param [in]  drvHandle	The Handler for the DRV System
 * @param [in]  duty		The commanded duty cycle for the pwm
 * @param [in]  state		The commutation state
 * @param [out]  pwmData_out		The switching waveforms in duty cycle
 * @param [out]  currentSyncOut		The duty cycle of the current sampling (used if ADC2 is used for Itotal sampling)
 * @param [out]  hetIOstateOut		The active IO for the PWM signals (one phase has to be disabled)
 */
void Generate_Outputs(DRV_Handle drvHandle, float32_t duty, int32_t state, MATH_vec3 *pwmData_out, float32_t *currentSyncOut, uint32_t *hetIOstateOut);

//! \brief     	Updates the gate driver fault status
//! \param[in] 	handle			The drv handle
inline void DRV_update_gdFaultStatus(DRV_Handle handle)
{
	DRV_Obj *drv = (DRV_Obj *) handle;

	drv->gdFaultStatus = (gioGetPort(gioPORTB) >> 2);
	drv->gdFaultStatus &= 0x00000003; //BIT 1: Faultn, BIT 0: OCTWn

	// Latch in fault conditions
	switch(drv->gdFaultStatus){
    	case 0:	//Over temperature latched shutdown
    		drv->bridgeFaultFlg = 0;
    		drv->overVoltageFlg = 0;
    		drv->overTempFlg = 1;
    		break;
    	case 1:	//Over current or undervoltage latched shutdown
    		drv->bridgeFaultFlg = 1;
    		drv->overVoltageFlg = 0;
    		drv->overTempFlg = 0;
    		break;
    	case 2:	//Over temperature warning
    		drv->bridgeFaultFlg = 0;
    		drv->overVoltageFlg = 0;
    		drv->overTempFlg = 1;
    		break;
    	case 3:	//No fault condition
    		drv->bridgeFaultFlg = 0;
    		drv->overVoltageFlg = 0;
    		drv->overTempFlg = 0;
    		break;
        default:
        	break;
	}

}

//! \brief     	Resets gate driver and clears gate driver fault
//! \param[in] 	handle			The drv handle
inline void DRV_gdFaultReset(DRV_Handle handle)
{
	DRV_Obj *drv = (DRV_Obj *) handle;

	// Dessert EN_GATE for 5uS to reset gate driver
	gioSetBit(gioPORTA, 4, 0);

	rtiResetCounter(rtiCOUNTER_BLOCK0);
	rtiStartCounter(rtiCOUNTER_BLOCK0);
	while(rtiGetCurrentTick(rtiCOMPARE0) < 4);	//1 ticks = 1uS
	rtiStopCounter(rtiCOUNTER_BLOCK0);

	gioSetBit(gioPORTA, 4, 1);

	// Clear fault flags
	drv->bridgeFaultFlg = 0;
	drv->overVoltageFlg = 0;
	drv->overTempFlg = 0;
	drv->faultDisableFlag  = 0;

}


//! \brief     	Handles resets and stopping the motor.
//! \param[in] 	handle			The drv handle
inline void DRV_EnableMotor(DRV_Handle handle)
{
    DRV_Obj *drv = (DRV_Obj *) handle;

    if(drv->enableFlag == FALSE)
    {
        drv->runBLDCInt=0;

        //shut down all PWMs
    	PWM_setOneShotTrip(drv->pwmHandle[0]);// Disable PWM A leg
    	PWM_setOneShotTrip(drv->pwmHandle[1]);// Disable PWM B leg
    	PWM_setOneShotTrip(drv->pwmHandle[2]);// Disable PWM C leg
        //hetREG1->DIR = ALL_PHASES_OFF; JPB

        // Reset any falts
        DRV_gdFaultReset(handle);

        //zero all displayed variables when disabled
        drv->speedRPM = 0;
        drv->speedHandle->speedRPM = 0;
        drv->speedHandle->speed = 0;
        drv->currentDisplay = 0;
        drv->calibrateFlag = 0;
        drv->instaHandle->vaOffset = 0;
        drv->instaHandle->vbOffset = 0;
        drv->instaHandle->vcOffset = 0;
        drv->iDCOffset = 0.5;
        drv->speedLoopFlag = FALSE;
    }
    // if motor type is not defined
    if((drv->enableFlag == TRUE) && (drv->runBLDCInt == FALSE))
    {
        // Read drv_SpeedRef Only when you have enabled the motor
        drv->speedRef = drv->ref;

        if((drv->runBLDCInt == 0) && (drv->drvFaultFlag == 0))
        {
            drv->speedHandle->inputSelect = 0;
            drv->speedHandle->baseRPM = 120 * (drv->baseFreq / drv->poles);
            drv->speedHandle->speedScaler = (uint32_t)(PWM_FREQUENCY / (1 * (float32_t)drv->baseFreq * 0.001));
            drv->speedHandle->inputSelect = 0;
            drv->speedHandle->newTimeStamp = 0;
            drv->speedHandle->oldTimeStamp = 0;
            drv->speedHandle->eventPeriod = 0;
            drv->speedHandle->speed = 0;
            drv->virtualTimer = 0;

            drv->rmpCntlHandle->equalFlag = 0;
            drv->rmpCntlHandle->rampDelayCount = 0;
            drv->rmpCntlHandle->targetValue = 0;

            //The speed at the end of the ramp should always be greater than the speed at the beginning of the ramp
            if(drv->endStartRPM > drv->beginStartRPM)
            {
                drv->rampStartRate = (PWM_FREQUENCY * 1000) * 60.0 / drv->beginStartRPM /
                                         COMMUTATES_PER_E_REV / (drv->poles / 2.0);
                drv->rampEndRate = (PWM_FREQUENCY * 1000) * 60.0 / drv->endStartRPM /
                                       COMMUTATES_PER_E_REV / (drv->poles / 2.0);
            }
            else
            {
                drv->rampStartRate = (PWM_FREQUENCY * 1000) * 60.0 / 50 / COMMUTATES_PER_E_REV / (drv->poles / 2.0);
                drv->rampEndRate = (PWM_FREQUENCY * 1000) * 60.0 / 100 /  COMMUTATES_PER_E_REV / (drv->poles / 2.0);
            }

            drv->cmtnPeriodTarget = drv->rampEndRate;
            drv->cmtnPeriodSetpt = drv->rampStartRate;
            drv->rmp3Handle->ramp3Delay = (uint32_t)(((float32_t)drv->rampUpTime * 0.001) /
                                            ((float32_t)(drv->cmtnPeriodSetpt - drv->cmtnPeriodTarget) * T));
            drv->rmp3Handle->desiredInput = drv->cmtnPeriodTarget;
            drv->rmp3Handle->out = drv->cmtnPeriodSetpt;
            drv->rmp3Handle->ramp3Min = drv->cmtnPeriodTarget;
            drv->rmp3Handle->ramp3DelayCount = 0;
            drv->rmp3Handle->ramp3DoneFlag = 0;

            drv->impulseHandle->counter = 0;
            drv->impulseHandle->out = 0;

            drv->mod6Handle->counter = 0;

            drv->speedLoopFlag = FALSE;

            drv->pidIDCHandle->Ui = 0;
            drv->pidIDCHandle->refValue = 0;
            drv->pidIDCHandle->fbackValue = 0;

            drv->pidSpdHandle->Ui = 0;
            drv->pidSpdHandle->refValue = 0;
            drv->pidSpdHandle->fbackValue = 0;

            drv->dFuncRun = drv->dFuncStartup;
            drv->bemfTrigCnt = 0;
            drv->bemfLastTrigCnt = 0;
            drv->goodTrigCnt = 0;
            drv->closedCommutationFlag = 0;
            drv->instaHandle->vInt = 0;

            //set control_mode based on check box settings from drv object
            //VOLTAGE		0			//open-loop volage mode only
            //CURRENT		1			//closed-loop current control
            //VELOCITY		2			//closed-loop velocity control
            //CASCADE		3			//cascaded closed-loop velocity->current control
            //DISABLED		4			//Motor is disabled
            //velocity loop check box writes either 0 (disabled) or 2 (enabled)
            //current loop check box writes either 0 (disabled) or 1 (enabled)
            drv->controlMode = drv->velocityMode + drv->currentMode;

            drv->runBLDCInt=1;

        }
    }
}


//! \brief     Runs the DRV object
//! \param[in] handle    The driver (DRV) handle
inline void DRV_run(DRV_Handle handle)
{
    DRV_Obj *obj = (DRV_Obj *) handle;

    // ------------------------------------------------------------------------------
    // Reset and Start the RTI for the control loop time measurement
    // ------------------------------------------------------------------------------
    rtiResetCounter(rtiCOUNTER_BLOCK0);
    rtiStartCounter(rtiCOUNTER_BLOCK0);

    // Update ADC object
    adcGetData(adcREG1, adcGROUP1, obj->AdcResults1);
    //adcGetData(adcREG1, adcGROUP2, obj->AdcResults2);

    // ------------------------------------------------------------------------------
    // Update gate driver fault status and protect system
    // ------------------------------------------------------------------------------
    DRV_update_gdFaultStatus(handle);
    if (obj->faultDisableFlag == 0) {
  	  obj->controlMode = DISABLED;
  	  obj->faultDisableFlag  = 1;
    }

    // ------------------------------------------------------------------------------
    // Check for change in control mode from disabled to torque control/speed control
    // ------------------------------------------------------------------------------
    // Latch in change of control mode
    if (obj->prevCtrlType != obj->currCtrlType ) {
    	// Attempt to clear motor fault condition
    	if ((obj->gdFaultStatus != 3) && (obj->firstFaultRstEval == 0)) {
  		  DRV_gdFaultReset(handle);
  		  obj->firstFaultRstEval = 1;
    	}
    	else if ((obj->gdFaultStatus != 3) && (obj->firstFaultRstEval == 1)) {
  		  obj->prevCtrlType = obj->currCtrlType;
    	}
  		obj->prevCtrlType = obj->currCtrlType;
    }
    else {
  	  obj->prevCtrlType = obj->controlMode;
  	  obj->currCtrlType = obj->controlMode;
  	  obj->firstFaultRstEval = 0;
    }

    //Get the DC Bus Volage
    obj->vDCBus = (((float32_t)obj->AdcResults1[2].value) * 0.00024414);

    // ------------------------------------------------------------------------------
    // Run the InstaSpin Algorithm
    // ------------------------------------------------------------------------------
    if (obj->runBLDCInt == 1)
    {
        if (obj->calibrateFlag)
        {
            /* From TMS570_InstaSPIN */
            // Get BEMF Values
            obj->iqVaIn = (((float32_t)obj->AdcResults1[5].value) * 0.00024414) - obj->instaHandle->vaOffset;
            obj->iqVbIn = (((float32_t)obj->AdcResults1[1].value) * 0.00024414) - obj->instaHandle->vbOffset;
            obj->iqVcIn = (((float32_t)obj->AdcResults1[3].value) * 0.00024414) - obj->instaHandle->vcOffset;

            // LPF to average the calibration offsets
            // Use the offsets calculated here to initialize BemfA_offset, BemfB_offset
            // and BemfC_offset so that they are used for the remaining build levels
            obj->instaHandle->vaOffset = (obj->calFiltGain * obj->iqVaIn) + obj->instaHandle->vaOffset;
            obj->instaHandle->vbOffset = (obj->calFiltGain * obj->iqVbIn) + obj->instaHandle->vbOffset;
            obj->instaHandle->vcOffset = (obj->calFiltGain * obj->iqVcIn) + obj->instaHandle->vcOffset;

            obj->iDCOffset = (obj->calFiltGain * obj->iDCFdbk) + obj->iDCOffset;

            // Turn Off All PWMs
        	PWM_setOneShotTrip(obj->pwmHandle[0]);// Disable PWM A leg
        	PWM_setOneShotTrip(obj->pwmHandle[1]);// Disable PWM B leg
        	PWM_setOneShotTrip(obj->pwmHandle[2]);// Disable PWM C leg
            //hetREG1->DIR = ALL_PHASES_OFF; JPB

            obj->calibrateFlag++;
            obj->calibrateFlag &= obj->calibrateTime;
        }
        else
        {
            /* From TMS570_InstaSPIN */
            // Get BEMF Values
            obj->iqVaIn = ((float32_t)obj->AdcResults1[5].value) * 0.00024414;
            obj->iqVbIn = ((float32_t)obj->AdcResults1[1].value) * 0.00024414;
            obj->iqVcIn = ((float32_t)obj->AdcResults1[3].value) * 0.00024414;

            // Connect inputs of the MOD6 module and call the Modulo 6 counter function.
            if (obj->ref > (0.0))
            {
                obj->mod6Handle->cntDirection = (1.0);
            }
            else
            {
                obj->mod6Handle->cntDirection = (-1.0);
            }

            obj->previousState = obj->mod6Handle->counter;
            MOD6CNT_Calc(obj->mod6Handle);

            // Connect inputs of the SPEED_PR module and call the speed calculation function.
            // While counting up we want positive speed
            if ((obj->mod6Handle->counter == 5) && (obj->previousState == 4) && (obj->mod6Handle->trigInput))
            {
                obj->speedHandle->curTimeStamp = obj->virtualTimer;
                SPEED_MEAS_CAP_Calc(obj->speedHandle);
                obj->speedLoopFlag = TRUE;
            }
            // While counting down we want negative speed
            else if ((obj->mod6Handle->counter == 0) && (obj->previousState == 1) && (obj->mod6Handle->trigInput))
            {
                obj->speedHandle->curTimeStamp = obj->virtualTimer;
                SPEED_MEAS_CAP_Calc(obj->speedHandle);
                obj->speedHandle->speed = (obj->speedHandle->speed * (-1.0));
                obj->speedHandle->speedRPM = (obj->speedHandle->speedRPM * (-1.0));
                obj->speedLoopFlag = TRUE;
            }

            // Connect inputs of the INSTASPIN_BLDC module and call the INSTASPIN_BLDC function.
            obj->instaHandle->vag = obj->iqVaIn - obj->instaHandle->vaOffset; // Adjust for offset of Va_in
            obj->instaHandle->vbg = obj->iqVbIn - obj->instaHandle->vbOffset; // Adjust for offset of Vb_in
            obj->instaHandle->vcg = obj->iqVcIn - obj->instaHandle->vcOffset; // Adjust for offset of Vc_in
            obj->instaHandle->state = obj->mod6Handle->counter;            // Update the state
            InstaSPIN_BLDC_Calc(obj->instaHandle);
            obj->mod6Handle->trigInput = obj->instaHandle->commTrig;

            if ((obj->closedCommutationFlag == 0) || (obj->speedLoopFlag == FALSE))
            {
                // Connect inputs of the RMP3 module and call the Ramp control 3 function
                RMP3_Calc(obj->rmp3Handle);

                // Connect inputs of the IMPULSE module and call the Impulse function.
                obj->impulseHandle->period = obj->rmp3Handle->out;
                IMPULSE_Calc(obj->impulseHandle);

                // Connect inputs of the MOD6 module and call the Modulo 6 counter function.
                obj->mod6Handle->trigInput = obj->impulseHandle->out;

                if (obj->advancedStartup)
                {
                    // When the BEMF signals it's time to commutate, compare against the forced commutation period
                    if (obj->instaHandle->commTrig)
                    {
                        obj->bemfLastTrigCnt = obj->bemfTrigCnt;
                        obj->bemfTrigCnt = 0;
                        // Check if the forced commutation period and the BEMF commutation period
                        // are within the allowed error window
                        if (labs(obj->bemfLastTrigCnt - obj->impulseHandle->period) < obj->goodTrigCntTrip)
                        {
                            obj->goodTrigCnt++;
                        }
                        else
                        {
                            obj->goodTrigCnt = 0;
                        }
                        obj->bemfLastTrigCnt = 0;
                    }
                    else
                    {
                        obj->bemfTrigCnt++;
                    }
                    // Check if there are enough commutation matches to switch to closed commutation mode
                    if (obj->goodTrigCnt > obj->tripCnt)
                    {
                        obj->closedCommutationFlag = 1;
                    }
                }
                // If we're not using advanced startup just switch to closed commutation mode at the end of the startup ramp.
                else if (obj->rmp3Handle->ramp3DoneFlag != 0)
                {
                	obj->closedCommutationFlag = 1;
                }
            }
            switch (obj->controlMode)
            {
                case VOLTAGE:
                    if (obj->closedCommutationFlag == 0)
                    {
                        obj->speedLoopFlag = 1; //no need to wait for speed feedback update in this mode.
                        obj->rmpCntlHandle->setpointValue = (obj->dFuncStartup * obj->mod6Handle->cntDirection);

                    }
                    else
                    {
                        // Connect inputs of the RMP module and call the Ramp control function.
                        obj->rmpCntlHandle->targetValue = obj->ref;
                        RMPCNTL_Calc(obj->rmpCntlHandle);
                    }
                    // Connect inputs of the PWM_DRV module and call the PWM signal generation update function.
                    Generate_Outputs(handle, obj->rmpCntlHandle->setpointValue, obj->instaHandle->state, &obj->gPwmData.Tabc, &obj->currentSync, &obj->hetIOstate);
                    break;
                case CURRENT:
                    obj->iRef = obj->ref;
                    if (obj->closedCommutationFlag == 0)
                    {
                        obj->speedLoopFlag = 1;
                        // Use startup current during initial ramp
                        obj->iRef = (obj->currentStartup * obj->mod6Handle->cntDirection);
                    }
                    // Connect inputs of the PID_REG3 module and call the PID current controller function.
                    PID_run(obj->pidIDCHandle, obj->iRef, obj->iDCFdbk, &obj->pidIDCValue);
                    Generate_Outputs(handle, obj->pidIDCValue, obj->instaHandle->state, &obj->gPwmData.Tabc, &obj->currentSync, &obj->hetIOstate);
                    break;
                case VELOCITY:
                    obj->speedRef = obj->ref;
                    // Connect inputs of the PID_REG3 module and call the PID current controller function.
                    // Switch from fixed duty-cycle or controlled Speed duty-cycle by SpeedLoopFlag variable
                    if ((obj->closedCommutationFlag == 0) || (obj->speedLoopFlag == FALSE))
                    {
                        obj->iqDuty = (obj->dFuncStartup * obj->mod6Handle->cntDirection); // Fixed duty-cycle
                    }
                    else
                    {
                        PID_run(obj->pidSpdHandle, obj->speedRef, obj->speedHandle->speed, &obj->pidSpdValue);
                        obj->iqDuty = obj->pidSpdValue;
                    }
                    // Generate the PWM and Reset outputs
                    Generate_Outputs(handle, obj->iqDuty, obj->instaHandle->state, &obj->gPwmData.Tabc, &obj->currentSync, &obj->hetIOstate);
                    break;
                case CASCADE:
                    obj->speedRef = obj->ref;
                    if ((obj->closedCommutationFlag == 0) || (obj->speedLoopFlag == FALSE))
                    {
                        PID_run(obj->pidIDCHandle, (obj->currentStartup * obj->mod6Handle->cntDirection), obj->iDCFdbk, &obj->pidIDCValue);
                    }
                    else
                    {
                        // Connect Speed PID output to IDC PID input
                        PID_run(obj->pidSpdHandle, obj->speedRef, obj->speedHandle->speed, &obj->pidSpdValue);
                        PID_run(obj->pidIDCHandle, obj->pidSpdValue, obj->iDCFdbk, &obj->pidIDCValue);
                    }
                    Generate_Outputs(handle, obj->pidIDCValue, obj->instaHandle->state, &obj->gPwmData.Tabc, &obj->currentSync, &obj->hetIOstate);
                    break;
                default:
                    // Connect inputs of the PWM_DRV module and call the PWM signal generation update function.
                    Generate_Outputs(handle, OFF, obj->instaHandle->state, &obj->gPwmData.Tabc, &obj->currentSync, &obj->hetIOstate);
                    break;
            }

            // convert pwm values from float to int16 and write the PWM data
            PWM_write_CmpA(obj->pwmHandle[0],(int16_t)(obj->gPwmData.Tabc.value[0]*32768));
            PWM_write_CmpA(obj->pwmHandle[1],(int16_t)(obj->gPwmData.Tabc.value[1]*32768));
            PWM_write_CmpA(obj->pwmHandle[2],(int16_t)(obj->gPwmData.Tabc.value[2]*32768));
            //PWM_write_Cmp(obj->pwmHandle[0], (int16_t) (obj->gPwmData.Tabc.value[0] * 32768));
            //PWM_write_Cmp(obj->pwmHandle[1], (int16_t) (obj->gPwmData.Tabc.value[0] * 32768));
            //PWM_write_Cmp(obj->pwmHandle[2], (int16_t) (obj->gPwmData.Tabc.value[1] * 32768));
            //PWM_write_Cmp(obj->pwmHandle[3], (int16_t) (obj->gPwmData.Tabc.value[1] * 32768));
            //PWM_write_Cmp(obj->pwmHandle[4], (int16_t) (obj->gPwmData.Tabc.value[2] * 32768));
            //PWM_write_Cmp(obj->pwmHandle[5], (int16_t) (obj->gPwmData.Tabc.value[2] * 32768));
            //PWM_write_Cmp(obj->pwmISync, (int16_t) (obj->currentSync * 32768));

            //sync the PWMs and ADC
            //PWM_Sync(obj->pwmSyncHandle);
            //hetREG1->DIR = obj->hetIOstate;

            //DC bus current
        	switch (obj->instaHandle->state) {
        	case 0:
        	case 1:
        		// positive current in A
        		obj->iDCFdbk = ((obj->AdcResults1[0].value << 4) - obj->cal_offset_A) * 0.0000305176;
        		break;

        	case 2:
        	case 3:
        		// positive current in B
        		obj->iDCFdbk = ((obj->AdcResults1[4].value << 4) - obj->cal_offset_B) * 0.0000305176;
        		break;

        	case 4:
        		// negative current in A
        		obj->iDCFdbk = ((obj->AdcResults1[0].value << 4) - obj->cal_offset_A) * -0.0000305176;
        		break;

        	case 5:
        		// negative current in B
        		obj->iDCFdbk = ((obj->AdcResults1[4].value << 4) - obj->cal_offset_B) * -0.0000305176;
        		break;
        	default:
        		obj->iDCFdbk = 0.0;
        	}

            //Filter the displayed speed
            obj->speed = (obj->spdFiltGain * (obj->speedHandle->speed - obj->speed)) + obj->speed;
            obj->speedRPM = (obj->speedHandle->baseRPM * obj->speed);

            obj->floatCounter = (float) obj->mod6Handle->counter;

            // Increase virtual timer and force 15 bit wrap around
            obj->virtualTimer++;
            obj->virtualTimer &= 0x00007FFF;

            obj->currentDisplay = obj->iDCFdbk;
            obj->instaHandle->intThreshold = obj->threshold;
        }
    }

    // ------------------------------------------------------------------------------
    // Stop the RTI for the control loop time measurement
    // ------------------------------------------------------------------------------
    rtiStopCounter(rtiCOUNTER_BLOCK0);
    obj->rtiCounterValue = rtiGetCurrentTick(rtiCOMPARE0);
    obj->rtiBenchmarkTime = obj->rtiCounterValue * 0.001; 	// 1 tick corresponds to 1ms
    return;
} // end of DRV_run() function

/*!
 * @ingroup         Generate_Outputs
 * @fn              void Generate_Outputs(DRV_Handle drvHandle)
 * @brief           Function to determine the duty cycle and output necessary PWMs
 * @param [in]  drvHandle	The Handler for the DRV System
 * @param [in]  drvHandle	The Handler for the DRV System
 * @param [in]  duty		The commanded duty cycle for the pwm
 * @param [in]  state		The commutation state
 * @param [out]  pwmData_out		The switching waveforms in duty cycle
 * @param [out]  currentSyncOut		The duty cycle of the current sampling (used if ADC2 is used for Itotal sampling)
 * @param [out]  hetIOstateOut		The active IO for the PWM signals (one phase has to be disabled)
 */
inline void Generate_Outputs(DRV_Handle drvHandle, float32_t duty, int32_t state, MATH_vec3 *pwmData_out, float32_t *currentSyncOut, uint32_t *hetIOstateOut)
{
    float32_t posDuty = duty;
    float32_t negDuty = duty * -1;
    static int32_t prevState;

    // center the current sample pulse in the center of the PWM on time
    *currentSyncOut = (float32_t)(posDuty*0.5);

    //Ensure there is no cross talk when switching states
    if(state != prevState)
    {
    	PWM_setOneShotTrip(drv.pwmHandle[0]);// Disable PWM A leg
    	PWM_setOneShotTrip(drv.pwmHandle[1]);// Disable PWM B leg
    	PWM_setOneShotTrip(drv.pwmHandle[2]);// Disable PWM C leg
    }
    else
    {
		switch (state)
		{
			case (0):
				// Phase C is off
				PWM_clearOneShotTrip(drv.pwmHandle[0]);// Enable PWM A leg
				PWM_clearOneShotTrip(drv.pwmHandle[1]);// Enable PWM B leg
				PWM_setOneShotTrip(drv.pwmHandle[2]);// Disable PWM C leg

				pwmData_out->value[1] = posDuty;	// Phase B
				pwmData_out->value[0] = negDuty;	// Phase A
				break;
			case (1):
				// Phase B is off
				PWM_clearOneShotTrip(drv.pwmHandle[0]);// Enable PWM A leg
				PWM_setOneShotTrip(drv.pwmHandle[1]);// Disable PWM B leg
				PWM_clearOneShotTrip(drv.pwmHandle[2]);// Enable PWM C leg

				pwmData_out->value[2] = posDuty;	// Phase C
				pwmData_out->value[0] = negDuty;	// Phase A
				break;
			case (2):
				// Phase A is off
				PWM_setOneShotTrip(drv.pwmHandle[0]);// Disable PWM A leg
				PWM_clearOneShotTrip(drv.pwmHandle[1]);// Enable PWM B leg
				PWM_clearOneShotTrip(drv.pwmHandle[2]);// Enable PWM C leg

				pwmData_out->value[2] = posDuty;	// Phase C
				pwmData_out->value[1] = negDuty;	// Phase B
				break;
			case (3):
				// Phase C is off
				PWM_clearOneShotTrip(drv.pwmHandle[0]);// Enable PWM A leg
				PWM_clearOneShotTrip(drv.pwmHandle[1]);// Enable PWM B leg
				PWM_setOneShotTrip(drv.pwmHandle[2]);// Disable PWM C leg

				pwmData_out->value[0] = posDuty;	// Phase A
				pwmData_out->value[1] = negDuty;	// Phase B
				break;
			case (4):
				// Phase B is off
				PWM_clearOneShotTrip(drv.pwmHandle[0]);// Enable PWM A leg
				PWM_setOneShotTrip(drv.pwmHandle[1]);// Disable PWM B leg
				PWM_clearOneShotTrip(drv.pwmHandle[2]);// Enable PWM C leg

				pwmData_out->value[0] = posDuty;	// Phase A
				pwmData_out->value[2] = negDuty;	// Phase C
				break;
			case (5):
				// Phase A is off
				PWM_setOneShotTrip(drv.pwmHandle[0]);// Disable PWM A leg
				PWM_clearOneShotTrip(drv.pwmHandle[1]);// Enable PWM B leg
				PWM_clearOneShotTrip(drv.pwmHandle[2]);// Enable PWM C leg

				pwmData_out->value[1] = posDuty;	// Phase B
				pwmData_out->value[2] = negDuty;	// Phase C
				break;
		}
    }
    prevState = state;
} // end of Generate_Outputs() function

//! \brief     	Gets the status of the controller enable flag
//! \param[in] 	handle  	The controller (CTRL) handle
//! \return		EnableFlg  	Current value of enable flag
inline uint16_t DRV_get_Enable(DRV_Handle handle)
{
    DRV_Obj *obj = (DRV_Obj *) handle;

    return (obj->enableFlag);
}

//! \brief     Starts the Motor Controller
//! \param[in] handle          		The drv handle
inline void DRV_Motor_start(DRV_Handle handle)
{
    DRV_Obj *obj = (DRV_Obj *)handle;

    //QEP_Clear_Index(obj->qepIndexHandle);
    adcStartConversion(adcREG1, adcGROUP1);
	PWM_clearOneShotTrip(obj->pwmHandle[0]);// Enable PWM A leg
	PWM_clearOneShotTrip(obj->pwmHandle[1]);// Enable PWM B leg
	PWM_clearOneShotTrip(obj->pwmHandle[2]);// Enable PWM C leg

    //if ((hetREG1->GCR & 1) == 0)
    //    hetREG1->GCR = 0x00030001U;	// Start HET

    return;
}

//! \brief     Stops the Motor Controller (Not used in this project)
//! \param[in] handle          		The drv handle
inline void DRV_Motor_stop(DRV_Handle handle)
{
    DRV_Obj *obj = (DRV_Obj *) handle;

    //hetREG1->GCR = 0x00030000U;							// Stop HET
    //hetREG1->DOUT = 0x000A0000U;						// Set PWM signals
    adcStopConversion(adcREG1, adcGROUP1);				// Stop ADC
    adcStopConversion(adcREG1, adcGROUP2);

    //QEP_Clear_Index(obj->qepIndexHandle);
    //obj->gPwmData.Tabc.value[0] = 31 << 7;				// Clear the PWM Compares
    //obj->gPwmData.Tabc.value[1] = 31 << 7;				// Clear the PWM Compares
    //obj->gPwmData.Tabc.value[2] = 31 << 7;				// Clear the PWM Compares
	PWM_setOneShotTrip(obj->pwmHandle[0]);// Disable PWM A leg
	PWM_setOneShotTrip(obj->pwmHandle[1]);// Disable PWM B leg
	PWM_setOneShotTrip(obj->pwmHandle[2]);// Disable PWM C leg

    return;
}

//! \brief     Gets adcData
//! \param[in] handle          The drv handle
//! \return    adcData (phase current and voltage data)
inline ADC_Data_t DRV_get_adcData(DRV_Handle handle)
{
    DRV_Obj *drv = (DRV_Obj *) handle;

    return (drv->adcData);
}

//! \brief     Gets rtiBenchmarkTime value
//! \param[in] handle			The drv handle
//! \return    rtiBenchmarkTime Current value of rti based FOC isr service time
inline float32_t DRV_get_rtiBenchmarkTime(DRV_Handle handle)
{
    DRV_Obj *drv = (DRV_Obj *) handle;

    return (drv->rtiBenchmarkTime);
}


//! \brief     	Gets the status of the driver bridgeFaultFlg
//! \param[in] 	handle		The drv handle
//! \return		EnableFlg  	Current value of bridgeFaultFlg
inline uint32_t DRV_get_bridgeFaultFlg(DRV_Handle handle)
{
	DRV_Obj *drv = (DRV_Obj *) handle;

	return( drv->bridgeFaultFlg);
}

//! \brief     	Gets the status of the driver overVoltageFlg
//! \param[in] 	handle		The drv handle
//! \return		EnableFlg  	Current value of overVoltageFlg
inline uint32_t DRV_get_overVoltageFlg(DRV_Handle handle)
{
	DRV_Obj *drv = (DRV_Obj *) handle;

	return( drv->overVoltageFlg);
}

//! \brief     	Gets the status of the driver overTempFlg
//! \param[in] 	handle		The drv handle
//! \return		EnableFlg  	Current value of overTempFlg
inline uint32_t DRV_get_overTempFlg(DRV_Handle handle)
{
	DRV_Obj *drv = (DRV_Obj *) handle;

	return( drv->overTempFlg);
}

inline void custom_run(DRV_Handle drvHandle){ // This is modeled after GUI_run but does not involve any gui related objects. **** This is the only edit made to the file

    DRV_Obj *drv = (DRV_Obj *)drvHandle;

   // Data Transfers happen here
      // Change parameters
      PID_setGains(drv->pidSpdHandle, PID_getProportionalGain(drv->pidSpdHandle), PID_getIntegralGain(drv->pidSpdHandle), PID_getDerivativeGain(drv->pidSpdHandle));
      PID_setMinMax(drv->pidSpdHandle, -(PID_getSaturation(drv->pidSpdHandle)), PID_getSaturation(drv->pidSpdHandle));

      PID_setGains(drv->pidIDCHandle, PID_getProportionalGain(drv->pidIDCHandle), PID_getIntegralGain(drv->pidIDCHandle),PID_getDerivativeGain(drv->pidIDCHandle));
      PID_setMinMax(drv->pidIDCHandle, -(PID_getSaturation(drv->pidIDCHandle)), PID_getSaturation(drv->pidIDCHandle));

      drv->threshold = 0.1;

      drv->controlMode = 0; //Duty Cycle mode
      drv->enableFlag = TRUE; //Always on
    //  Graph_set_prescalar(graphHandle, gui->LogScalar); //Omkar

      switch( drv->controlMode )
      {
      case(CURRENT):
  		drv->ref = 0.3;
      	drv->currentMode = 1;
      	drv->velocityMode = 0;
  		break;
      case(VELOCITY):
  		drv->ref = 0.3;
      	drv->currentMode = 0;
      	drv->velocityMode = 2;
  		break;
      case(CASCADE):
  		drv->ref = 0.3;
      	drv->currentMode = 1;
      	drv->velocityMode = 2;
      	break;
      default:
      	drv->ref = 0.3; //from sys_main.c in voltage mode
      	drv->currentMode = 0;
      	drv->velocityMode = 0;
      	break;
      }

      drv->dFuncStartup = 0.1;
      drv->rampUpTime = 25;
      drv->beginStartRPM = 50;
      drv->endStartRPM = 100;
      drv->advancedStartup = 0;
      drv->commErrorMax = 1.0;
      drv->tripCnt = 3;
      drv->currentStartup = 0.1;
      drv->iMax = 0.95;
      drv->minVDC = 1920;
      drv->maxVDC = 2880;

  	  drv->tpsFlag = 1; //TPS Flag is set here but may be too late

      return;
}



//! \brief     Sets up the PWMs (Pulse Width Modulators)
//! \param[in] handle          The driver (DRV) handle
//! \param[in] ISRperiod  	   ISR period in sec
//! \param[in] het_vCNT_SCALE  The scaler to the timer
void DRV_setupPwms(DRV_Handle handle, const float32_t ISRperiod, const int32_t het_vCNT_SCALE);

#ifdef __cplusplus
}
#endif // extern "C"
//@}  // ingroup



#endif // end of _DRV_H_ definition

Thank you in advance,

Omkar

  • Omar,

    First, try to launch a debug session from your CCXML file (Open Target Configuration Window, Right Click on your CCXML and do a "Launch Debug Session")

    This will bring up the debugger but not yet try to connect to the CPU.

    Then you'll see the Cortex R device w. a reddish "X" on it in the Debug window, under the emulator in a 'tree' type view.

    Make sure you have the Cortex R node selected. Then you should be able to do Ctrl-Shift-S, or Run->Reset->System Reset, or select system reset from the little 'black chip w. circulating arrows' icon on the toolbar.

    Usually if you issue a system reset then connect you'll be fine.

    -Anthony
  • Hi Anthony,

    Thanks for the quick reply! Unfortunately the same error appears after system reset when I try to connect the target:

    CortexR4: A fatal error occurred while attempting to remove the remaining debug state that could not be removed at disconnect. This might have occurred because a breakpoint was set at an address that is no longer valid. This behaviour may be turned off in the "Debug Properties" tab in the Customize dialog under the Option menu

    So I think the state of the board hasn't changed. In the linked thread, I had tried to do a CPU reset at the memory level but the same errors are returned.

    Thanks,
    Omkar
  • Also, I recall that you had mentioned that you were able to get the kit to run without the GUI by poking at the GUI Obj variables in the watch window. Did you have to modify the code at all in that case? Or did you just launch a debug session with the shipped code and change the values in the window without having to step through the program?
  • Hi Omar,

    Ok then there are more steps to the unbricking that you can try.
    But to confirm - did the code that you uploaded always brick the boards? If so thank you I was looking for some test code to give to the folks that write the emulation drivers to see if there's a better way...

    Now this thread e2e.ti.com/.../264498
    has some instructions in the

    Tue, May 14 2013 2:44 PM

    Post from JM Mifsud that take you through the steps to use the DAP to issue a reset to the chip that hopefully should grab control if the system reset doesn't work.

    If not the other thing that works is to retry over and over while pressing the reset button until you hit the 'sweet spot' in the timing of the two events. You're trying to 'retry' to take control of the chip in some narrow time window between pressing the reset button and the code doing whatever bad thing it does to cause the CPU to be unresponsive to the debugger (like turning off the clocks on the chip, or accessing some memory location that never responds).


    Regarding your 2nd question - yes I've been able to spin the motor on the RM48 CNCD by just changing the GUI object variables in CCS's expression / watch window. Of course some of the variable names that are pulled up by the java script are wrong and need to be fixed.

    On the RM46 CNCD I haven't yet succeeded because there apparently is an extra variable for the TPS that needs to be set.. but I haven't figured it out yet. Got sidetracked doing some debugging and haven't come back to the motor board.
  • Hi Anthony,

    The first few times I uploaded my code, all seemed fine because I was able to erase the flash after. I think the problem arose after I did a debug session with the code and started stepping through it. I tried Mr. Mifsud's fix but unfortunately see the same issue, so I will try the approach of pressing the reset until I hit the sweet spot. Just to clarify when you say "the timing of the two events" do you mean I should hit the reset the second the board is powered up in order to prevent the bad code from taking hold of the CPU?

    Thanks,
    Omkar
  • Hi Omkar,

    No it's more like when you try to connect - it gives you the error message and asks you to retry.

    Then you're trying to get the timing 'just right' between clicking on the Retry button and (actually releasing) the physical reset button on the board. Try to almost vary the timing randomly a bit between doing these two. It seems like a lot but usually after maybe the first 50 or 100 clicks/presses it'll wind up connecting.

    If you get really stuck shoot me a private message and we can discuss more. Kind of looking for a good tough test case to throw at the emulation driver experts as really we'd like to be able to do something smarter than this random timing thing...)
  • Wow! Thanks so much, ended up getting it on the second try and the board is back! Really appreciate the help.