Other Parts Discussed in Thread: SYSCONFIG, CC2340R5
Tool/software:
I am using CC2340R5-Q1 and i have merged SPI driver in Basic_BLE code. I am trying to communicate with NTM88 TPMS IC to get the Tire Temperature and Pressure readings. CC2340R5-Q1 is acting as SPI controller and NTM88 TPMS IC is acting as SPI peripheral. So in my application NTM88 wakes up the BLE module whenever there is a pressure leak detected by using GPIO interrupt(named as "Peripheral_Ready" pin) by making it High, then in turn CC2340 acknowledges it by lowering the MOSI pin(as NTM88 has less no. pins ,MOSI pin is also used for handshaking before starting the SPI communication) and waits for NTM88 to lower the Peripheral_ready pin before starting the SPI transfers and CC2340 has to clear the CORE_TR_HOLD bit of the SPIOPS register on NTM88 through SPI write operation in order to complete the SPI transfer . if this write operation is not completed NTM88 goes into watchdog reset and SPI transfer is not done.
So, my problem here is, i am able to complete handshaking properly, even i am able to see pulses on MOSI, MISO, SCLK pins also but still the NTM88 IC is going into watchdog reset as CC2340 is not able to clear the CORE_TR_HOLD bit of the SPIOPS register. So, i am doubting that it may be not able to send write command successfully. kindly help me to solve the issue. I am trying to read 9 bytes of data from NTM88 and write 1 byte to SPIOPS register to clear the CORE_TR_HOLD bit. So Nine 16-bit READ commands are performed to read the Nine sensor data bytes. Then, the two 16-bit WRITE commands are performed to clear the SPIOPS register. This makes a total of Eleven 16-bit transfers. here SPI data size is 16-bits.
MOSI & MISO waveforms
SPI Settings in sysconfig
In order to perform eleven 16-bit transfer, what should be the value of Min DMA Transfer Size. Here i have written 10, is this ok? if not then what should be the correct value.
SPI_Controller.c (cc2340 code)
#include <stddef.h> #include <stdint.h> #include "string.h" /* POSIX Header files */ #include <pthread.h> #include <semaphore.h> #include <unistd.h> /* RTOS header files */ #include <FreeRTOS.h> #include <task.h> /* Driver Header files */ #include <ti/drivers/GPIO.h> #include <ti/drivers/SPI.h> #include <ti/display/Display.h> #include <ti/bleapp/ble_app_util/inc/bleapputil_api.h> #include <ti/bleapp/ble_app_util/inc/bleapputil_internal.h> /* Driver configuration */ #include "ti_drivers_config.h" #define THREADSTACKSIZE (1024) #define ADDR_FIRST_DATA_BYTE 0xCF #define ADDR_SPIOPS 0x38 #define NB_16BIT_XFERS (NB_DATA_BYTES + 2) #define NB_DATA_BYTES 9 #define SPI_MSG_LENGTH 10 // Pressure Constants : Pressure sensor range: 90 kPa to 930 kPa ( 0.9 to 9.3 bar #define DELTA_P (0.824) #define P_MIN_MINUS_DELTA_P (88.353) #define KPa_TO_Psi_CONST (0.145038) // Acceleration Constants : Accelerometer Range: –120 g to +520 g #define PROOF_INERTIA_AT_A_MIN_MINUS_AMIN_MULTIPLY_DELTA_A (-52.204) #define DELTA_A (0.102) #define MAX_LOOP (10) typedef struct Send_Data { bool isDataToSend; uint8_t nb_bytes; uint8_t array_data[140]; } t_Send_Data; t_Send_Data gSendData; static Display_Handle display; static unsigned char controllerRxBuffer[NB_16BIT_XFERS*2]; static unsigned char controllerTxBuffer[NB_16BIT_XFERS*2]; volatile unsigned char wakeup_flg=0; unsigned char u8Temperature = 0; unsigned char fPressure = 0; //unsigned char fAccX=0; unsigned char fVolt=0; unsigned char Vehicle_status=0; static uint8_t u8SpiFillTxBuffer (void); static bool bSpiGetParity (uint8_t parityByte); static uint8_t u8SpiGetStatus (uint16_t u16SpiRsp); static uint8_t u8SpiGetData (uint16_t u16SpiRsp); static uint8_t u8SpiStoreData (void); static void vfnSpiFillBufferRead (uint16_t u16address, uint8_t *i); static void vfnSpiFillBufferWrite (uint16_t u16data, uint8_t *i); static void vfnSpiFillBufferCmd (uint16_t u16data, uint8_t *i); static void vfnSpiTriggerXfers (SPI_Handle controllerSpi, uint8_t u8nb_bytes); void vfnSpiPerformXfers (SPI_Handle controllerSpi); uint8_t getTemperatureValue(uint8_t temperatureRawValue); uint8_t getPressureValue(uint8_t u8PressureRawValueL, uint8_t u8PressureRawValueH); //float getAccelerometerValue(uint8_t u8AccValueL, uint8_t u8AccValueH); uint8_t getVoltageValue(uint8_t voltageRawValue ); uint8_t map(long x, long in_min, long in_max, long out_min, long out_max); /* Semaphore to block controller until peripheral is ready for transfer */ sem_t controllerSem; /* * ======== peripheralReadyFxn ======== * Callback function for the GPIO interrupt on CONFIG_SPI_PERIPHERAL_READY. */ void peripheralReadyFxn(uint_least8_t index) { GPIO_write(CONFIG_GPIO_SPI_CONTROLLER_PICO, 0); sem_post(&controllerSem); wakeup_flg=1 ; } /* * ======== controllerThread ======== * Controller SPI sends a message to peripheral while simultaneously receiving a * message from the peripheral. */ void *controllerThread(void *arg0) { SPI_Handle controllerSpi; SPI_Params spiParams; SPI_Transaction transaction; uint32_t i; bool transferOK; int32_t status; /* configure interrupt on CONFIG_SPI_PERIPHERAL_READY */ GPIO_setConfig(CONFIG_SPI_PERIPHERAL_READY,GPIO_CFG_IN_PD | GPIO_CFG_IN_INT_RISING); // interrupt cofigured for positive edge GPIO_setCallback(CONFIG_SPI_PERIPHERAL_READY, peripheralReadyFxn); GPIO_enableInt(CONFIG_SPI_PERIPHERAL_READY); /* * Create synchronization semaphore; the controller will wait on this semaphore * until the peripheral is ready. */ status = sem_init(&controllerSem, 0, 0); if (status != 0) { // Display_printf(display, 0, 0, "Error creating controllerSem\n"); // while (1) {} } while(1) { if(wakeup_flg) { wakeup_flg=0; // GPIO_write(CONFIG_GPIO_SPI_CONTROLLER_PICO, 1); /* * Wait until peripheral is ready for transfer; peripheral will pull * CONFIG_SPI_PERIPHERAL_READY low. */ while(GPIO_read(CONFIG_SPI_PERIPHERAL_READY) == 1); /* Open SPI as controller (default) */ SPI_Params_init(&spiParams); spiParams.frameFormat = SPI_POL0_PHA1; /* See device-specific technical reference manual for supported speeds */ spiParams.bitRate = 1000000; spiParams.dataSize = 16; controllerSpi = SPI_open(CONFIG_SPI_CONTROLLER, &spiParams); if (controllerSpi == NULL) { // Display_printf(display, 0, 0, "Error initializing controller SPI\n"); // while (1) {} } else { // Display_printf(display, 0, 0, "Controller SPI initialized\n"); vfnSpiPerformXfers(controllerSpi); SPI_close(controllerSpi); } } GPIO_resetConfig(CONFIG_GPIO_SPI_CONTROLLER_PICO); GPIO_setConfig(CONFIG_GPIO_SPI_CONTROLLER_PICO, GPIO_CFG_OUTPUT | GPIO_CFG_OUT_HIGH); sem_wait(&controllerSem); } // Display_printf(display, 0, 0, "\nDone"); return (NULL); } /* * ======== mainThread ======== */ void *mainThread(void *arg0) { pthread_t thread0; pthread_attr_t attrs; struct sched_param priParam; int retc; int detachState; /* Call driver init functions. */ // Display_init(); GPIO_init(); SPI_init(); /* Create application threads */ pthread_attr_init(&attrs); detachState = PTHREAD_CREATE_DETACHED; /* Set priority and stack size attributes */ retc = pthread_attr_setdetachstate(&attrs, detachState); if (retc != 0) { /* pthread_attr_setdetachstate() failed */ while (1) {} } retc |= pthread_attr_setstacksize(&attrs, THREADSTACKSIZE); if (retc != 0) { /* pthread_attr_setstacksize() failed */ while (1) {} } /* Create controller thread */ priParam.sched_priority = 1; pthread_attr_setschedparam(&attrs, &priParam); retc = pthread_create(&thread0, &attrs, controllerThread, NULL); if (retc != 0) { /* pthread_create() failed */ while (1) {} } return (NULL); } void emptyMain(void) { pthread_t thread; pthread_attr_t attrs; struct sched_param priParam; int retc; pthread_attr_init(&attrs); /* Set priority, detach state, and stack size attributes */ priParam.sched_priority = 1; retc = pthread_attr_setschedparam(&attrs, &priParam); retc |= pthread_attr_setdetachstate(&attrs, PTHREAD_CREATE_DETACHED); retc |= pthread_attr_setstacksize(&attrs, THREADSTACKSIZE); if (retc != 0) { /* failed to set attributes */ while (1) {} } retc = pthread_create(&thread, &attrs, mainThread, NULL); if (retc != 0) { /* pthread_create() failed */ while (1) {} } } static uint8_t u8SpiFillTxBuffer (void) { uint8_t i, buffer_index; uint16_t u16address; // We fill the buffer from the beginning buffer_index = 0; /***** READ commands to get the sensor data ******************/ u16address = ADDR_FIRST_DATA_BYTE; for (i=0; i<NB_DATA_BYTES; i++) { vfnSpiFillBufferRead(u16address++, &buffer_index); } /***** WRITE commands to let the NTM88 resume operations *****/ vfnSpiFillBufferWrite(ADDR_SPIOPS, &buffer_index); vfnSpiFillBufferWrite(0x00, &buffer_index); // Note that it would be necessary to perform an additional transfer to read the WRITE command status return buffer_index; } /********************************************************************************** * Description: Calculates and returns the parity of the byte passed as parameter * Input: u8parityByte, the byte of which we want to know the parity * Output: the parity *********************************************************************************/ static bool bSpiGetParity (uint8_t u8parityByte) { uint8_t i=0; uint8_t u8count=0; for (i=0; i< 7 ; i++){ if (u8parityByte%2 == 1) u8count++; //increments count u8parityByte /= 2; } return (u8count%2 != 0); } /***************************************************************************** * Description: Adds a READ command to the SPI buffer and increments the buffer * index * Input: uint16_t address, the address to read * uint8_t* i, the pointer to the index in the buffer at which the command * should be written * Output: void *****************************************************************************/ static void vfnSpiFillBufferRead (uint16_t u16address, uint8_t *i) { vfnSpiFillBufferCmd(u16address, i); } /***************************************************************************** * Description: Adds a WRITE command to the SPI buffer and increments the buffer * index * Input: uint16_t data, the data to write, which can be the address or the value * to write * uint8_t* i, the pointer to the index in the buffer at which the command * should be written * Output: void *****************************************************************************/ static void vfnSpiFillBufferWrite (uint16_t u16data, uint8_t *i) { u16data += (1<<13); vfnSpiFillBufferCmd(u16data, i); } /***************************************************************************** * Description: Formats the command, stores it in the SPI buffer and increments * the buffer index * Input: uint16_t data, the data to write, which can be the address or the value * to write * uint8_t* i, the pointer to the index in the buffer at which the command * should be written * Output: void *****************************************************************************/ static void vfnSpiFillBufferCmd (uint16_t u16data, uint8_t *i) { /* * 16 bits format * OP Command for Write ---> 1 / for Read ---> 0 * OP | A12 A11 A10 A9 A8 A7 A6 A5 A4 A3 A2 A1 A0 | P1 P0 * x Address Address Address Address Parity * P1 -> Parity for OP A12 A11 A10 A9 A8 A7 * P2 -> Parity for A6 A5 A4 A3 A2 A1 A0 */ uint8_t u8parityByteMSB=0, u8parityByteLSB=0; bool bP0=0, bP1=0; uint8_t u8parityDuo=0; uint16_t u16CommandToTPMS=0; u8parityByteMSB = (uint8_t)(u16data / 128); u8parityByteLSB = (uint8_t)(u16data % 128); bP1 = bSpiGetParity(u8parityByteMSB); bP0 = bSpiGetParity(u8parityByteLSB); // Combining P1 and P0 u8parityDuo = 2*bP1 + bP0; u16CommandToTPMS = (uint16_t)(u16data<<2) + u8parityDuo; controllerTxBuffer[(*i)++] = u16CommandToTPMS & 0xFF; // LSByte first controllerTxBuffer[(*i)++] = u16CommandToTPMS / 256; // MSByte second return; } /********************************************************************************** * Description: Triggers the SPI transfers * Input: void * Output: void *********************************************************************************/ static void vfnSpiTriggerXfers (SPI_Handle controllerSpi, uint8_t u8nb_bytes) { SPI_Transaction transaction; static bool transferOK = 0; /* Initialize controller SPI transaction structure */ memset((void *)controllerRxBuffer, 0, (NB_16BIT_XFERS*2)); transaction.count = 12; transaction.txBuf = (void *)controllerTxBuffer; transaction.rxBuf = (void *)controllerRxBuffer; /* Perform SPI transfer */ transferOK = SPI_transfer(controllerSpi, &transaction); if (transferOK) { //Display_printf(display, 0, 0, "Controller received: %s", controllerRxBuffer); } else { // Display_printf(display, 0, 0, "Unsuccessful controller SPI transfer"); } } /********************************************************************************** * Description: Extracts the 8-bit status from the 16-bit response * Input: void * Output: void *********************************************************************************/ static uint8_t u8SpiGetStatus(uint16_t u16SpiRsp) { return (u16SpiRsp>>10)& 0x1F; } /********************************************************************************** * Description: Extracts the 8-bit data from the 16-bit response * Input: void * Output: void *********************************************************************************/ static uint8_t u8SpiGetData(uint16_t u16SpiRsp) { return (u16SpiRsp>>2)& 0xFF; } /********************************************************************************** * Description: Stores the data read via SPI * Input: void * Output: void *********************************************************************************/ static uint8_t u8SpiStoreData (void) { uint8_t i; uint8_t u8offset_read_data; volatile uint16_t u16spi_response; volatile uint8_t u8read_status = 0; /* We discard the response of the first 16-bit xfer since it contains no information, so we discard indexes 0 and 1 */ u8offset_read_data = 2; for (i=0; i<NB_DATA_BYTES; i++) { // First, re-assemble the 16-bit response u16spi_response = (uint16_t)(controllerRxBuffer[2*i+1+u8offset_read_data]); // MSByte u16spi_response <<= 8; u16spi_response &= 0xFF00; u16spi_response |= controllerRxBuffer[2*i+u8offset_read_data]; // LSByte // Then extract the data and status from it gSendData.array_data[i] = u8SpiGetData(u16spi_response); u8read_status |= u8SpiGetStatus(u16spi_response); } gSendData.nb_bytes = NB_DATA_BYTES; return u8read_status; } /********************************************************************************** * Description: Prepares the SPI transmission buffer, triggers the transfers and * stores the data read after completion of the transfer. * Input: void * Output: void *********************************************************************************/ void vfnSpiPerformXfers (SPI_Handle controllerSpi) { uint8_t u8xfer_nb_bytes; /* Prepare the Tx buffer for SPI transfers */ u8xfer_nb_bytes = u8SpiFillTxBuffer(); /* Launch the SPI transfers - this is a blocking operation */ vfnSpiTriggerXfers(controllerSpi, u8xfer_nb_bytes); /* Store sensor data in the application buffer. Note that the returned status is discarded here, but in a final application it should be used to check the validity of the data received and do a re-try in case transfers were not successfully */ if(u8SpiStoreData()) { u8Temperature = getTemperatureValue(gSendData.array_data[5]); fPressure = getPressureValue(gSendData.array_data[3], gSendData.array_data[2]); // fAccX = getAccelerometerValue(gSendData.array_data[8], gSendData.array_data[7]); fVolt = getVoltageValue(gSendData.array_data[4]); Vehicle_status=gSendData.array_data[6]; BLEAppUtil_enqueueMsg(BLEAPPUTIL_EVT_APP_EVENT, 0); } } /********************************************************************************** * Description: Calculates the temperature values from raw values. * Input: uint8_t temperatureRawValue : Raw value. * Output: uint8_t : Calculated value. *********************************************************************************/ uint8_t getTemperatureValue(uint8_t temperatureRawValue) { return (temperatureRawValue - 15); } /********************************************************************************** * Description: Calculates the pressure values from raw values. * Input: uint8_t u8PressureRawValueL : Raw value (Low Byte). * uint8_t u8PressureRawValueH : Raw value (High Byte). * Output: uint16_t : Calculated value. *********************************************************************************/ uint8_t getPressureValue(uint8_t u8PressureRawValueL, uint8_t u8PressureRawValueH) { volatile uint16_t u16Pcode = 0; volatile uint8_t fPressure = 0; u16Pcode = (uint16_t)(u8PressureRawValueH << 8); u16Pcode = u16Pcode | u8PressureRawValueL; // fPressure = ((DELTA_P * u16Pcode) + (P_MIN_MINUS_DELTA_P)); fPressure = ((DELTA_P * u16Pcode)) * (KPa_TO_Psi_CONST); return fPressure; } /********************************************************************************** * Description: Calculates the accelerometer X values from raw values. * Input: uint8_t u8AccXValueL : Raw value (Low Byte). * uint8_t u8AccXValueH : Raw value (High Byte). * Output: uint8_t : Calculated value. *********************************************************************************/ /*float getAccelerometerValue(uint8_t u8AccValueL, uint8_t u8AccValueH) { volatile uint16_t u16Acode = 0; volatile uint8_t fAcceleration = 0; u16Acode = (uint16_t)(u8AccValueH << 8); u16Acode = u16Acode | u8AccValueL; //fAcceleration = ((DELTA_A * u16Acode) + (PROOF_INERTIA_AT_A_MIN_MINUS_AMIN_MULTIPLY_DELTA_A)); fAcceleration =(u16Acode/10); return fAcceleration; }*/ /********************************************************************************** * Description: Calculates the voltage values from raw values. * Input: uint8_t voltageRawValue : Raw value. * Output: float : Calculated value. *********************************************************************************/ uint8_t getVoltageValue(uint8_t voltageRawValue ) { volatile uint8_t fVoltage=0; volatile signed char percentage=0; fVoltage= ((0.01*voltageRawValue)+1.22)*10; percentage=map( fVoltage, 19, 31, 0, 100); if(percentage>100) percentage=100; else if(percentage<=0) percentage=0; return percentage; } uint8_t map(long x, long in_min, long in_max, long out_min, long out_max) { return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; }
SPI code of NTM88 side:
/****************************************************************************** Copyright 2019-2021 NXP. This software is owned or controlled by NXP and may only be used strictly in accordance with the applicable license terms. By expressly accepting such terms or by downloading, installing, activating and/or otherwise using the software, you are agreeing that you have read, and that you agree to comply with and are bound by, such license terms. If you do not agree to be bound by the applicable license terms, then you may not retain, install, activate or otherwise use the software *******************************************************************************/ #include <hidef.h> /* for EnableInterrupts macro */ #include "derivative.h" /* include peripheral declarations */ #include "ntm88_axis_xz_lib.h" #include "sensor_measurements.h" #include "spi_communication.h" #include "user_configuration.h" /* * Local macros */ #define RUN_MODE 1 #define STOP4_MODE 2 #define ACK_WAIT_TIME_MILLISEC 64 // Valid values: 2, 4, 8, 16, 32, 64 or 128 // Defines for KBI init, do not modify them #define KBI_FALLING_EDGE 0 #define KBI_RISING_EDGE 1 // KBI pin #define READ_KBI_PIN PTAD_PTAD3 /*/!\ The two macros below must also be defined in the MKW project /!\ */ #define ADDR_FIRST_DATA_BYTE 0xCF #define NB_DATA_BYTES 9 /* * Local definitions */ UINT8 u8Vehiclestate=0; #pragma DATA_SEG __SHORT_SEG MY_ZEROPAGE /* Declare the data array at the address known by the MKW */ UINT8 gau8DataArray[NB_DATA_BYTES] @ADDR_FIRST_DATA_BYTE; #pragma CODE_SEG DEFAULT /* * Local functions */ void vfnKbiEnable (UINT8 u8edge); void vfnKbiDisable (void); void vfnStoreSensorData (void); void vfnEnableTimeout (UINT8 u8duration_ms); void vfnDisableTimeout (void); UINT8 u8WaitForMkwAck (UINT8 u8power_mode); /************************************************************************************** * Description: Enables KBI on PTA3 * Input: u8edge, the edge to configure * Output: void ***************************************************************************************/ void vfnKbiEnable (UINT8 u8edge) { // Init KBI //PTAPE[3:0] PTADD[3:0] KBIPE[3:0] KBEDG[3:0] Pullup Pulldown //(pull enable) (data direction) (KBI pin enable) (KBI Edge Select) // 0 0 x x disabled disabled // 1 0 0 x enabled disabled // x 1 x x disabled disabled // * 1 0 1 0 enabled disabled // 1 0 1 1 disabled enabled PTADD_PTADD3 = 0; //Insure PTA3 is configured as input //Keyboard Detection Mode //0 Keyboard detects edges only. //1 Keyboard detects both edges and levels. KBISC_KBIMOD = 0; // In STOP1 this bit is ignored and only low level is detected //1. Mask keyboard interrupts by clearing KBIE in KBISC. KBISC_KBIE = 0; //2. Enable the KBI polarity by setting the appropriate KBEDGn bits in KBIES. //Keyboard Edge Selects // 0 Falling edge/low level. // 1 Rising edge/high level. KBIES_KBEDG3 = u8edge; //3. If using internal pullup/pulldown device, configure the associated pullup enable bits in PTAPE[3:0]. PTAPE_PTAPE3 = 1; //4. Enable the KBI pins by setting the appropriate KBIPE[3:0] bits in KBIPE. // KBI Pin Enable Register (KBIPE) KBIPE_KBIPE0 = 0; //0 Pin not enabled as keyboard interrupt. KBIPE_KBIPE1 = 0; //0 Pin not enabled as keyboard interrupt. KBIPE_KBIPE2 = 0; //0 Pin not enabled as keyboard interrupt. KBIPE_KBIPE3 = 1; //1 Pin enabled as keyboard interrupt. //5. Write to KBACK in KBISC to clear any false interrupts. KBISC_KBACK = 1; //6. Set KBIE in KBISC to enable interrupts. KBISC_KBIE = 1; // If wake up from STOP1 the interrupt is not generated even if KBIE is set } /************************************************************************************** * Description: Disables KBI on PTA3 * Input: void * Output: void ***************************************************************************************/ void vfnKbiDisable (void) { KBIPE_KBIPE3 = 0; //1 Pin disabled as keyboard interrupt KBISC_KBIE = 0; // Disable interrupt } /************************************************************************************** * Description: Configures a timeout using RTI block * Input: u8duration_ms, the timeout duration in milliseconds * Output: void ***************************************************************************************/ void vfnEnableTimeout (UINT8 u8duration_ms) { UINT8 u8period; /* Clear flag */ TPMS_INTERRUPT_FLAG &= ~RTI_INTERRUPT_FLAG; /* Configure the RTI timeout: the RTI block being clocked by the LFO clock which * can have an actual frequency between 500kHz and 1500kHz, configuring a 64ms delay will * result in an actual delay between 43 and 128ms. */ u8period = 0; // First clear flag SRTISC_RTIACK = 1; // Select LFO as clock to be able to wake up from STOP1 SRTISC_RTICLKS = 0; // Calculate RTIS field: RTIS = log2(delay), refer to register definition in datasheet while (u8duration_ms >>= 1) { ++u8period; } SRTISC_RTIS = u8period; // Enable interrupt SRTISC_RTIE = 1; } /************************************************************************************** * Description: Disables the RTI block * Input: void * Output: void ***************************************************************************************/ void vfnDisableTimeout (void) { // Turn off the RTI SRTISC_RTIS = 0; // Disable the interrupt SRTISC_RTIE = 0; /* Clear flag */ TPMS_INTERRUPT_FLAG &= ~RTI_INTERRUPT_FLAG; } /************************************************************************************** * Description: Waits for the MKW to acknowledge the wakeup. * The function is left when the MKW performed the acknowkedge or when * the timeout was reached. * Input: u8power_mode, the power mode to be entered while waiting for the acknowledge * Valid inputs: RUN_MODE or STOP4_MODE defined in this file * Output: u8status, clear if the MKW performed the acknowledge, set otherwise. ***************************************************************************************/ UINT8 u8WaitForMkwAck (UINT8 u8power_mode) { UINT8 u8status; /* The MKW will lower the KBI pin to indicate it is ready to perform the transfer. * In this function we are waiting for the KBI to be low. */ /* Enable timeout to make sure we do not get stuck */ vfnEnableTimeout(ACK_WAIT_TIME_MILLISEC); /* Check in which power mode we should wait */ if (u8power_mode == RUN_MODE) { while ((READ_KBI_PIN == 1) && ((TPMS_INTERRUPT_FLAG & RTI_INTERRUPT_FLAG) != RTI_INTERRUPT_FLAG) ); } else if (u8power_mode == STOP4_MODE) { // Configure the KBI interrupt vfnKbiEnable(KBI_FALLING_EDGE); // Clear the flags TPMS_INTERRUPT_FLAG &= ~KBI_INTERRUPT_FLAG; // Configure STOP4 vfnSetStopMode(STOP4); do { __asm STOP; }while (((TPMS_INTERRUPT_FLAG & KBI_INTERRUPT_FLAG) != KBI_INTERRUPT_FLAG) && (TPMS_INTERRUPT_FLAG & RTI_INTERRUPT_FLAG) != RTI_INTERRUPT_FLAG); // We exited the loop, disable KBI vfnKbiDisable(); // Check if the MKW is ready or if we woke up on timeout if ((TPMS_INTERRUPT_FLAG & KBI_INTERRUPT_FLAG) == KBI_INTERRUPT_FLAG) u8status = 0; // Acknowledge received else u8status = 1; // Acknowledge not received // Clear the KBI flag - RTI flag will be cleared in vfnDisableTimeout() TPMS_INTERRUPT_FLAG &= ~KBI_INTERRUPT_FLAG; } else { // Undefined power mode, return error u8status = 1; } vfnDisableTimeout(); return u8status; } /************************************************************************************** * Description: Takes and stores sensor data, enables SPI, wakes up the MKW and waits * for the acknowledge. When received, the wake up pin is lowered and CPU is * halted to prevent memory contention issues. * Before exiting the function, SPI is disabled. * Input: void * Output: void ***************************************************************************************/ void vfnTriggerDataTransfer (void) { /* Take sensor measurements first, while the MKW is still in sleep to save power */ vfnStoreSensorData(); /* Enable SPI */ SIMOPT1_SPIEN = 1; /* It is time for the MKW to read the data => wake up the MKW */ WAKEUP_PIN_HIGH; /* Wait for the MKW to indicate it is ready to start the transfers * We wait in STOP4 to save power. We have already enabled STOP4 for * the sensor measurements */ if (0 == u8WaitForMkwAck(STOP4_MODE)) { /* Acknowledge by lowering the pin */ WAKEUP_PIN_LOW; /* Halt the CPU to prevent memory contention issues during SPI transfers. * The CPU will resume when MKW clears the bit or on watchdog timeout. * When watchdog timeout occurs, the program restarts from the beginning * of the main */ SPIOPS_CORE_TR_HOLD = 1; } else // MKW has not acknowledged => transfers are cancelled { /* Lower the pin before going back to sleep */ WAKEUP_PIN_LOW; } /* Disable SPI */ SIMOPT1_SPIEN = 0; return; } /************************************************************************************** * Description: Performs the sensor measurements and stores them in the data array * Input: void * Output: void ***************************************************************************************/ void vfnStoreSensorData (void) { UINT8 u8index; /* Clear array index */ u8index = 0; #if (ADV_ON_MOVEMENT == 1) /* Clear accel X value in case it is not measured. If measured, value will be overwritten */ //gu16CompAccelX = 0; /* When we are here, we have already taken raw V, raw T and comp Z for movement detection. * We still have to take comp P and compensate V and T. * We have already enabled STOP4 mode. * Note that compensated T is necessary for the WDIV calibration we will perform later */ vfnTakeRemainingSensorsMeasurements(0); /*#if (X_axis == 1) vfnTakeRemainingSensorsMeasurements(1); #else vfnTakeRemainingSensorsMeasurements(0); // We dont need accel X #endif */ //#else /* Configure STOP4 to take the measurements */ // vfnSetStopMode(STOP4); /* Clear accel X and Z values in case they are not measured. If measured, values will be overwritten */ // gu16CompAccelZ = 0; // gu16CompAccelX = 0; /* When we are here, we have not yet performed any measurement. * We can choose which sensor data to take. * Note that compensated T is necessary for the WDIV calibration we will perform later */ //#if (X_axis == 1) // vfnTakeSensorsMeasurements(TAKE_P|TAKE_V|TAKE_T|TAKE_X|COMP); // Take P, V, T, Accel X //#else // vfnTakeSensorsMeasurements(TAKE_P|TAKE_V|TAKE_T|TAKE_Z|COMP); // Take P, V, T, Accel Z //#endif #endif /* Fill the data array*/ // gau8DataArray[u8index++] = gau8TpmsId[0]; // gau8DataArray[u8index++] = gau8TpmsId[1]; // gau8DataArray[u8index++] = gau8TpmsId[2]; // gau8DataArray[u8index++] = gau8TpmsId[3]; gau8DataArray[u8index++] = 0x01;//0xcf;//gau8TpmsId[4]; gau8DataArray[u8index++] = 0x02;//0xcf;//gau8TpmsId[5]; gau8DataArray[u8index++] = 0x03;//(UINT8)(gu16CompPressure >> 8); gau8DataArray[u8index++] = 0x04;//(UINT8)(gu16CompPressure); gau8DataArray[u8index++] = 0x05;//gu8CompVolt; //(UINT8)(gu16CompAccelZ >> 8); gau8DataArray[u8index++] = 0x06;//gu8CompTemp;//(UINT8)(gu16CompAccelZ); gau8DataArray[u8index++] = 0x07;//u8Vehiclestate; //(UINT8)(gu16CompAccelX >> 8); #if (ADV_ON_MOVEMENT == 1) #if (X_axis == 1) gau8DataArray[u8index++] = 0x08;//(UINT8)(gu16CompAccelX >> 8); gau8DataArray[u8index++] = 0x09;//(UINT8)(gu16CompAccelX); #else gau8DataArray[u8index++] = (UINT8)(gu16CompAccelZ >> 8); gau8DataArray[u8index++] = (UINT8)(gu16CompAccelZ); #endif #else gau8DataArray[u8index++] = 0; gau8DataArray[u8index++] = 0; #endif //gau8DataArray[u8index++] = gu8CompTemp; return; }