Other Parts Discussed in Thread: CONTROLSUITE, MOTORWARE, DRV8301, DRV8305, DRV8323, C2000WARE
Tool/software: Code Composer Studio
Hello,
I am trying to build a I2C connection between the F28379D and F28027F and I am using the I2C eeprom Examples from controlSuite. I also want to read out ADC Values with the F28379D and control the speed with the motorware lab05b with the F28027F.
My Question are if the first code is correct, I am reading out the ADC Values and put it in the MsgBuffer?
And which Variable is to controll the speed in Lab05b, if it is spdKp do i just have to set it the same with MsgBuffer?
F28379D Code:
//
// Included Files
//
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <file.h>
#include "F28x_Project.h" // DSP28x Headerfile
#include "sci_io.h"
//
// Defines
//
#define I2C_SLAVE_ADDR 0x50
#define I2C_NUMBYTES 2
#define I2C_EEPROM_HIGH_ADDR 0x00
#define I2C_EEPROM_LOW_ADDR 0x30
//
// Micro-seconds to wait for ADC conversion. Longer than necessary.
//
#define CONV_WAIT 1L
//
// Function Prototypes
//
void I2CA_Init(void);
Uint16 I2CA_WriteData(struct I2CMSG *msg);
Uint16 I2CA_ReadData(struct I2CMSG *msg);
__interrupt void i2c_int1a_isr(void);
void pass(void);
void fail(void);
int16_t currentSample;
//
// Globals
//
struct I2CMSG I2cMsgOut1={ I2C_MSGSTAT_SEND_WITHSTOP,
I2C_SLAVE_ADDR,
I2C_NUMBYTES,
I2C_EEPROM_HIGH_ADDR,
I2C_EEPROM_LOW_ADDR,
0x12, // Msg Byte 1
0x34}; // Msg Byte 2
struct I2CMSG I2cMsgIn1={ I2C_MSGSTAT_SEND_NOSTOP,
I2C_SLAVE_ADDR,
I2C_NUMBYTES,
I2C_EEPROM_HIGH_ADDR,
I2C_EEPROM_LOW_ADDR};
struct I2CMSG *CurrentMsgPtr;
Uint16 PassCount;
Uint16 FailCount;
extern void DSP28x_usDelay(Uint32 Count);
const unsigned char escRed[] = {0x1B, 0x5B, '3','1', 'm'};
const unsigned char escWhite[] = {0x1B, 0x5B, '3','7', 'm'};
const unsigned char escLeft[] = {0x1B, 0x5B, '3','7', 'm'};
const unsigned char pucTempString[] = "ADCIN14 Sample: ";
//
// sampleADC -
//
int16_t sampleADC(void)
{
int16_t sample;
//
// Force start of conversion on SOC0
//
AdcaRegs.ADCSOCFRC1.all = 0x03;
//
// Wait for end of conversion.
//
while(AdcaRegs.ADCINTFLG.bit.ADCINT1 == 0)
{
//
// Wait for ADCINT1
//
}
AdcaRegs.ADCINTFLGCLR.bit.ADCINT1 = 1; // Clear ADCINT1
//
// Get ADC sample result from SOC0
//
sample = AdcaResultRegs.ADCRESULT1;
return(sample);
}
//
// scia_init - SCIA 8-bit word, baud rate 0x000F, default, 1 STOP bit,
// no parity
//
void scia_init()
{
//
// Note: Clocks were turned on to the SCIA peripheral
// in the InitSysCtrl() function
//
//
// 1 stop bit, No loopback, No parity,8 char bits, async mode,
// idle-line protocol
//
SciaRegs.SCICCR.all =0x0007;
//
// enable TX, RX, internal SCICLK, Disable RX ERR, SLEEP, TXWAKE
//
SciaRegs.SCICTL1.all =0x0003;
SciaRegs.SCICTL2.bit.TXINTENA =1;
SciaRegs.SCICTL2.bit.RXBKINTENA =1;
//
// 115200 baud @LSPCLK = 22.5MHz (90 MHz SYSCLK)
//
SciaRegs.SCIHBAUD.all =0x0000;
SciaRegs.SCILBAUD.all =53;
SciaRegs.SCICTL1.all =0x0023; // Relinquish SCI from Reset
return;
}
//
// Main
//
void main(void)
{
Uint16 Error;
Uint16 i;
volatile int status = 0;
CurrentMsgPtr = &I2cMsgOut1;
//
// Step 1. Initialize System Control:
// PLL, WatchDog, enable Peripheral Clocks
// This example function is found in the F2837xD_SysCtrl.c file.
//
InitSysCtrl();
//
// Step 2. Initialize GPIO:
// This example function is found in the F2837xD_Gpio.c file and
// illustrates how to set the GPIO to it's default state.
//
InitGpio();
//
// For this example, only init the pins for the SCI-A port.
// These functions are found in the F2837xD_Gpio.c file.
//
GPIO_SetupPinMux(32, GPIO_MUX_CPU1, 1);
GPIO_SetupPinMux(33, GPIO_MUX_CPU1, 1);
//
// Step 3. Clear all __interrupts and initialize PIE vector table:
// Disable CPU __interrupts
//
DINT;
//
// Initialize PIE control registers to their default state.
// The default state is all PIE __interrupts disabled and flags
// are cleared.
// This function is found in the F2837xD_PieCtrl.c file.
//
InitPieCtrl();
//
// Disable CPU __interrupts and clear all CPU __interrupt flags:
//
IER = 0x0000;
IFR = 0x0000;
//
// Initialize the PIE vector table with pointers to the shell Interrupt
// Service Routines (ISR).
// This will populate the entire table, even if the __interrupt
// is not used in this example. This is useful for debug purposes.
// The shell ISR routines are found in F2837xD_DefaultIsr.c.
// This function is found in F2837xD_PieVect.c.
//
InitPieVectTable();
//
// Interrupts that are used in this example are re-mapped to
// ISR functions found within this file.
//
EALLOW; // This is needed to write to EALLOW protected registers
PieVectTable.I2CA_INT = &i2c_int1a_isr;
EDIS; // This is needed to disable write to EALLOW protected registers
//
// Step 4. Initialize the Device Peripherals:
//
I2CA_Init();
//
// Step 5. User specific code
//
//
// Clear Counters
//
PassCount = 0;
FailCount = 0;
//
// Clear incoming message buffer
//
for (i = 0; i < I2C_MAX_BUFFER_SIZE; i++)
{
I2cMsgIn1.MsgBuffer[i] = 0x0000;
}
//
// Enable __interrupts required for this example
//
//
// Enable I2C __interrupt 1 in the PIE: Group 8 __interrupt 1
//
PieCtrlRegs.PIEIER8.bit.INTx1 = 1;
//
// Enable CPU INT8 which is connected to PIE group 8
//
IER |= M_INT8;
EINT;
//
// If running from flash copy RAM only functions to RAM
//
#ifdef _FLASH
memcpy(&RamfuncsRunStart, &RamfuncsLoadStart, (size_t)&RamfuncsLoadSize);
#endif
//
// Initialize System Control:
// PLL, WatchDog, enable Peripheral Clocks
// This example function is found in the F2806x_SysCtrl.c file.
//
InitSysCtrl();
//
// For this example, only init the pins for the SCI-A port.
//
EALLOW;
GpioCtrlRegs.GPBMUX1.bit.GPIO42 = 3;
GpioCtrlRegs.GPBMUX1.bit.GPIO43 = 3;
GpioCtrlRegs.GPBGMUX1.bit.GPIO42 = 3;
GpioCtrlRegs.GPBGMUX1.bit.GPIO43 = 3;
EDIS;
//
// Clear all interrupts and initialize PIE vector table:
// Disable CPU interrupts
//
DINT;
//
// Initialize PIE control registers to their default state.
// The default state is all PIE interrupts disabled and flags
// are cleared.
// This function is found in the F2837xD_PieCtrl.c file.
//
InitPieCtrl();
//
// Disable CPU interrupts and clear all CPU interrupt flags
//
IER = 0x0000;
IFR = 0x0000;
//
// Initialize the PIE vector table with pointers to the shell Interrupt
// Service Routines (ISR).
// This will populate the entire table, even if the interrupt
// is not used in this example. This is useful for debug purposes.
// The shell ISR routines are found in F2837xD_DefaultIsr.c.
// This function is found in F2837xD_PieVect.c.
//
InitPieVectTable();
//
// Initialize SCIA
//
scia_init();
//
// Initialize GPIOs for the LEDs and turn them off
//
EALLOW;
GpioCtrlRegs.GPADIR.bit.GPIO31 = 1;
GpioCtrlRegs.GPBDIR.bit.GPIO34 = 1;
GpioDataRegs.GPADAT.bit.GPIO31 = 1;
GpioDataRegs.GPBDAT.bit.GPIO34 = 1;
EDIS;
//
// Enable global Interrupts and higher priority real-time debug events:
//
EINT; // Enable Global interrupt INTM
ERTM; // Enable Global realtime interrupt DBGM
//
// Configure the ADC: Initialize the ADC
//
EALLOW;
//
// write configurations
//
AdcaRegs.ADCCTL2.bit.PRESCALE = 6; // set ADCCLK divider to /4
AdcbRegs.ADCCTL2.bit.PRESCALE = 6; // set ADCCLK divider to /4
AdcSetMode(ADC_ADCA, ADC_RESOLUTION_12BIT, ADC_SIGNALMODE_SINGLE);
AdcSetMode(ADC_ADCB, ADC_RESOLUTION_12BIT, ADC_SIGNALMODE_SINGLE);
//
// Set pulse positions to late
//
AdcaRegs.ADCCTL1.bit.INTPULSEPOS = 1;
AdcbRegs.ADCCTL1.bit.INTPULSEPOS = 1;
//
// power up the ADCs
//
AdcaRegs.ADCCTL1.bit.ADCPWDNZ = 1;
AdcbRegs.ADCCTL1.bit.ADCPWDNZ = 1;
//
// delay for 1ms to allow ADC time to power up
//
DELAY_US(1000);
//
// ADCA
//
EALLOW;
AdcaRegs.ADCSOC0CTL.bit.CHSEL = 0x0E; //SOC0 will convert pin ADCIN14
//
// sample window is acqps + 1 SYSCLK cycles
//
AdcaRegs.ADCSOC0CTL.bit.ACQPS = 25;
AdcaRegs.ADCSOC1CTL.bit.CHSEL = 0x0E; //SOC1 will convert pin ADCIN14
//
// sample window is acqps + 1 SYSCLK cycles
//
AdcaRegs.ADCSOC1CTL.bit.ACQPS = 25;
AdcaRegs.ADCINTSEL1N2.bit.INT1SEL = 1; //end of SOC1 will set INT1 flag
AdcaRegs.ADCINTSEL1N2.bit.INT1E = 1; //enable INT1 flag
AdcaRegs.ADCINTFLGCLR.bit.ADCINT1 = 1; //make sure INT1 flag is cleared
//
// Redirect STDOUT to SCI
//
status = add_device("scia", _SSA, SCI_open, SCI_close, SCI_read, SCI_write,
SCI_lseek, SCI_unlink, SCI_rename);
freopen("scia:", "w", stdout);
setvbuf(stdout, NULL, _IONBF, 0);
//
// Twiddle LEDs
//
GpioDataRegs.GPADAT.bit.GPIO31 = 0;
GpioDataRegs.GPBDAT.bit.GPIO34 = 1;
for(i = 0; i < 50; i++)
{
GpioDataRegs.GPATOGGLE.bit.GPIO31 = 1;
GpioDataRegs.GPBTOGGLE.bit.GPIO34 = 1;
DELAY_US(50000);
}
//
// LEDs off
//
GpioDataRegs.GPADAT.bit.GPIO31 = 1;
GpioDataRegs.GPBDAT.bit.GPIO34 = 1;
currentSample = sampleADC();
for(;;)
{
//
// Sample ADCIN14
//
currentSample = sampleADC();
//
// If the sample is above midscale light one LED
//
if(currentSample > 2048)
{
GpioDataRegs.GPBSET.bit.GPIO34 = 1;
GpioDataRegs.GPACLEAR.bit.GPIO31 = 1;
}
else
{
//
// Otherwise light the other
//
GpioDataRegs.GPBCLEAR.bit.GPIO34 = 1;
GpioDataRegs.GPASET.bit.GPIO31 = 1;
}
// DELAY_US(1000000);
// }
//
// Write data to EEPROM section
//
//
// Check the outgoing message to see if it should be sent.
// In this example it is initialized to send with a stop bit.
//
if(I2cMsgOut1.MsgStatus == I2C_MSGSTAT_SEND_WITHSTOP)
{
Error = I2CA_WriteData(&I2cMsgOut1);
//
// If communication is correctly initiated, set msg status to busy
// and update CurrentMsgPtr for the __interrupt service routine.
// Otherwise, do nothing and try again next loop. Once message is
// initiated, the I2C __interrupts will handle the rest. Search for
// ICINTR1A_ISR in the i2c_eeprom_isr.c file.
//
if (Error == I2C_SUCCESS)
{
CurrentMsgPtr = &I2cMsgOut1;
I2cMsgOut1.MsgStatus = I2C_MSGSTAT_WRITE_BUSY;
}
}
//
// Read data from EEPROM section
//
//
// Check outgoing message status. Bypass read section if status is
// not inactive.
//
if(I2cMsgOut1.MsgStatus == I2C_MSGSTAT_INACTIVE)
{
//
// Check incoming message status.
//
if(I2cMsgIn1.MsgStatus == I2C_MSGSTAT_SEND_NOSTOP)
{
//
// EEPROM address setup portion
//
while(I2CA_ReadData(&I2cMsgIn1) != I2C_SUCCESS)
{
//
// Maybe setup an attempt counter to break an infinite while
// loop. The EEPROM will send back a NACK while it is
// performing a write operation. Even though the write
// communique is complete at this point, the EEPROM could
// still be busy programming the data. Therefore, multiple
// attempts are necessary.
//
}
//
// Update current message pointer and message status
//
CurrentMsgPtr = &I2cMsgIn1;
I2cMsgIn1.MsgStatus = I2C_MSGSTAT_SEND_NOSTOP_BUSY;
}
//
// Once message has progressed past setting up the internal address
// of the EEPROM, send a restart to read the data bytes from the
// EEPROM. Complete the communique with a stop bit. MsgStatus is
// updated in the __interrupt service routine.
//
else if(I2cMsgIn1.MsgStatus == I2C_MSGSTAT_RESTART)
{
//
// Read data portion
//
while(I2CA_ReadData(&I2cMsgIn1) != I2C_SUCCESS)
{
//
// Maybe setup an attempt counter to break an infinite while
// loop.
//
}
//
// Update current message pointer and message status
//
CurrentMsgPtr = &I2cMsgIn1;
I2cMsgIn1.MsgStatus = I2C_MSGSTAT_READ_BUSY;
}
}
}
}// I2C Loop-end
//
// I2CA_Init - Initialize I2CA settings
//
void I2CA_Init(void)
{
I2caRegs.I2CSAR.all = 0x0050; // Slave address - EEPROM control code
I2caRegs.I2CPSC.all = 16; // Prescaler - need 7-12 Mhz on module clk
I2caRegs.I2CCLKL = 10; // NOTE: must be non zero
I2caRegs.I2CCLKH = 5; // NOTE: must be non zero
I2caRegs.I2CIER.all = 0x24; // Enable SCD & ARDY __interrupts
I2caRegs.I2CMDR.all = 0x0020; // Take I2C out of reset
// Stop I2C when suspended
I2caRegs.I2CFFTX.all = 0x6000; // Enable FIFO mode and TXFIFO
I2caRegs.I2CFFRX.all = 0x2040; // Enable RXFIFO, clear RXFFINT,
return;
}
//
// I2CA_WriteData - Transmit I2CA message
//
Uint16 I2CA_WriteData(struct I2CMSG *msg)
{
Uint16 i;
//
// Wait until the STP bit is cleared from any previous master communication.
// Clearing of this bit by the module is delayed until after the SCD bit is
// set. If this bit is not checked prior to initiating a new message, the
// I2C could get confused.
//
if(I2caRegs.I2CMDR.bit.STP == 1)
{
return I2C_STP_NOT_READY_ERROR;
}
//
// Setup slave address
//
I2caRegs.I2CSAR.all = msg->SlaveAddress;
//
// Check if bus busy
//
if(I2caRegs.I2CSTR.bit.BB == 1)
{
return I2C_BUS_BUSY_ERROR;
}
//
// Setup number of bytes to send
// MsgBuffer + Address
//
// currentSample = sampleADC();
msg->NumOfBytes = currentSample; //ADC-Sample setup
I2caRegs.I2CCNT = msg->NumOfBytes+2;
//
// Setup data to send
//
I2caRegs.I2CDXR.all = msg->MemoryHighAddr;
I2caRegs.I2CDXR.all = msg->MemoryLowAddr;
// CurrentMsgPtr->MsgBuffer[i] = I2caRegs.I2CDRR.all;
for (i=0; i < msg->NumOfBytes; i++)
{
msg->MsgBuffer[i] = I2caRegs.I2CDXR.all;
}
//
// Send start as master transmitter
//
I2caRegs.I2CMDR.all = 0x6E20;
return I2C_SUCCESS;
}
//
// I2CA_ReadData - Read I2CA Message
//
Uint16 I2CA_ReadData(struct I2CMSG *msg)
{
//
// Wait until the STP bit is cleared from any previous master communication.
// Clearing of this bit by the module is delayed until after the SCD bit is
// set. If this bit is not checked prior to initiating a new message, the
// I2C could get confused.
//
if(I2caRegs.I2CMDR.bit.STP == 1)
{
return I2C_STP_NOT_READY_ERROR;
}
I2caRegs.I2CSAR.all = msg->SlaveAddress;
if(msg->MsgStatus == I2C_MSGSTAT_SEND_NOSTOP)
{
//
// Check if bus busy
//
if(I2caRegs.I2CSTR.bit.BB == 1)
{
return I2C_BUS_BUSY_ERROR;
}
I2caRegs.I2CCNT = 2;
I2caRegs.I2CDXR.all = msg->MemoryHighAddr;
I2caRegs.I2CDXR.all = msg->MemoryLowAddr;
I2caRegs.I2CMDR.all = 0x2620; // Send data to setup EEPROM address
}
else if(msg->MsgStatus == I2C_MSGSTAT_RESTART)
{
I2caRegs.I2CCNT = msg->NumOfBytes; // Setup how many bytes to expect
I2caRegs.I2CMDR.all = 0x2C20; // Send restart as master receiver
}
return I2C_SUCCESS;
}
//
// i2c_int1a_isr - I2CA ISR
//
__interrupt void i2c_int1a_isr(void)
{
Uint16 IntSource, i;
//
// Read __interrupt source
//
IntSource = I2caRegs.I2CISRC.all;
//
// Interrupt source = stop condition detected
//
if(IntSource == I2C_SCD_ISRC)
{
//
// If completed message was writing data, reset msg to inactive state
//
if(CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_WRITE_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_INACTIVE;
}
else
{
//
// If a message receives a NACK during the address setup portion of
// the EEPROM read, the code further below included in the register
// access ready __interrupt source code will generate a stop
// condition. After the stop condition is received (here), set the
// message status to try again. User may want to limit the number of
// retries before generating an error.
if(CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_SEND_NOSTOP_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_SEND_NOSTOP;
}
//
// If completed message was reading EEPROM data, reset msg to
// inactive state and read data from FIFO.
//
else if(CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_READ_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_INACTIVE;
for(i=0; i < I2C_NUMBYTES; i++)
{
CurrentMsgPtr->MsgBuffer[i] = I2caRegs.I2CDRR.all;
}
//
// Check received data
//
for(i=0; i < I2C_NUMBYTES; i++)
{
if(I2cMsgIn1.MsgBuffer[i] == I2cMsgOut1.MsgBuffer[i])
{
PassCount++;
}
else
{
FailCount++;
}
}
if(PassCount == I2C_NUMBYTES)
{
pass();
}
else
{
fail();
}
}
}
}
//
// Interrupt source = Register Access Ready
// This __interrupt is used to determine when the EEPROM address setup
// portion of the read data communication is complete. Since no stop bit is
// commanded, this flag tells us when the message has been sent instead of
// the SCD flag. If a NACK is received, clear the NACK bit and command a
// stop. Otherwise, move on to the read data portion of the communication.
//
else if(IntSource == I2C_ARDY_ISRC)
{
if(I2caRegs.I2CSTR.bit.NACK == 1)
{
I2caRegs.I2CMDR.bit.STP = 1;
I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;
}
else if(CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_SEND_NOSTOP_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_RESTART;
}
}
else
{
//
// Generate some error due to invalid __interrupt source
//
__asm(" ESTOP0");
}
//
// Enable future I2C (PIE Group 8) __interrupts
//
PieCtrlRegs.PIEACK.all = PIEACK_GROUP8;
}
//
// pass - Halt debugger and signify pass
//
void pass()
{
__asm(" ESTOP0");
for(;;);
}
//
// fail - Halt debugger and signify fail
//
void fail()
{
__asm(" ESTOP0");
for(;;);
}
//
// End of file
//
F28027F Code:
// the includes
// system includes
#include <math.h>
#include "main.h"
#include "DSP28x_Project.h" // Device Headerfile and Examples Include File
#ifdef FLASH
#pragma CODE_SECTION(mainISR,"ramfuncs");
#endif
//
// Function Prototypes
//
void I2CA_Init(void);
uint16_t I2CA_WriteData(struct I2CMSG *msg);
uint16_t I2CA_ReadData(struct I2CMSG *msg);
__interrupt void i2c_int1a_isr(void);
void pass(void);
void fail(void);
// **************************************************************************
// the defines
#define LED_BLINK_FREQ_Hz 5
#define I2C_SLAVE_ADDR 0x50
#define I2C_NUMBYTES 2 // (4 byte ... int?)
#define I2C_EEPROM_HIGH_ADDR 0x00
#define I2C_EEPROM_LOW_ADDR 0x30
// **************************************************************************
// the globals
uint_least16_t gCounter_updateGlobals = 0;
bool Flag_Latch_softwareUpdate = true;
CTRL_Handle ctrlHandle;
#ifdef CSM_ENABLE
#pragma DATA_SECTION(halHandle,"rom_accessed_data");
#endif
HAL_Handle halHandle;
#ifdef CSM_ENABLE
#pragma DATA_SECTION(gUserParams,"rom_accessed_data");
#endif
USER_Params gUserParams;
HAL_PwmData_t gPwmData = {_IQ(0.0), _IQ(0.0), _IQ(0.0)};
HAL_AdcData_t gAdcData;
_iq gMaxCurrentSlope = _IQ(0.0);
#ifdef FAST_ROM_V1p6
CTRL_Obj *controller_obj;
#else
#ifdef CSM_ENABLE
#pragma DATA_SECTION(ctrl,"rom_accessed_data");
#endif
CTRL_Obj ctrl; //v1p7 format
#endif
uint16_t gLEDcnt = 0;
volatile MOTOR_Vars_t gMotorVars = MOTOR_Vars_INIT;
#ifdef FLASH
// Used for running BackGround in flash, and ISR in RAM
extern uint16_t *RamfuncsLoadStart, *RamfuncsLoadEnd, *RamfuncsRunStart;
#ifdef CSM_ENABLE
extern uint16_t *econst_start, *econst_end, *econst_ram_load;
extern uint16_t *switch_start, *switch_end, *switch_ram_load;
#endif
#endif
#ifdef DRV8301_SPI
// Watch window interface to the 8301 SPI
DRV_SPI_8301_Vars_t gDrvSpi8301Vars;
#endif
#ifdef DRV8305_SPI
// Watch window interface to the 8305 SPI
DRV_SPI_8305_Vars_t gDrvSpi8305Vars;
#endif
#ifdef DRV8323_SPI
// Watch window interface to the 8323 SPI
DRV_SPI_8323_Vars_t gDrvSpi8323Vars;
#endif
_iq gFlux_pu_to_Wb_sf;
_iq gFlux_pu_to_VpHz_sf;
_iq gTorque_Ls_Id_Iq_pu_to_Nm_sf;
_iq gTorque_Flux_Iq_pu_to_Nm_sf;
struct I2CMSG I2cMsgOut1=
{
// 8 bytes
I2C_MSGSTAT_SEND_WITHSTOP, // 1
I2C_SLAVE_ADDR, // 1
I2C_NUMBYTES, // 4
I2C_EEPROM_HIGH_ADDR, // 1
I2C_EEPROM_LOW_ADDR, // 1
//
// Msg Byte 1
//
0x12,
//
// Msg Byte 2
//
0x34
};
struct I2CMSG I2cMsgIn1=
{
// 8 bytes
I2C_MSGSTAT_SEND_NOSTOP, // 1
I2C_SLAVE_ADDR, // 1
I2C_NUMBYTES, // 4
I2C_EEPROM_HIGH_ADDR, // 1
I2C_EEPROM_LOW_ADDR // 1
};
//
// Used in interrupts
//
struct I2CMSG *CurrentMsgPtr;
uint16_t PassCount;
uint16_t FailCount;
// **************************************************************************
// the functions
void main(void)
{
uint_least8_t estNumber = 0;
#ifdef FAST_ROM_V1p6
uint_least8_t ctrlNumber = 1;
#endif
// Only used if running from FLASH
// Note that the variable FLASH is defined by the project
#ifdef FLASH
// Copy time critical code and Flash setup code to RAM
// The RamfuncsLoadStart, RamfuncsLoadEnd, and RamfuncsRunStart
// symbols are created by the linker. Refer to the linker files.
memCopy((uint16_t *)&RamfuncsLoadStart,(uint16_t *)&RamfuncsLoadEnd,(uint16_t *)&RamfuncsRunStart);
#ifdef CSM_ENABLE
//copy .econst to unsecure RAM
if(*econst_end - *econst_start)
{
memCopy((uint16_t *)&econst_start,(uint16_t *)&econst_end,(uint16_t *)&econst_ram_load);
}
//copy .switch ot unsecure RAM
if(*switch_end - *switch_start)
{
memCopy((uint16_t *)&switch_start,(uint16_t *)&switch_end,(uint16_t *)&switch_ram_load);
}
#endif
#endif
uint16_t writeDataWorked;
uint16_t i;
//
// WARNING: Always ensure you call memcpy before running any functions from
// RAM InitSysCtrl includes a call to a RAM based function and without a
// call to memcpy first, the processor will go "into the weeds"
#ifdef _FLASH
memcpy(&RamfuncsRunStart, &RamfuncsLoadStart, (size_t)&RamfuncsLoadSize);
#endif
CurrentMsgPtr = &I2cMsgOut1;
//
// Step 1. Initialize System Control:
// PLL, WatchDog, enable Peripheral Clocks
// This example function is found in the f2802x_SysCtrl.c file.
//
InitSysCtrl();
//
// Step 2. Initialize GPIO:
// This example function is found in the f2802x_Gpio.c file and
// illustrates how to set the GPIO to it's default state.
//
//InitGpio();
//
// Setup only the GP I/O only for I2C functionality
//
InitI2CGpio();
//
// Step 3. Clear all interrupts and initialize PIE vector table:
// Disable CPU interrupts
//
DINT;
//
// Initialize PIE control registers to their default state.
// The default state is all PIE interrupts disabled and flags
// are cleared.
// This function is found in the f2802x_PieCtrl.c file.
//
InitPieCtrl();
//
// Disable CPU interrupts and clear all CPU interrupt flags
//
IER = 0x0000;
IFR = 0x0000;
//
// Initialize the PIE vector table with pointers to the shell Interrupt
// Service Routines (ISR).
// This will populate the entire table, even if the interrupt
// is not used in this example. This is useful for debug purposes.
// The shell ISR routines are found in f2802x_DefaultIsr.c.
// This function is found in f2802x_PieVect.c.
//
InitPieVectTable();
//
// Interrupts that are used in this example are re-mapped to
// ISR functions found within this file.
//
EALLOW; // This is needed to write to EALLOW protected registers
PieVectTable.I2CINT1A = &i2c_int1a_isr;
EDIS; // This is needed to disable write to EALLOW protected registers
//
// Step 4. Initialize all the Device Peripherals
//
I2CA_Init(); // I2C-A only
//
// Step 5. User specific code
//
//
// Clear Counters
//
PassCount = 0;
FailCount = 0;
//
// Clear incoming message buffer
//
for (i = 0; i < (I2C_MAX_BUFFER_SIZE - 2); i++)
{
I2cMsgIn1.MsgBuffer[i] = 0x0000;
}
//
// Enable interrupts required for this example
//
//
// Enable I2C interrupt 1 in the PIE: Group 8 interrupt 1
//
// PieCtrlRegs.PIEIER8.bit.INTx1 = 1;
/* ==> do not need to enable interrupt since this program acts as slave */
//
// Enable CPU INT8 which is connected to PIE group 8
//
//IER |= M_INT8;
//EINT;
// initialize the hardware abstraction layer
halHandle = HAL_init(&hal,sizeof(hal));
// check for errors in user parameters
USER_checkForErrors(&gUserParams);
// store user parameter error in global variable
gMotorVars.UserErrorCode = USER_getErrorCode(&gUserParams);
// do not allow code execution if there is a user parameter error
if(gMotorVars.UserErrorCode != USER_ErrorCode_NoError)
{
for(;;)
{
gMotorVars.Flag_enableSys = false;
}
}
// initialize the user parameters
USER_setParams(&gUserParams);
// set the hardware abstraction layer parameters
HAL_setParams(halHandle,&gUserParams);
// initialize the controller
#ifdef FAST_ROM_V1p6
ctrlHandle = CTRL_initCtrl(ctrlNumber, estNumber); //v1p6 format (06xF and 06xM devices)
controller_obj = (CTRL_Obj *)ctrlHandle;
#else
ctrlHandle = CTRL_initCtrl(estNumber,&ctrl,sizeof(ctrl)); //v1p7 format default
#endif
{
CTRL_Version version;
// get the version number
CTRL_getVersion(ctrlHandle,&version);
gMotorVars.CtrlVersion = version;
}
// set the default controller parameters
CTRL_setParams(ctrlHandle,&gUserParams);
// setup faults
HAL_setupFaults(halHandle);
// initialize the interrupt vector table
HAL_initIntVectorTable(halHandle);
// enable the ADC interrupts
HAL_enableAdcInts(halHandle);
// enable global interrupts
HAL_enableGlobalInts(halHandle);
// enable debug interrupts
HAL_enableDebugInt(halHandle);
// disable the PWM
HAL_disablePwm(halHandle);
#ifdef DRV8301_SPI
// turn on the DRV8301 if present
HAL_enableDrv(halHandle);
// initialize the DRV8301 interface
HAL_setupDrvSpi(halHandle,&gDrvSpi8301Vars);
#endif
#ifdef DRV8305_SPI
// turn on the DRV8305 if present
HAL_enableDrv(halHandle);
// initialize the DRV8305 interface
HAL_setupDrvSpi(halHandle,&gDrvSpi8305Vars);
#endif
#ifdef DRV8323_SPI
// turn on the DRV8323 if present
HAL_enableDrv(halHandle);
// initialize the DRV8323 interface
HAL_setupDrvSpi(halHandle,&gDrvSpi8323Vars);
gDrvSpi8323Vars.Ctrl_Reg_06.CSA_GAIN = Gain_20VpV;
gDrvSpi8323Vars.Ctrl_Reg_06.VREF_DIV = 1;
gDrvSpi8323Vars.WriteCmd = true;
HAL_writeDrvData(halHandle,&gDrvSpi8323Vars);
gDrvSpi8323Vars.ReadCmd = true;
HAL_readDrvData(halHandle,&gDrvSpi8323Vars);
#endif
// enable DC bus compensation
CTRL_setFlag_enableDcBusComp(ctrlHandle, true);
// compute scaling factors for flux and torque calculations
gFlux_pu_to_Wb_sf = USER_computeFlux_pu_to_Wb_sf();
gFlux_pu_to_VpHz_sf = USER_computeFlux_pu_to_VpHz_sf();
gTorque_Ls_Id_Iq_pu_to_Nm_sf = USER_computeTorque_Ls_Id_Iq_pu_to_Nm_sf();
gTorque_Flux_Iq_pu_to_Nm_sf = USER_computeTorque_Flux_Iq_pu_to_Nm_sf();
for(;;)
{
//
// Write data to EEPROM section
//
//
// Check the outgoing message to see if it should be sent.
// In this example it is initialized to send with a stop bit.
//
if(I2cMsgOut1.MsgStatus == I2C_MSGSTAT_SEND_WITHSTOP)
{
writeDataWorked = I2CA_WriteData(&I2cMsgOut1);
//
// If communication is correctly initiated, set msg status to busy
// and update CurrentMsgPtr for the interrupt service routine.
// Otherwise, do nothing and try again next loop. Once message is
// initiated, the I2C interrupts will handle the rest. Search for
// ICINTR1A_ISR in the i2c_eeprom_isr.c file.
//
if (writeDataWorked == I2C_SUCCESS)
{
CurrentMsgPtr = &I2cMsgOut1;
I2cMsgOut1.MsgStatus = I2C_MSGSTAT_WRITE_BUSY;
}
}
//
// Read data from EEPROM section
//
//
// Check outgoing message status. Bypass read section if status is
// not inactive.
//
if (I2cMsgOut1.MsgStatus == I2C_MSGSTAT_INACTIVE)
{
//
// Check incoming message status.
//
if(I2cMsgIn1.MsgStatus == I2C_MSGSTAT_SEND_NOSTOP)
{
//
// EEPROM address setup portion
//
while(I2CA_ReadData(&I2cMsgIn1) != I2C_SUCCESS)
{
//
// Maybe setup an attempt counter to break an infinite
// while loop. The EEPROM will send back a NACK while it is
// performing a write operation. Even though the write
// communique is complete at this point, the EEPROM could
// still be busy programming the data. Therefore, multiple
// attempts are necessary.
//
}
//
// Update current message pointer and message status
//
CurrentMsgPtr = &I2cMsgIn1;
I2cMsgIn1.MsgStatus = I2C_MSGSTAT_SEND_NOSTOP_BUSY;
}
//
// Once message has progressed past setting up the internal address
// of the EEPROM, send a restart to read the data bytes from the
// EEPROM. Complete the communique with a stop bit. MsgStatus is
// updated in the interrupt service routine.
//
else if(I2cMsgIn1.MsgStatus == I2C_MSGSTAT_RESTART)
{
//
// Read data portion
//
while(I2CA_ReadData(&I2cMsgIn1) != I2C_SUCCESS)
{
//
// Maybe setup an attempt counter to break an infinite
// while loop.
//
}
//
// Update current message pointer and message status
//
CurrentMsgPtr = &I2cMsgIn1;
I2cMsgIn1.MsgStatus = I2C_MSGSTAT_READ_BUSY;
}
}
// Waiting for enable system flag to be set
while(!(gMotorVars.Flag_enableSys));
// Enable the Library internal PI. Iq is referenced by the speed PI now
CTRL_setFlag_enableSpeedCtrl(ctrlHandle, true);
// loop while the enable system flag is true
while(gMotorVars.Flag_enableSys)
{
CTRL_Obj *obj = (CTRL_Obj *)ctrlHandle;
// increment counters
gCounter_updateGlobals++;
// enable/disable the use of motor parameters being loaded from user.h
CTRL_setFlag_enableUserMotorParams(ctrlHandle,gMotorVars.Flag_enableUserParams);
// enable/disable Rs recalibration during motor startup
EST_setFlag_enableRsRecalc(obj->estHandle,gMotorVars.Flag_enableRsRecalc);
// enable/disable automatic calculation of bias values
CTRL_setFlag_enableOffset(ctrlHandle,gMotorVars.Flag_enableOffsetcalc);
if(CTRL_isError(ctrlHandle))
{
// set the enable controller flag to false
CTRL_setFlag_enableCtrl(ctrlHandle,false);
// set the enable system flag to false
gMotorVars.Flag_enableSys = false;
// disable the PWM
HAL_disablePwm(halHandle);
}
else
{
// update the controller state
bool flag_ctrlStateChanged = CTRL_updateState(ctrlHandle);
// enable or disable the control
CTRL_setFlag_enableCtrl(ctrlHandle, gMotorVars.Flag_Run_Identify);
if(flag_ctrlStateChanged)
{
CTRL_State_e ctrlState = CTRL_getState(ctrlHandle);
if(ctrlState == CTRL_State_OffLine)
{
// enable the PWM
HAL_enablePwm(halHandle);
}
else if(ctrlState == CTRL_State_OnLine)
{
if(gMotorVars.Flag_enableOffsetcalc == true)
{
// update the ADC bias values
HAL_updateAdcBias(halHandle);
}
else
{
// set the current bias
HAL_setBias(halHandle,HAL_SensorType_Current,0,_IQ(I_A_offset));
HAL_setBias(halHandle,HAL_SensorType_Current,1,_IQ(I_B_offset));
HAL_setBias(halHandle,HAL_SensorType_Current,2,_IQ(I_C_offset));
// set the voltage bias
HAL_setBias(halHandle,HAL_SensorType_Voltage,0,_IQ(V_A_offset));
HAL_setBias(halHandle,HAL_SensorType_Voltage,1,_IQ(V_B_offset));
HAL_setBias(halHandle,HAL_SensorType_Voltage,2,_IQ(V_C_offset));
}
// Return the bias value for currents
gMotorVars.I_bias.value[0] = HAL_getBias(halHandle,HAL_SensorType_Current,0);
gMotorVars.I_bias.value[1] = HAL_getBias(halHandle,HAL_SensorType_Current,1);
gMotorVars.I_bias.value[2] = HAL_getBias(halHandle,HAL_SensorType_Current,2);
// Return the bias value for voltages
gMotorVars.V_bias.value[0] = HAL_getBias(halHandle,HAL_SensorType_Voltage,0);
gMotorVars.V_bias.value[1] = HAL_getBias(halHandle,HAL_SensorType_Voltage,1);
gMotorVars.V_bias.value[2] = HAL_getBias(halHandle,HAL_SensorType_Voltage,2);
// enable the PWM
HAL_enablePwm(halHandle);
}
else if(ctrlState == CTRL_State_Idle)
{
// disable the PWM
HAL_disablePwm(halHandle);
gMotorVars.Flag_Run_Identify = false;
}
if((CTRL_getFlag_enableUserMotorParams(ctrlHandle) == true) &&
(ctrlState > CTRL_State_Idle) &&
(gMotorVars.CtrlVersion.minor == 6))
{
// call this function to fix 1p6
USER_softwareUpdate1p6(ctrlHandle);
}
}
}
if(EST_isMotorIdentified(obj->estHandle))
{
// set the current ramp
EST_setMaxCurrentSlope_pu(obj->estHandle,gMaxCurrentSlope);
gMotorVars.Flag_MotorIdentified = true;
// set the speed reference
CTRL_setSpd_ref_krpm(ctrlHandle,gMotorVars.SpeedRef_krpm);
// set the speed acceleration
CTRL_setMaxAccel_pu(ctrlHandle,_IQmpy(MAX_ACCEL_KRPMPS_SF,gMotorVars.MaxAccel_krpmps));
if(Flag_Latch_softwareUpdate)
{
Flag_Latch_softwareUpdate = false;
USER_calcPIgains(ctrlHandle);
// initialize the watch window kp and ki current values with pre-calculated values
gMotorVars.Kp_Idq = CTRL_getKp(ctrlHandle,CTRL_Type_PID_Id);
gMotorVars.Ki_Idq = CTRL_getKi(ctrlHandle,CTRL_Type_PID_Id);
// initialize the watch window kp and ki values with pre-calculated values
gMotorVars.Kp_spd = CTRL_getKp(ctrlHandle,CTRL_Type_PID_spd);
gMotorVars.Ki_spd = CTRL_getKi(ctrlHandle,CTRL_Type_PID_spd);
}
}
else
{
Flag_Latch_softwareUpdate = true;
// the estimator sets the maximum current slope during identification
gMaxCurrentSlope = EST_getMaxCurrentSlope_pu(obj->estHandle);
}
// when appropriate, update the global variables
if(gCounter_updateGlobals >= NUM_MAIN_TICKS_FOR_GLOBAL_VARIABLE_UPDATE)
{
// reset the counter
gCounter_updateGlobals = 0;
updateGlobalVariables_motor(ctrlHandle);
}
// update Kp and Ki gains
updateKpKiGains(ctrlHandle);
// enable/disable the forced angle
EST_setFlag_enableForceAngle(obj->estHandle,gMotorVars.Flag_enableForceAngle);
// enable or disable power warp
CTRL_setFlag_enablePowerWarp(ctrlHandle,gMotorVars.Flag_enablePowerWarp);
#ifdef DRV8301_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8301Vars);
HAL_readDrvData(halHandle,&gDrvSpi8301Vars);
#endif
#ifdef DRV8305_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8305Vars);
HAL_readDrvData(halHandle,&gDrvSpi8305Vars);
#endif
#ifdef DRV8323_SPI
HAL_writeDrvData(halHandle,&gDrvSpi8323Vars);
HAL_readDrvData(halHandle,&gDrvSpi8323Vars);
#endif
} // end of while(gFlag_enableSys) loop
// disable the PWM
HAL_disablePwm(halHandle);
// set the default controller parameters (Reset the control to re-identify the motor)
CTRL_setParams(ctrlHandle,&gUserParams);
gMotorVars.Flag_Run_Identify = false;
} // end of for(;;) loop
} // end of main() function
interrupt void mainISR(void)
{
// toggle status LED
if(++gLEDcnt >= (uint_least32_t)(USER_ISR_FREQ_Hz / LED_BLINK_FREQ_Hz))
{
HAL_toggleLed(halHandle,(GPIO_Number_e)HAL_Gpio_LED2);
gLEDcnt = 0;
}
// acknowledge the ADC interrupt
HAL_acqAdcInt(halHandle,ADC_IntNumber_1);
// convert the ADC data
HAL_readAdcData(halHandle,&gAdcData);
// run the controller
CTRL_run(ctrlHandle,halHandle,&gAdcData,&gPwmData);
// write the PWM compare values
HAL_writePwmData(halHandle,&gPwmData);
// setup the controller
CTRL_setup(ctrlHandle);
return;
} // end of mainISR() function
void updateGlobalVariables_motor(CTRL_Handle handle)
{
CTRL_Obj *obj = (CTRL_Obj *)handle;
// get the speed estimate
gMotorVars.Speed_krpm = EST_getSpeed_krpm(obj->estHandle);
// get the real time speed reference coming out of the speed trajectory generator
gMotorVars.SpeedTraj_krpm = _IQmpy(CTRL_getSpd_int_ref_pu(handle),EST_get_pu_to_krpm_sf(obj->estHandle));
// get the torque estimate
gMotorVars.Torque_Nm = USER_computeTorque_Nm(handle, gTorque_Flux_Iq_pu_to_Nm_sf, gTorque_Ls_Id_Iq_pu_to_Nm_sf);
// get the magnetizing current
gMotorVars.MagnCurr_A = EST_getIdRated(obj->estHandle);
// get the rotor resistance
gMotorVars.Rr_Ohm = EST_getRr_Ohm(obj->estHandle);
// get the stator resistance
gMotorVars.Rs_Ohm = EST_getRs_Ohm(obj->estHandle);
// get the stator inductance in the direct coordinate direction
gMotorVars.Lsd_H = EST_getLs_d_H(obj->estHandle);
// get the stator inductance in the quadrature coordinate direction
gMotorVars.Lsq_H = EST_getLs_q_H(obj->estHandle);
// get the flux in V/Hz in floating point
gMotorVars.Flux_VpHz = EST_getFlux_VpHz(obj->estHandle);
// get the flux in Wb in fixed point
gMotorVars.Flux_Wb = USER_computeFlux(handle, gFlux_pu_to_Wb_sf);
// get the controller state
gMotorVars.CtrlState = CTRL_getState(handle);
// get the estimator state
gMotorVars.EstState = EST_getState(obj->estHandle);
// Get the DC buss voltage
gMotorVars.VdcBus_kV = _IQmpy(gAdcData.dcBus,_IQ(USER_IQ_FULL_SCALE_VOLTAGE_V/1000.0));
return;
} // end of updateGlobalVariables_motor() function
void updateKpKiGains(CTRL_Handle handle)
{
if((gMotorVars.CtrlState == CTRL_State_OnLine) && (gMotorVars.Flag_MotorIdentified == true) && (Flag_Latch_softwareUpdate == false))
{
// set the kp and ki speed values from the watch window
CTRL_setKp(handle,CTRL_Type_PID_spd,gMotorVars.Kp_spd);
CTRL_setKi(handle,CTRL_Type_PID_spd,gMotorVars.Ki_spd);
// set the kp and ki current values for Id and Iq from the watch window
CTRL_setKp(handle,CTRL_Type_PID_Id,gMotorVars.Kp_Idq);
CTRL_setKi(handle,CTRL_Type_PID_Id,gMotorVars.Ki_Idq);
CTRL_setKp(handle,CTRL_Type_PID_Iq,gMotorVars.Kp_Idq);
CTRL_setKi(handle,CTRL_Type_PID_Iq,gMotorVars.Ki_Idq);
}
return;
} // end of updateKpKiGains() function
//
// I2CA_Init -
//
void
I2CA_Init(void)
{
//
// Initialize I2C
//
I2caRegs.I2CSAR = 0x0050; // Slave address - EEPROM control code
//
// I2CCLK = SYSCLK/(I2CPSC+1)
//
#if (CPU_FRQ_40MHZ||CPU_FRQ_50MHZ)
I2caRegs.I2CPSC.all = 4; // Prescaler - need 7-12 Mhz on module clk
#endif
#if (CPU_FRQ_60MHZ)
I2caRegs.I2CPSC.all = 6; // Prescaler - need 7-12 Mhz on module clk
#endif
I2caRegs.I2CCLKL = 10; // NOTE: must be non zero
I2caRegs.I2CCLKH = 5; // NOTE: must be non zero
I2caRegs.I2CIER.all = 0x24; // Enable SCD & ARDY interrupts
//
// Take I2C out of reset. Stop I2C when suspended
//
I2caRegs.I2CMDR.all = 0x0020;
I2caRegs.I2CFFTX.all = 0x6000; // Enable FIFO mode and TXFIFO
I2caRegs.I2CFFRX.all = 0x2040; // Enable RXFIFO, clear RXFFINT,
return;
}
//
// I2CA_WriteData -
//
uint16_t I2CA_WriteData(struct I2CMSG *msg)
{
uint16_t i;
//
// Wait until the STP bit is cleared from any previous master communication
// Clearing of this bit by the module is delayed until after the SCD bit is
// set. If this bit is not checked prior to initiating a new message, the
// I2C could get confused.
//
if (I2caRegs.I2CMDR.bit.STP == 1)
{
return I2C_STP_NOT_READY_ERROR;
}
//
// Setup slave address
//
I2caRegs.I2CSAR = msg->SlaveAddress;
//
// Check if bus busy
//
if (I2caRegs.I2CSTR.bit.BB == 1)
{
return I2C_BUS_BUSY_ERROR;
}
//
// Setup number of bytes to send MsgBuffer + Address
//
I2caRegs.I2CCNT = msg->NumOfBytes+2;
//
// Setup data to send
//
I2caRegs.I2CDXR = msg->MemoryHighAddr;
I2caRegs.I2CDXR = msg->MemoryLowAddr;
for (i=0; i<msg->NumOfBytes; i++)
{
I2caRegs.I2CDXR = *(msg->MsgBuffer+i);
}
//
// Send start as master transmitter
//
I2caRegs.I2CMDR.all = 0x6E20;
return I2C_SUCCESS;
}
//
// I2CA_ReadData -
//
uint16_t
I2CA_ReadData(struct I2CMSG *msg)
{
//
// Wait until the STP bit is cleared from any previous master communication
// Clearing of this bit by the module is delayed until after the SCD bit is
// set. If this bit is not checked prior to initiating a new message, the
// I2C could get confused.
//
if (I2caRegs.I2CMDR.bit.STP == 1)
{
return I2C_STP_NOT_READY_ERROR;
}
I2caRegs.I2CSAR = msg->SlaveAddress;
if(msg->MsgStatus == I2C_MSGSTAT_SEND_NOSTOP)
{
//
// Check if bus busy
//
if (I2caRegs.I2CSTR.bit.BB == 1)
{
return I2C_BUS_BUSY_ERROR;
}
I2caRegs.I2CCNT = 2;
I2caRegs.I2CDXR = msg->MemoryHighAddr;
I2caRegs.I2CDXR = msg->MemoryLowAddr;
I2caRegs.I2CMDR.all = 0x2620; // Send data to setup EEPROM address
}
else if(msg->MsgStatus == I2C_MSGSTAT_RESTART)
{
//
// Setup how many bytes to expect
//
I2caRegs.I2CCNT = msg->NumOfBytes;
//
// Send restart as master receiver
//
I2caRegs.I2CMDR.all = 0x2C20;
}
return I2C_SUCCESS;
}
//
// i2c_int1a_isr - I2C-A
//
__interrupt void
i2c_int1a_isr(void)
{
uint16_t IntSource, i;
//
// Read interrupt source
//
IntSource = I2caRegs.I2CISRC.all;
//
// Interrupt source = stop condition detected
//
if(IntSource == I2C_SCD_ISRC)
{
//
// If completed message was writing data, reset msg to inactive state
//
if (CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_WRITE_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_INACTIVE;
}
else
{
//
// If a message receives a NACK during the address setup portion
// of the EEPROM read, the code further below included in the
// register access ready interrupt source code will generate a stop
// condition. After the stop condition is received (here), set the
// message status to try again. User may want to limit the number
// of retries before generating an error.
//
if(CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_SEND_NOSTOP_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_SEND_NOSTOP;
}
//
// If completed message was reading EEPROM data, reset msg to
// inactive state and read data from FIFO.
//
else if (CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_READ_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_INACTIVE;
for(i=0; i < I2C_NUMBYTES; i++)
{
CurrentMsgPtr->MsgBuffer[i] = I2caRegs.I2CDRR;
}
//
// Check received data
//
for(i=0; i < I2C_NUMBYTES; i++)
{
if(I2cMsgIn1.MsgBuffer[i] == I2cMsgOut1.MsgBuffer[i])
{
PassCount++;
}
else
{
FailCount++;
}
}
if(PassCount == I2C_NUMBYTES)
{
pass();
}
else
{
fail();
}
}
}
}
//
// Interrupt source = Register Access Ready
// This interrupt is used to determine when the EEPROM address setup
// portion of the read data communication is complete. Since no stop bit is
// commanded, this flag tells us when the message has been sent instead of
// the SCD flag. If a NACK is received, clear the NACK bit and command a
// stop. Otherwise, move on to the read data portion of the communication.
//
else if(IntSource == I2C_ARDY_ISRC)
{
if(I2caRegs.I2CSTR.bit.NACK == 1)
{
I2caRegs.I2CMDR.bit.STP = 1;
I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;
}
else if(CurrentMsgPtr->MsgStatus == I2C_MSGSTAT_SEND_NOSTOP_BUSY)
{
CurrentMsgPtr->MsgStatus = I2C_MSGSTAT_RESTART;
}
}
else
{
//
// Generate some error due to invalid interrupt source
//
__asm(" ESTOP0");
}
//
// Enable future I2C (PIE Group 8) interrupts
//
PieCtrlRegs.PIEACK.all = PIEACK_GROUP8;
}
//
// pass -
//
void
pass()
{
__asm(" ESTOP0");
for(;;);
}
//
// fail -
//
void
fail()
{
__asm(" ESTOP0");
for(;;);
}
//@} //defgroup
// end of file