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.

TMS320F28379S: C2000 microcontrollers forum

Part Number: TMS320F28379S


//###########################################################################
//
// FILE:    2802xI2C_non_FIFO_main.c
//
// TITLE:   2802x_I2C_non_FIFO_example
//
// ASSUMPTIONS:
//
//    Add description here... TODO
//
//    $Boot_Table
//    While an emulator is connected to your device, the TRSTn pin = 1,
//    which sets the device into EMU_BOOT boot mode. In this mode, the
//    peripheral boot modes are as follows:
//
//      Boot Mode:   EMU_KEY        EMU_BMODE
//                   (0xD00)         (0xD01)
//      ---------------------------------------
//      Wait         !=0x55AA        X
//      I/O          0x55AA          0x0000
//      SCI          0x55AA          0x0001
//      Wait         0x55AA          0x0002
//      Get_Mode     0x55AA          0x0003
//      SPI          0x55AA          0x0004
//      I2C          0x55AA          0x0005
//      OTP          0x55AA          0x0006
//      Wait         0x55AA          0x0007
//      Wait         0x55AA          0x0008
//      SARAM        0x55AA          0x000A   <-- "Boot to SARAM"
//      Flash        0x55AA          0x000B
//      Wait         0x55AA          Other
//
//   Write EMU_KEY to 0xD00 and EMU_BMODE to 0xD01 via the debugger
//   according to the Boot Mode Table above. Build/Load project,
//   Reset the device, and Run example
//
//   $End_Boot_Table
//
// DESCRIPTION:
//
//    This program will write 1-14 words to EEPROM and read them back.
//    The data written and the EEPROM address written to are contained
//    in the message structure, I2cMsgOut1. The data read back will be
//    contained in the message structure I2cMsgIn1.
//
//    This program will work with the on-board I2C EEPROM supplied on
//    the F2802x eZdsp.
//
//
//###########################################################################
// $TI Release: F2802x Support Library v3.02.00.00 $
// $Release Date: Tue Jun 26 03:12:17 CDT 2018 $
// $Copyright:
// Copyright (C) 2009-2018 Texas Instruments Incorporated - http://www.ti.com/
//
// Redistribution and use in source and binary forms, with or without 
// modification, are permitted provided that the following conditions 
// are met:
// 
//   Redistributions of source code must retain the above copyright 
//   notice, this list of conditions and the following disclaimer.
// 
//   Redistributions in binary form must reproduce the above copyright
//   notice, this list of conditions and the following disclaimer in the 
//   documentation and/or other materials provided with the   
//   distribution.
// 
//   Neither the name of Texas Instruments Incorporated nor the names of
//   its contributors may be used to endorse or promote products derived
//   from this software without specific prior written permission.
// 
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
// $
//###########################################################################

//
// Included Files
//
#include "DSP28x_Project.h"     // Device Headerfile and Examples Include File

//
// I2C Function Prototypes
//
void   I2CA_Init(void);

uint16_t I2CA_WriteToReg(uint16_t slave_addr, uint16_t reg,
                         uint16_t data[], uint16_t data_size);

uint16_t I2CA_WriteToManyRegs(uint16_t slave_addr, uint16_t reg[],
               uint16_t reg_size, uint16_t data[], uint16_t data_size);

uint16_t I2CA_ReadFromReg(uint16_t slave_addr, uint16_t reg,
                 uint16_t data[], uint16_t data_size);

uint16_t I2CA_ReadFromManyRegs(uint16_t slave_addr, uint16_t reg[],
                 uint16_t reg_size, uint16_t data[], uint16_t data_size);

void InitI2CAGpio();

//
// Defines
//
#define I2C_SLAVE_ADDR        0x50
#define NACK_CHECK            1

//
// Globals
//


//
// Main
//
void main(void)
{
    uint16_t Status, 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

    //
    // Initialize System Control:
    // PLL, WatchDog, enable Peripheral Clocks
    // This example function is found in the f2802x_SysCtrl.c file.
    //
    InitSysCtrl();
    
    //
    // Setup only the GP I/O only for I2C functionality
    //
    InitI2CAGpio();

    //
    // 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();

    //
    // Initialize all the Device Peripherals
    //
    I2CA_Init();    // I2C-A only

    //
    // Define variables/buffers used for I2C comms
    //
    uint16_t reg[2]; // Register bytes buffer
    uint16_t tx_data_buff[64]; // Data bytes buffer
    uint16_t rx_data_buff[64]; // Data bytes buffer


    // Define register bytes
    reg[0] = 0x00;
    reg[1] = 0x00;

    // Define data bytes
    for(i = 0; i <= sizeof(tx_data_buff); i++)
    {
        tx_data_buff[i] = i;
        rx_data_buff[i] = 0;
    }

    // Transfer register and data bytes
    Status = I2CA_WriteToManyRegs(I2C_SLAVE_ADDR, reg, sizeof(reg),
                                  tx_data_buff, sizeof(tx_data_buff));

    if(Status == I2C_SUCCESS)
    {

        Status = I2CA_ReadFromManyRegs(I2C_SLAVE_ADDR, reg, sizeof(reg),
                                       rx_data_buff, sizeof(rx_data_buff));
        while(Status != I2C_SUCCESS)
        {
            Status = I2CA_ReadFromManyRegs(I2C_SLAVE_ADDR, reg, sizeof(reg),
                                           rx_data_buff, sizeof(rx_data_buff));
        }
    }

    __asm("   ESTOP0");

}

//
// I2CA_Init -
//
void
I2CA_Init(void)
{
    //
    // 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
    // Set I2CCLKL/I2CCLKH for 100KHz SCL clock
    I2caRegs.I2CCLKL = 38;           // NOTE: must be non zero
    I2caRegs.I2CCLKH = 38;            // NOTE: must be non zero
    I2caRegs.I2CIER.all = 0x0;      // Disable interrupts

    //
    // Take I2C out of reset. Stop I2C when suspended
    //
    I2caRegs.I2CMDR.all = 0x0020;

    return;
}

//
// InitI2CGpio - This function initializes GPIO pins to function as I2C pins
//
// Each GPIO pin can be configured as a GPIO pin or up to 3 different
// peripheral functional pins. By default all pins come up as GPIO
// inputs after reset.
//
// Caution:
// Only one GPIO pin should be enabled for SDAA operation.
// Only one GPIO pin shoudl be enabled for SCLA operation.
// Comment out other unwanted lines.
//
void
InitI2CAGpio()
{
    EALLOW;

    //
    // Enable internal pull-up for the selected pins
    // Pull-ups can be enabled or disabled disabled by the user.
    // This will enable the pullups for the specified pins.
    // Comment out other unwanted lines.
    //
    GpioCtrlRegs.GPBPUD.bit.GPIO32 = 0;   // Enable pull-up for GPIO32 (SDAA)
    GpioCtrlRegs.GPBPUD.bit.GPIO33 = 0;   // Enable pull-up for GPIO33 (SCLA)

    //
    // Set qualification for selected pins to asynch only
    // This will select asynch (no qualification) for the selected pins.
    // Comment out other unwanted lines.
    //
    GpioCtrlRegs.GPBQSEL1.bit.GPIO32 = 3;  // Asynch input GPIO32 (SDAA)
    GpioCtrlRegs.GPBQSEL1.bit.GPIO33 = 3;  // Asynch input GPIO33 (SCLA)

    //
    // Configure I2C pins using GPIO regs
    // This specifies which of the possible GPIO pins will be I2C
    // functional pins. Comment out other unwanted lines.
    //
    GpioCtrlRegs.GPBMUX1.bit.GPIO32 = 1;   // Configure GPIO32 for SDAA
    GpioCtrlRegs.GPBMUX1.bit.GPIO33 = 1;   // Configure GPIO33 for SCLA

    EDIS;
}

//
// I2CA_WriteToReg - This function writes data bytes to a slave
//                   device's register.
//
// INPUTS:
//      - slave_addr ==> Address of slave device being written to
//      - reg[] ==> Slave device register being written to
//      - data[] ==> data buffer of bytes to be written to the slave
//                      device register
//      - data_size ==> # of data bytes being written, size of data buffer
//
uint16_t I2CA_WriteToReg(uint16_t slave_addr, uint16_t reg,
                         uint16_t data[], uint16_t data_size)
{
    uint16_t i, Status;

    Status = I2C_SUCCESS;

    //
    // 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 = slave_addr;

    //
    // Check if bus busy
    //
    if (I2caRegs.I2CSTR.bit.BB == 1)
    {
        return I2C_BUS_BUSY_ERROR;
    }

    //
    // Set up as master transmitter
    // FREE + MST + TRX + IRS
    //
    I2caRegs.I2CMDR.all = 0x4620;

    //
    // Setup number of bytes to send
    // == register byte + (# of data[] buffer bytes)
    //
    I2caRegs.I2CCNT = 1 + data_size;

    I2caRegs.I2CMDR.bit.STT = 0x1; // Send START condition
    I2caRegs.I2CMDR.bit.STP = 0x1; // STOP condition will be
                                   // generated when I2CCNT is zero

    //
    // I2C module will send the following:
    // register byte ==> data bytes ==> STOP condition
    //
    while(!I2caRegs.I2CSTR.bit.XRDY){} // Make sure data
                                       // is ready to be written
    I2caRegs.I2CDXR = reg;

    #if NACK_CHECK // check if NACK was received
        if(I2caRegs.I2CSTR.bit.NACK == 1)
        {
            I2caRegs.I2CMDR.bit.STP = 1;
            I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

            Status = I2C_ERROR;
            return Status;
        }
    #endif

    // Transmit Data Bytes followed by STOP condition
    for (i=0; i< data_size; i++)
    {
        while(!I2caRegs.I2CSTR.bit.XRDY){} // Make sure data
                                           // is ready to be written
        I2caRegs.I2CDXR = data[i];

        #if NACK_CHECK // check if NACK was received
            if(I2caRegs.I2CSTR.bit.NACK == 1)
            {
                I2caRegs.I2CMDR.bit.STP = 1;
                I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

                Status = I2C_ERROR;
                break;
            }
        #endif
    }


    // Data successfully written
    return Status;
}

//
// I2CA_WriteToReg - This function writes data bytes to a slave
//                   device's register.
//
// INPUTS:
//      - slave_addr ==> Address of slave device being written to
//      - reg[] ==> Slave device registers being written to
//      - reg_size ==> # of register bytes being written, size of
//                          reg_size buffer
//      - data[] ==> data buffer of bytes to be written to the slave
//                      device register
//      - data_size ==> # of data bytes being written, size of data buffer
//
uint16_t I2CA_WriteToManyRegs(uint16_t slave_addr, uint16_t reg[],
               uint16_t reg_size, uint16_t data[], uint16_t data_size)
{
    uint16_t i, Status;

    Status = I2C_SUCCESS;

    //
    // 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 = slave_addr;

    //
    // Check if bus busy
    //
    if (I2caRegs.I2CSTR.bit.BB == 1)
    {
        return I2C_BUS_BUSY_ERROR;
    }

    //
    // Set up as master transmitter
    // FREE + MST + TRX + IRS
    //
    I2caRegs.I2CMDR.all = 0x4620;

    //
    // Setup number of bytes to send
    // == (# of register bytes) + (# of data[] buffer bytes)
    //
    I2caRegs.I2CCNT = reg_size + data_size;

    I2caRegs.I2CMDR.bit.STT = 0x1; // Send START condition
    I2caRegs.I2CMDR.bit.STP = 0x1; // STOP condition will be
                                   // generated when I2CCNT is zero

    //
    // I2C module will send the following:
    // register bytes ==> data bytes ==> STOP condition
    //

    // Transmit Register Bytes
    for (i=0; i< reg_size; i++)
    {
        while(!I2caRegs.I2CSTR.bit.XRDY){} // Make sure data
                                           // is ready to be written
        I2caRegs.I2CDXR = reg[i];

        #if NACK_CHECK // check if NACK was received
            if(I2caRegs.I2CSTR.bit.NACK == 1)
            {
                I2caRegs.I2CMDR.bit.STP = 1;
                I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

                Status = I2C_ERROR;
                return Status;
            }
        #endif
    }

    // Transmit Data Bytes followed by STOP condition
    for (i=0; i< data_size; i++)
    {
        while(!I2caRegs.I2CSTR.bit.XRDY){} // Make sure data
                                           // is ready to be written
        I2caRegs.I2CDXR = data[i];

        #if NACK_CHECK // check if NACK was received
            if(I2caRegs.I2CSTR.bit.NACK == 1)
            {
                I2caRegs.I2CMDR.bit.STP = 1;
                I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

                Status = I2C_ERROR;
                return Status;
            }
        #endif
    }


    // Data successfully written
    return Status;
}

//
// I2CA_ReadFromReg - This function reads data bytes from a slave
//                   device's register.
//
// INPUTS:
//      - slave_addr ==> Address of slave device being read from
//      - reg ==> Slave device register being read from
//      - data[] ==> data buffer to store the bytes read from the
//                      slave device register
//      - data_size ==> # of data bytes being received, size of data buffer
//
uint16_t I2CA_ReadFromReg(uint16_t slave_addr, uint16_t reg,
                  uint16_t data[], uint16_t data_size)
{
    uint16_t i, Status;

    Status = I2C_SUCCESS;

    //
    // 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 = slave_addr;

    //
    // Check if bus busy
    //
    if (I2caRegs.I2CSTR.bit.BB == 1)
    {
        return I2C_BUS_BUSY_ERROR;
    }

    //
    // 1. Transmit the slave address followed by the register
    //      bytes being read from
    //

    //
    // Setup number of bytes to send
    // == # of register bytes
    //
    I2caRegs.I2CCNT = 1;

    //
    // Set up as master transmitter
    // FREE + MST + TRX + IRS
    //
    I2caRegs.I2CMDR.all = 0x4620;

    I2caRegs.I2CMDR.bit.STT = 0x1; // Send START condition

    while(!I2caRegs.I2CSTR.bit.ARDY) // Wait for slave address to be sent
    {
        if(I2caRegs.I2CSTR.bit.XSMT == 0)
        {
            break;
        }
    }

    #if NACK_CHECK // check if NACK was received
        if(I2caRegs.I2CSTR.bit.NACK == 1)
        {
            I2caRegs.I2CMDR.bit.STP = 1;
            I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

            Status = I2C_ERROR;
            return Status;
        }
    #endif



    // Transmit Register Byte
    while(!I2caRegs.I2CSTR.bit.XRDY){} // Make sure data
                                       // is ready to be written
    I2caRegs.I2CDXR = reg;

    #if NACK_CHECK // check if NACK was received
        if(I2caRegs.I2CSTR.bit.NACK == 1)
        {
            I2caRegs.I2CMDR.bit.STP = 1;
            I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

            Status = I2C_ERROR;
            return Status;
        }
    #endif


    // Wait for previous communication to complete
    while(!I2caRegs.I2CSTR.bit.ARDY){}

    //
    // 2. Receive data bytes from slave device
    //

    //
    // Set up as master receiver
    // FREE + MST + IRS ==> (Master Receiver)
    //
    I2caRegs.I2CMDR.all = 0x4420;

    //
    // Setup number of bytes to receive
    // == # of data bytes
    //
    I2caRegs.I2CCNT = data_size;

    I2caRegs.I2CMDR.bit.STT = 0x1; // Send repeated START condition & Slave Addr
    I2caRegs.I2CMDR.bit.STP = 0x1; // set STOP condition to be
                                   // generated when I2CCNT is zero

    #if NACK_CHECK // check if NACK was received
        if(I2caRegs.I2CSTR.bit.NACK == 1)
        {
            I2caRegs.I2CMDR.bit.STP = 1;
            I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

            Status = I2C_ERROR;
            return Status;
        }
    #endif

    for (i=0; i< data_size; i++)
    {
        while(!I2caRegs.I2CSTR.bit.RRDY){} // Make sure data
                                           // is ready to be received

        data[i] = I2caRegs.I2CDRR; // Buffer the received byte

    }

    // Data successfully read
    return Status;
}

//
// I2CA_ReadFromManyRegs - This function reads data bytes from a slave
//                  device's registers. For transmitting more than one
//                  register during the initial writes
//
// INPUTS:
//      - slave_addr ==> Address of slave device being read from
//      - reg[] ==> Slave device registers being read from
//      - reg_size ==> # of register bytes being written, size of
//                          reg_size buffer
//      - data[] ==> data buffer to store the bytes read from the
//                      slave device register
//      - data_size ==> # of data bytes being received, size of data buffer
//
uint16_t I2CA_ReadFromManyRegs(uint16_t slave_addr, uint16_t reg[],
                  uint16_t reg_size, uint16_t data[], uint16_t data_size)
{
    uint16_t i, Status;

    Status = I2C_SUCCESS;

    //
    // 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 = slave_addr;

    //
    // Check if bus busy
    //
    if (I2caRegs.I2CSTR.bit.BB == 1)
    {
        return I2C_BUS_BUSY_ERROR;
    }

    //
    // 1. Transmit the slave address followed by the register
    //      bytes being read from
    //

    //
    // Setup number of bytes to send
    // == # of register bytes
    //
    I2caRegs.I2CCNT = reg_size;

    //
    // Set up as master transmitter
    // FREE + MST + TRX + IRS
    //
    I2caRegs.I2CMDR.all = 0x4620;

    I2caRegs.I2CMDR.bit.STT = 0x1; // Send START condition

    while(!I2caRegs.I2CSTR.bit.ARDY) // Wait for slave address to be sent
    {
        if(I2caRegs.I2CSTR.bit.XSMT == 0)
        {
            break; // ACK received on slave address
        }
    }

    #if NACK_CHECK // check if NACK was received
        if(I2caRegs.I2CSTR.bit.NACK == 1)
        {
            I2caRegs.I2CMDR.bit.STP = 1;
            I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

            Status = I2C_ERROR;
            return Status;
        }
    #endif



    // Transmit Register Bytes
    for (i=0; i< reg_size; i++)
    {
        while(!I2caRegs.I2CSTR.bit.XRDY){} // Make sure data
                                           // is ready to be written
        I2caRegs.I2CDXR = reg[i];

        #if NACK_CHECK // check if NACK was received
            if(I2caRegs.I2CSTR.bit.NACK == 1)
            {
                I2caRegs.I2CMDR.bit.STP = 1;
                I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

                Status = I2C_ERROR;
                return Status;
            }
        #endif
    }

    // Wait for previous communication to complete
    while(!I2caRegs.I2CSTR.bit.ARDY){}

    //
    // 2. Receive data bytes from slave device
    //

    //
    // Set up as master receiver
    // FREE + MST + IRS ==> (Master Receiver)
    //
    I2caRegs.I2CMDR.all = 0x4420;

    //
    // Setup number of bytes to receive
    // == # of data bytes
    //
    I2caRegs.I2CCNT = data_size;

    I2caRegs.I2CMDR.bit.STT = 0x1; // Send repeated START condition & Slave Addr
    I2caRegs.I2CMDR.bit.STP = 0x1; // set STOP condition to be
                                   // generated when I2CCNT is zero

    #if NACK_CHECK // check if NACK was received
        if(I2caRegs.I2CSTR.bit.NACK == 1)
        {
            I2caRegs.I2CMDR.bit.STP = 1;
            I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;

            Status = I2C_ERROR;
            return Status;
        }
    #endif

    for (i=0; i< data_size; i++)
    {
        while(!I2caRegs.I2CSTR.bit.RRDY){} // Make sure data
                                           // is ready to be received

        data[i] = I2caRegs.I2CDRR; // Buffer the received byte

    }

    // Data successfully read
    return Status;
}

//
// End of File
//

Hi

I don't understand the right way to manage NACK events. I have used an old sample of code (attached) in order to read a value from an i2c peripheral that at the moment is not connected. Of course I have NACK and the sw recognize the event but when it try to send a stop condition the BB bit become 1 and the MST goto 0. Next calls to I2CA_ReadFromReg the return always Bus BUsy error no other actions can be done on the bus.

Best Regards 

  • Hi,

    To handle a NACK , you should follow the following steps

    • Set I2CMDR.STP which will send a "stop" bit and  release SCL. 
    • Write I2CSTR.NACK=1 to clear the flag (it's a write-1-to-clear bit)
    • Wait for I2CMDR.MST to self-clear before initiating any further I2C transactions

    This way you would know that previous I2C transaction is complete and then you can start new I2C transaction. 

    Are you seeing that he MST bit is not cleared after triggering a STOP condition?

    Best Regards

    Siddharth

  • Hi Siddharth

    Is just what I do on line 577 and 578 of the I2CA_ReadFromReg procedure and stepping  I see MST get cleared (is in this case stop condition interrupt generated?) but BB will be set and I can't start any new transaction.

    Regards

  • Hi, 

    Can you confirm if the STOP condition is generated? If the STOP condition is generated it should reset the BB bit? 

    What is the value of I2CSTR register before generating the STOP and after generating the STOP condition?

    Best Regards

    Siddharth

  • Hi Siddharth

    Before setting STP:

    After

    The SCL line switch to high when a set STP=1. The problem is that BB is not cleared.

    Bets Regards

  • Hi, 

    Do you see the SCD bit getting set?  If the STOP condition is generated it should reset the BB bit, then you can proceed with the next I2C transaction.

    Best Regards

    Siddharth 

  • Hi,

    I don't see SCD bit getting set as you can see in my previous reply. But have you try the code?

    Regards

    Luca

  • Hi

    But since if I see using the scope that before setting STP in CMDR the SCD line is high while SCL is low and after setting STP also the the SCL become high this can't be a stop condition.

    Regards  

  • Hi, 

    From the snapshot that you shared, I see that the NACK bit is still 1 . Can you ensure that it is cleared before you set STP bit?

    Best Regards

    Siddharth

  • Hi Siddharth

    May the external signals (SCL, SDA) polarizzation and loading affect the behaviour you describe? Because I have a board with 28377D that work as epected and a board with 28379S that doesn't work properly.

    Best Regards

  • Hi,

    If it works fine on 28377D board and doesn't work on 28379S board, then it looks like it not an issue with I2C module. It maybe something to do with the board that is causing this behavior.

    Best Regards

    Siddharth

  • Hi Siddharth

    First problem was caused by hardware that will maintain the bus not free... now I can communicate with slave but sometime I have strange behaviour and i2c go into interrupt procedure but reading the I2CISRC I get I2C_NO_ISRC!

    Attached you will find the relevant code please have a look to it...

    /* =============================================================================
        PROJECT NAME:
        ITEM TYPE:
        ITEM NAME:
        ITEM REFERENCE:
        CURRENT VERSION:
        DATE:
        ITEM DESCRIPTION:
        DOC REFERENCES:
        AUTHOR(S):
        COPYRIGHT:
        REVISION HISTORY:
    ============================================================================= */
    #define I2CB_GLOBALS
    #include "includes.h"
    
    /* ============================================================================
        FUNCTION NAME:
        PURPOSE:
        DESCRIPTION:
        DOMAIN:
        ACCURACY:
        NOTES:
     ============================================================================ */
    void SetUpI2CB(void)
    {
    
        GPIO_SetupPinMux(SCLB_GPIO, GPIO_MUX_CPU1, SCLB_PHER);
        GPIO_SetupPinOptions(SCLB_GPIO, GPIO_INPUT, GPIO_ASYNC | GPIO_PULLUP);
    
        GPIO_SetupPinMux(SDAB_GPIO, GPIO_MUX_CPU1, SDAB_PHER);
        GPIO_SetupPinOptions(SDAB_GPIO, GPIO_INPUT, GPIO_ASYNC | GPIO_PULLUP);
    
        //  Reset the module
        I2cbRegs.I2CMDR.all = 0;
        //  200MHz/(19+1) = 10MHz
        I2cbRegs.I2CPSC.bit.IPSC = 19;
        //  Minimum low time for slave is 1.3us (program 1.5us)
        I2cbRegs.I2CCLKL = 15;
        //  Minimum high time for slave is 0.6us (program 1us)
        I2cbRegs.I2CCLKH = 10;
        //  Module stops in breakpoint
        I2cbRegs.I2CMDR.bit.FREE = 1;
        //  Module operate as master
        I2cbRegs.I2CMDR.bit.MST = 1;
    
        //  Enables interrupts
        I2cbRegs.I2CIER.bit.ARDY = 1;
        I2cbRegs.I2CIER.bit.NACK = 1;
        I2cbRegs.I2CIER.bit.RRDY = 1;
        I2cbRegs.I2CIER.bit.SCD = 1;
        I2cbRegs.I2CIER.bit.XRDY = 1;
        //  Remove module from reset condition
    //    I2cbRegs.I2CMDR.bit.IRS = 1;
    }
    
    /* ============================================================================
        FUNCTION NAME:
        PURPOSE:
        DESCRIPTION:
        DOMAIN:
        ACCURACY:
        NOTES:
     ============================================================================ */
    void i2cb_start_transfer(int16_t sadd, int16_t n_wr, int16_t n_rd, int16_t op)
    {
    union I2CMDR_REG cmdr;
    
        i2cb.stop = false;
        i2cb.nack = false;
        i2cb.done = false;
        i2cb.sar = sadd;
        i2cb.n_writes = n_wr;
        i2cb.n_reads = n_rd;
    
        DELAY_US(10);
    
        cmdr.all = 0;
        cmdr.bit.IRS = 1;
        cmdr.bit.MST = 1;
        cmdr.bit.FREE = 1;
        switch( op )
        {
        case I2C_WRITE:
            i2cb.state = I2C_WRITING;
            i2cb.trx_ptr = 0;
            I2cbRegs.I2CSAR.bit.SAR = sadd;
            I2cbRegs.I2CCNT = n_wr;
            cmdr.bit.TRX = 1;
            cmdr.bit.STP = 1;
            cmdr.bit.STT = 1;
            break;
    
        case I2C_WRITE_READ:
            i2cb.state = I2C_WRITING;
            i2cb.trx_ptr = 0;
            I2cbRegs.I2CSAR.bit.SAR = sadd;
            I2cbRegs.I2CCNT = n_wr;
            cmdr.bit.TRX = 1;
            cmdr.bit.STP = 0;
            cmdr.bit.STT = 1;
            break;
    
        case I2C_READ:
            i2cb.state = I2C_READING;
            i2cb.trx_ptr = 0;
            I2cbRegs.I2CSAR.bit.SAR = sadd;
            I2cbRegs.I2CCNT = n_rd;
            cmdr.bit.TRX = 0;
            cmdr.bit.STP = 1;
            cmdr.bit.STT = 1;
            break;
    
        case I2C_POLLING:
            i2cb.state = EEPROM_POLLING;
            i2cb.trx_ptr = 0;
            I2cbRegs.I2CSAR.bit.SAR = sadd;
            I2cbRegs.I2CCNT = n_wr;
            cmdr.bit.TRX = 1;
            cmdr.bit.STP = 1;
            cmdr.bit.STT = 1;
            break;
    
        default:
            break;
        }
    
        I2cbRegs.I2CMDR.all = cmdr.all;
    }
    
    /* ============================================================================
        FUNCTION NAME:
        PURPOSE:
        DESCRIPTION:
        DOMAIN:
        ACCURACY:
        NOTES:
     ============================================================================ */
    void i2cb_tx_rx(uint16_t sadd, int16_t n_writes, int16_t n_reads)
    {
    //bool esito;
    
        if( n_reads == 0 )
        {
            //  Start write only transfer
            i2cb_start_transfer(sadd, n_writes, n_reads, I2C_WRITE);
        }
        else
        {
            if( n_writes == 0 )
            {
                //  start read only transfer
                i2cb_start_transfer(sadd, n_writes, n_reads, I2C_READ);
            }
            else
            {
                //  start a read after write transfer
                i2cb_start_transfer(sadd, n_writes, n_reads, I2C_WRITE_READ);
            }
        }
    
    /*  wait for end of operation
        while( !(i2cb_d.done || i2cb_d.nack) );
        if( i2cb_d.nack )
        {
            esito = false;
        }
        else
        {
            esito = true;
        }
        return ( esito );
    */
    }
    
    /* ============================================================================
        FUNCTION NAME:
        PURPOSE:
        DESCRIPTION:
        DOMAIN:
        ACCURACY:
        NOTES:
     ============================================================================ */
    bool i2cb_ready(void)
    {
    
        return( i2cb.done || i2cb.nack );
    }
    
    /* ============================================================================
        FUNCTION NAME:
        PURPOSE:
        DESCRIPTION:
        DOMAIN:
        ACCURACY:
        NOTES:
     ============================================================================ */
    interrupt void i2cb_isr(void)
    {
    // Set interrupt priority:
    volatile uint16_t TempPIEIER = PieCtrlRegs.PIEIER8.all;
    uint16_t tmp;
    
        IER |= M_INT8;
        IER &= MINT8;
        PieCtrlRegs.PIEIER8.all &= MG8_3;
        PieCtrlRegs.PIEACK.all = 0xFFFF;
        asm(" NOP");
        EINT;
    
        // Insert ISR Code here.......
        tmp = I2cbRegs.I2CISRC.all;
        switch ( tmp  )
        {
        case I2C_NO_ISRC:
            i2cb.nack = true;
            break;
    
        case I2C_ARB_ISRC:
            tmp = 0;
            break;
    
        case I2C_NACK_ISRC:
            I2cbRegs.I2CSTR.all = I2C_CLR_NACK_BIT;
            I2cbRegs.I2CMDR.bit.STP = 1;
            i2cb.nack = true;
            break;
    
        case I2C_ARDY_ISRC:
            I2cbRegs.I2CSTR.bit.ARDY = 1;
            if( (i2cb.state == EEPROM_POLLING) || i2cb.nack )
            {
                i2cb.done = true;
            }
            else
            {
                if( i2cb.state == I2C_WRITING )
                {
                    i2cb_start_transfer(i2cb.sar, 0, i2cb.n_reads, I2C_READ);
                }
            }
            break;
    
        case I2C_RX_ISRC:
            I2cbRegs.I2CSTR.bit.RRDY = 1;
            i2cb.rx_buf[i2cb.trx_ptr++] = I2cbRegs.I2CDRR.bit.DATA;
            break;
    
        case I2C_TX_ISRC:
            I2cbRegs.I2CSTR.bit.XRDY = 1;
            I2cbRegs.I2CDXR.bit.DATA = i2cb.tx_buf[i2cb.trx_ptr++];
            break;
    
        case I2C_SCD_ISRC:
            I2cbRegs.I2CSTR.bit.SCD = 1;
            i2cb.state = I2C_NOP;
            i2cb.stop = true;
            i2cb.done = true;
            break;
    
        case I2C_AAS_ISRC:
            tmp = 0;
            break;
    
        default:
            tmp = 0;
            break;
        }
    
        // Restore registers saved:
        DINT;
        PieCtrlRegs.PIEIER8.all = TempPIEIER;
    }
    
    

  • Hi, 

    That's strange. If you are getting an interrupt, it should capture the source of interrupt. 

    Can you try reading the I2CISR register immediately after entering the ISR routine?

    Best Regards

    Siddharth

  • Hi

    Is just what I do, I read I2CISRC after the standard sw nested interrupt procedure prologue

    Regards

  • Not sure what could be causing this , ideally, it should capture the source of interrupt.  

    Did you check the register value in CCS (using Register view) immediately after it enters the ISR?

    Best Regards

    Siddharth

  • Dear Siddharth

    I think I solve the problem but if is it true there will be an hw anomaly in the I2C interrupts. To avoid enter I2C interrupt and get zero in I2CISRC register I have to wait a bit before exit the procedure. It seems that after clearing the source of interrupt the I2C delay to much to clear interrupt request to PIE and this cause to generate another interrupt but with no sources.

    Best Regards  

  • Hi, 

    I observed that you are saving and restoring the PIEIER8 value in TempPIEIER varaible. Is there any particular reasong for doing so?

    Best Regards

    Siddharth

  • Hi Siddharth

    I have to manage software prioritized nested interrupts, you never do this?

    Regards 

  • Okay , got it. 

    After clearing the I2C interrupt, do you see the interrupt still pending in the PIE registers? How long do you have to wait before exiting the ISR?

    Best Regards

    Siddharth

  • Hi

    I have put 10us of delay but I have not try to decrease it may be also smaller is enougth...

    Regards

  • Ok, thanks. ShaII I go ahead and close this thread since you were able to resolve the issue?

    Best Regards

    Siddharth

  • Dear Siddharth

    No please don't close this ticket, is about two years that I fight with c2000 i2c and I never find a reliable solution. The is not the delay but I think is related on the action I take in the interrupt procedure. For example in case of nack I first read 0x2 in the i2csrc register but just after read the value the register is updated to 0x3,, and so on... Some action clear this register to zero when I think while hardware has registered the interrupt. There are some example that uses i2c normal interrupts? not FIFO interrupts. I have in mind to use interrupts to avoid to wait for i2c execution but I want to start a transfer and wait only for it to occur.

    Regards

  • Okay. 

    Do you have any reference/sample code that you can share which will help us in reproducing the issue?

    Best Regards

    Siddharth

  • Hi Siddharth

    Attached you will find the sample code. I have noted that going step by step the problem of have i2c interrupt with I2CSRC = 0 doesn't appen so I put the line

     while(!I2caRegs.I2CSTR.bit.SCD); in the I2C nack interrupt this seems solve the problem.

    Regards

    test_i2c.zip

    case I2C_NACK_ISRC:
        I2caRegs.I2CSTR.all = I2C_CLR_NACK_BIT;
        I2caRegs.I2CMDR.bit.STP = 1;
        i2ca.nack = true;
        while(!I2caRegs.I2CSTR.bit.SCD);
    break;
    
    
    
    

  • Hi, 

    Okay, will take a look at the code you provide and get back to you.

    Best Regards

    Siddharth

  • Hi Siddharth

    No news about?

    Regards

  • Hi, 

    Sorry , could not get to look into this since was busy with some other priority work.

    Will update you by next week .

    Best Regards

    Siddharth