TI中文支持网
TI专业的中文技术问题搜集分享网站

MSP432P401R: IIC重复通信无法发出数据

Part Number: MSP432P401R

我使用eUSCI_B0的IIC通信时,对同一个从机发送并接收数据。在第一次发送时,主机成功发送并接受到了数据。但是在第二次发送时,程序卡在了I2C_masterSendMultiByteStart上,无法进行之后的代码。使用Keil5调试发现,程序并没有办法在第二次发送时进入函数内部。

注:

  1. 程序使用了接收中断来判断是否接收到数据
  2. 在接收完程序后程序失能了接收中断

//中断相关代码

void EUSCIB0_IRQHandler(void)
{
	uint_fast16_t status;
	status = MAP_I2C_getEnabledInterruptStatus(EUSCI_B0_BASE);
	
	if(status & EUSCI_B_I2C_RECEIVE_INTERRUPT0)
	{
		if(rxIndex != (rxLength - 1))RxData[rxIndex++] = MAP_I2C_masterReceiveMultiByteNext(EUSCI_B0_BASE);
		else
		{
			RxData[rxIndex++] = MAP_I2C_masterReceiveMultiByteNext(EUSCI_B0_BASE);
			MAP_I2C_masterReceiveMultiByteFinish(EUSCI_B0_BASE);
			MAP_I2C_masterReceiveMultiByteStop(EUSCI_B0_BASE);
			isReceive = 1;
		}
	}
}

//main函数中相关代码

MAP_I2C_setMode(EUSCI_B0_BASE, EUSCI_B_I2C_TRANSMIT_MODE);
				MAP_GPIO_setAsOutputPin(GPIO_PORT_P1, GPIO_PIN0);
				MAP_GPIO_setOutputHighOnPin(GPIO_PORT_P1, GPIO_PIN0);
				MAP_GPIO_setOutputLowOnPin(ledPort, redPin | greenPin);
				isReceive = 0;
				for(rxIndex = 0; rxIndex < rxLength - 1; rxIndex++) RxData[rxIndex] = 0;
				rxIndex= 0;
				MAP_I2C_clearInterruptFlag(EUSCI_B0_BASE, EUSCI_B_I2C_TRANSMIT_INTERRUPT0 | EUSCI_B_I2C_NAK_INTERRUPT);
				MAP_I2C_masterSendMultiByteStart(EUSCI_B0_BASE, 0x01);
				MAP_I2C_masterSendMultiByteStop(EUSCI_B0_BASE);
				while (MAP_I2C_masterIsStopSent(EUSCI_B0_BASE));
				MAP_I2C_setMode(EUSCI_B0_BASE, EUSCI_B_I2C_RECEIVE_MODE);
				MAP_I2C_masterReceiveStart(EUSCI_B0_BASE);
				MAP_I2C_clearInterruptFlag(EUSCI_B0_BASE, EUSCI_B_I2C_RECEIVE_INTERRUPT0);
				MAP_I2C_enableInterrupt(EUSCI_B0_BASE, EUSCI_B_I2C_RECEIVE_INTERRUPT0);
				while(!isReceive);
				while(MAP_GPIO_getInputPinValue(GPIO_PORT_P1, GPIO_PIN1)
														== GPIO_INPUT_PIN_LOW);
				if(RxData[0] == 0x85 && RxData[1] == 0x83)
				{
					MAP_GPIO_setOutputHighOnPin(ledPort, greenPin);
					MAP_GPIO_setOutputLowOnPin(ledPort, redPin);
				}else
				{
					MAP_GPIO_setOutputLowOnPin(ledPort, greenPin);
					MAP_GPIO_setOutputHighOnPin(ledPort, redPin);
				}MAP_I2C_disableInterrupt(EUSCI_B0_BASE, EUSCI_B_I2C_RECEIVE_INTERRUPT0);
				MAP_GPIO_setOutputLowOnPin(GPIO_PORT_P1, GPIO_PIN0);
				MAP_GPIO_setOutputLowOnPin(GPIO_PORT_P2, GPIO_PIN2);

Susan Yang:

JianLin Hou 说:但是在第二次发送时,程序卡在了I2C_masterSendMultiByteStart上

附上我之前使用的I2C驱动,您可以先看一下

//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - https://www.ti2k.com/wp-content/uploads/ti2k/DeyiSupport_OtherMCU_
//
// 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.
//
//****************************************************************************
#include <stdbool.h>
#include <stdint.h>
#include "msp432.h"
#include "i2c_driver.h"
#include "driverlib.h"//*****************************************************************************
//
// Definitions
//
//*****************************************************************************//*****************************************************************************
//
// Global Data
//
//*****************************************************************************
volatile eUSCI_status ui8Status;uint8_t*pData;
uint8_tui8DummyRead;
uint32_t g_ui32ByteCount;
boolburstMode = false;/* I2C Master Configuration Parameter */
volatile eUSCI_I2C_MasterConfig i2cConfig =
{EUSCI_B_I2C_CLOCKSOURCE_SMCLK,// SMCLK Clock Source0,EUSCI_B_I2C_SET_DATA_RATE_400KBPS,// Desired I2C Clock of 400khz0,// No byte counter thresholdEUSCI_B_I2C_SEND_STOP_AUTOMATICALLY_ON_BYTECOUNT_THRESHOLD// Autostop
};//*****************************************************************************
//
// Imported Data
//
//*****************************************************************************//*****************************************************************************
//
// Constants
//
//*****************************************************************************//*****************************************************************************
//
// Function Prototypes
//
//*****************************************************************************/***********************************************************Function:
*/
void initI2C(void)
{/* I2C Clock Soruce Speed */i2cConfig.i2cClk = MAP_CS_getSMCLK();/* Select I2C function for I2C_SCL(P6.5) & I2C_SDA(P6.4) */GPIO_setAsPeripheralModuleFunctionOutputPin(GPIO_PORT_P6, GPIO_PIN5 | GPIO_PIN4,GPIO_PRIMARY_MODULE_FUNCTION);/* Initializing I2C Master to SMCLK at 400kbs with autostop */
//MAP_I2C_initMaster(EUSCI_B1_MODULE, &i2cConfig);
}/***********************************************************Function:
*/
bool writeI2C(uint8_t ui8Addr, uint8_t ui8Reg, uint8_t *Data, uint8_t ui8ByteCount)
{/* Wait until ready to write */while (MAP_I2C_isBusBusy(EUSCI_B1_BASE));/* Assign Data to local Pointer */pData = Data;/* Disable I2C module to make changes */MAP_I2C_disableModule(EUSCI_B1_MODULE);/* Setup the number of bytes to transmit + 1 to account for the register byte */i2cConfig.byteCounterThreshold = ui8ByteCount + 1;MAP_I2C_initMaster(EUSCI_B1_MODULE, (const eUSCI_I2C_MasterConfig *)&i2cConfig);/* Load device slave address */MAP_I2C_setSlaveAddress(EUSCI_B1_MODULE, ui8Addr);/* Enable I2C Module to start operations */MAP_I2C_enableModule(EUSCI_B1_MODULE);/* Enable master STOP, TX and NACK interrupts */MAP_I2C_enableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_STOP_INTERRUPT +EUSCI_B_I2C_NAK_INTERRUPT + EUSCI_B_I2C_TRANSMIT_INTERRUPT0);/* Set our local state to Busy */ui8Status = eUSCI_BUSY;/* Send start bit and register */MAP_I2C_masterSendMultiByteStart(EUSCI_B1_MODULE,ui8Reg);/* Enable master interrupt for the remaining data */MAP_Interrupt_enableInterrupt(INT_EUSCIB1);// NOW WAIT FOR DATA BYTES TO BE SENTwhile(ui8Status == eUSCI_BUSY){
#ifdef USE_LPMMAP_PCM_gotoLPM0();
#else__no_operation();
#endif}/* Disable interrupts */MAP_I2C_disableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_STOP_INTERRUPT +EUSCI_B_I2C_NAK_INTERRUPT + EUSCI_B_I2C_TRANSMIT_INTERRUPT0);MAP_Interrupt_disableInterrupt(INT_EUSCIB1);if(ui8Status == eUSCI_NACK){return(false);}else{return(true);}
}/***********************************************************Function:
*/
bool readI2C(uint8_t ui8Addr, uint8_t ui8Reg, uint8_t *Data, uint8_t ui8ByteCount)
{/* Todo: Put a delay *//* Wait until ready */while (MAP_I2C_isBusBusy(EUSCI_B1_BASE));/* Assign Data to local Pointer */pData = Data;/* Disable I2C module to make changes */MAP_I2C_disableModule(EUSCI_B1_MODULE);/* Setup the number of bytes to receive */i2cConfig.byteCounterThreshold = ui8ByteCount;i2cConfig.autoSTOPGeneration = EUSCI_B_I2C_SEND_STOP_AUTOMATICALLY_ON_BYTECOUNT_THRESHOLD;MAP_I2C_initMaster(EUSCI_B1_MODULE, (const eUSCI_I2C_MasterConfig *)&i2cConfig);/* Load device slave address */MAP_I2C_setSlaveAddress(EUSCI_B1_MODULE, ui8Addr);/* Enable I2C Module to start operations */MAP_I2C_enableModule(EUSCI_B1_MODULE);/* Enable master STOP and NACK interrupts */MAP_I2C_enableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_STOP_INTERRUPT +EUSCI_B_I2C_NAK_INTERRUPT);/* Set our local state to Busy */ui8Status = eUSCI_BUSY;/* Send start bit and register */MAP_I2C_masterSendMultiByteStart(EUSCI_B1_MODULE,ui8Reg);/* Enable master interrupt for the remaining data */MAP_Interrupt_enableInterrupt(INT_EUSCIB1);/* NOTE: If the number of bytes to receive = 1, then as target register is being shifted* out during the write phase, UCBxTBCNT will be counted and will trigger STOP bit prematurely* If count is > 1, wait for the next TXBUF empty interrupt (just after reg value has been* shifted out*/while(ui8Status == eUSCI_BUSY){if(MAP_I2C_getInterruptStatus(EUSCI_B1_MODULE, EUSCI_B_I2C_TRANSMIT_INTERRUPT0)){ui8Status = eUSCI_IDLE;}}ui8Status = eUSCI_BUSY;/* Turn off TX and generate RE-Start */MAP_I2C_masterReceiveStart(EUSCI_B1_MODULE);/* Enable RX interrupt */MAP_I2C_enableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_RECEIVE_INTERRUPT0);/* Wait for all data be received */while(ui8Status == eUSCI_BUSY){#ifdef USE_LPMMAP_PCM_gotoLPM0();
#else__no_operation();
#endif}/* Disable interrupts */MAP_I2C_disableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_STOP_INTERRUPT +EUSCI_B_I2C_NAK_INTERRUPT + EUSCI_B_I2C_RECEIVE_INTERRUPT0);MAP_Interrupt_disableInterrupt(INT_EUSCIB1);if(ui8Status == eUSCI_NACK){return(false);}else{return(true);}
}/***********************************************************Function:
*/
bool readBurstI2C(uint8_t ui8Addr, uint8_t ui8Reg, uint8_t *Data, uint32_t ui32ByteCount)
{/* Todo: Put a delay *//* Wait until ready */while (MAP_I2C_isBusBusy(EUSCI_B1_BASE));/* Assign Data to local Pointer */pData = Data;/* Disable I2C module to make changes */MAP_I2C_disableModule(EUSCI_B1_MODULE);/* Setup the number of bytes to receive */i2cConfig.autoSTOPGeneration = EUSCI_B_I2C_NO_AUTO_STOP;g_ui32ByteCount = ui32ByteCount;burstMode = true;MAP_I2C_initMaster(EUSCI_B1_MODULE, (const eUSCI_I2C_MasterConfig *)&i2cConfig);/* Load device slave address */MAP_I2C_setSlaveAddress(EUSCI_B1_MODULE, ui8Addr);/* Enable I2C Module to start operations */MAP_I2C_enableModule(EUSCI_B1_MODULE);/* Enable master STOP and NACK interrupts */MAP_I2C_enableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_STOP_INTERRUPT +EUSCI_B_I2C_NAK_INTERRUPT);/* Set our local state to Busy */ui8Status = eUSCI_BUSY;/* Send start bit and register */MAP_I2C_masterSendMultiByteStart(EUSCI_B1_MODULE,ui8Reg);/* Enable master interrupt for the remaining data */MAP_Interrupt_enableInterrupt(INT_EUSCIB1);/* NOTE: If the number of bytes to receive = 1, then as target register is being shifted* out during the write phase, UCBxTBCNT will be counted and will trigger STOP bit prematurely* If count is > 1, wait for the next TXBUF empty interrupt (just after reg value has been* shifted out*/while(ui8Status == eUSCI_BUSY){if(MAP_I2C_getInterruptStatus(EUSCI_B1_MODULE, EUSCI_B_I2C_TRANSMIT_INTERRUPT0)){ui8Status = eUSCI_IDLE;}}ui8Status = eUSCI_BUSY;/* Turn off TX and generate RE-Start */MAP_I2C_masterReceiveStart(EUSCI_B1_MODULE);/* Enable RX interrupt */MAP_I2C_enableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_RECEIVE_INTERRUPT0);/* Wait for all data be received */while(ui8Status == eUSCI_BUSY){#ifdef USE_LPMMAP_PCM_gotoLPM0();
#else__no_operation();
#endif}/* Disable interrupts */MAP_I2C_disableInterrupt(EUSCI_B1_MODULE, EUSCI_B_I2C_STOP_INTERRUPT +EUSCI_B_I2C_NAK_INTERRUPT + EUSCI_B_I2C_RECEIVE_INTERRUPT0);MAP_Interrupt_disableInterrupt(INT_EUSCIB1);if(ui8Status == eUSCI_NACK){return(false);}else{return(true);}
}/***********************************************************Function: euscib1IntHandler*/
void euscib1IntHandler(void)
{uint_fast16_t status;status = MAP_I2C_getEnabledInterruptStatus(EUSCI_B1_MODULE);MAP_I2C_clearInterruptFlag(EUSCI_B1_MODULE, status);if (status & EUSCI_B_I2C_NAK_INTERRUPT){/* Generate STOP when slave NACKS */MAP_I2C_masterSendMultiByteStop(EUSCI_B1_MODULE);/* Clear any pending TX interrupts */MAP_I2C_clearInterruptFlag(EUSCI_B1_MODULE, EUSCI_B_I2C_TRANSMIT_INTERRUPT0);/* Set our local state to NACK received */ui8Status = eUSCI_NACK;}if (status & EUSCI_B_I2C_START_INTERRUPT){/* Change our local state */ui8Status = eUSCI_START;}if (status & EUSCI_B_I2C_STOP_INTERRUPT){/* Change our local state */ui8Status = eUSCI_STOP;}if (status & EUSCI_B_I2C_RECEIVE_INTERRUPT0){/* RX data */*pData++ = MAP_I2C_masterReceiveMultiByteNext(EUSCI_B1_MODULE);ui8DummyRead= MAP_I2C_masterReceiveMultiByteNext(EUSCI_B1_MODULE);if (burstMode){g_ui32ByteCount--;if (g_ui32ByteCount == 1){burstMode = false;/* Generate STOP */MAP_I2C_masterSendMultiByteStop(EUSCI_B1_MODULE);}}}if (status & EUSCI_B_I2C_TRANSMIT_INTERRUPT0){/* Send the next data */MAP_I2C_masterSendMultiByteNext(EUSCI_B1_MODULE, *pData++);}#ifdef USE_LPMMAP_Interrupt_disableSleepOnIsrExit();
#endif
}

//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - https://www.ti2k.com/wp-content/uploads/ti2k/DeyiSupport_OtherMCU_
//
// 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.
//
//
//****************************************************************************
#ifndef _I2C_DRIVER_H_
#define _I2C_DRIVER_H_//****************************************************************************
//
// Types
//
//****************************************************************************
typedef enum {eUSCI_IDLE = 0,eUSCI_SUCCESS = 0,eUSCI_BUSY = 1,eUSCI_NACK = 2,eUSCI_STOP,eUSCI_START
} eUSCI_status;//*****************************************************************************
//
// Definitions
//
//*****************************************************************************//*****************************************************************************
//
// Exported variables
//
//*****************************************************************************//*****************************************************************************
//
// Exported prototypes
//
//*****************************************************************************
extern void initI2C(void);
extern bool writeI2C(uint8_t ui8Addr, uint8_t ui8Reg, uint8_t *Data, uint8_t ui8ByteCount);
extern bool readI2C(uint8_t ui8Addr, uint8_t ui8Reg, uint8_t *Data, uint8_t ui8ByteCount);
extern bool readBurstI2C(uint8_t ui8Addr, uint8_t ui8Reg, uint8_t *Data, uint32_t ui32ByteCount);
#endif /* _I2C_DRIVER_H_ */

赞(0)
未经允许不得转载:TI中文支持网 » MSP432P401R: IIC重复通信无法发出数据
分享到: 更多 (0)