Blog List:
1.Uncover the Cores: Introduction
3. Uncover the Cores: System Concept & Workflow
4. Uncover the Cores: Getting started with PSoC 62S4 Pioneer Kit
5. Uncover the Cores: Final Project
Introduction:
As explained in the previous blogs, I will go about building the final project. This will consist of using the CM0 to run CAPSENSE with CM4 on Deep Sleep. When the command is given, the CM4 will be activated to measure the ambient light and temperature around the device & also show it on the screen.
I will use the Dual-CPU IPC semaphore as the building block. I will build on this example to develop the code.
As you can see, there is a seperate code for both the CM0+ and the CM4. I will do the main task in CM0+ and when the key is pressed, CM4 will be activated.
So, CM4 code file will contain the code to read the sensor readings from the Ambient Light Sensor and the Thermistor. It will also include the code to show this on the screen and finally switch back to the CM0+. The rest of the functionality will be all on the CM0+ core for optimal power consumption.
Code:
Code for CM0+:
/********************************************************************************
* File Name: main.c
*
* Description: This is the source code for CM0+ in the the Dual CPU IPC Semaphore
* Application for ModusToolbox.
*
* Related Document: See README.md
*
*
*********************************************************************************
* Copyright 2020-2022, Cypress Semiconductor Corporation (an Infineon company) or
* an affiliate of Cypress Semiconductor Corporation. All rights reserved.
*
* This software, including source code, documentation and related
* materials ("Software") is owned by Cypress Semiconductor Corporation
* or one of its affiliates ("Cypress") and is protected by and subject to
* worldwide patent protection (United States and foreign),
* United States copyright laws and international treaty provisions.
* Therefore, you may use this Software only as provided in the license
* agreement accompanying the software package from which you
* obtained this Software ("EULA").
* If no EULA applies, Cypress hereby grants you a personal, non-exclusive,
* non-transferable license to copy, modify, and compile the Software
* source code solely for use in connection with Cypress's
* integrated circuit products. Any reproduction, modification, translation,
* compilation, or representation of this Software except as specified
* above is prohibited without the express written permission of Cypress.
*
* Disclaimer: THIS SOFTWARE IS PROVIDED AS-IS, WITH NO WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, NONINFRINGEMENT, IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. Cypress
* reserves the right to make changes to the Software without notice. Cypress
* does not assume any liability arising out of the application or use of the
* Software or any product or circuit described in the Software. Cypress does
* not authorize its products for use in any products where a malfunction or
* failure of the Cypress product may reasonably be expected to result in
* significant property damage, injury or death ("High Risk Product"). By
* including Cypress's product in a High Risk Product, the manufacturer
* of such system or application assumes all risk of such use and in doing
* so agrees to indemnify Cypress against all liability.
*********************************************************************************/
#include "cy_pdl.h"
#include "ipc_def.h"
#include <stdlib.h>
#include "cycfg.h"
#include "cyhal.h"
#include "cybsp.h"
int main(void)
{
cy_rslt_t result;
/* Initialize the device and board peripherals */
result = cybsp_init() ;
if (result != CY_RSLT_SUCCESS)
{
CY_ASSERT(0);
}
/* Enable global interrupts */
__enable_irq();
/* Lock the sempahore to wait for CM4 to be init */
Cy_IPC_Sema_Set(SEMA_NUM, false);
/* Enable CM4. CY_CORTEX_M4_APPL_ADDR must be updated if CM4 memory layout is changed. */
Cy_SysEnableCM4(CY_CORTEX_M4_APPL_ADDR);
/* Wait till CM4 unlocks the semaphore */
do
{
__WFE();
}
while (Cy_IPC_Sema_Status(SEMA_NUM) == CY_IPC_SEMA_STATUS_LOCKED);
/* Update clock settings */
SystemCoreClockUpdate();
for (;;)
{
/* Check if the button is pressed */
if (Cy_GPIO_Read(CYBSP_SW2_PORT, CYBSP_SW2_PIN) == 0)
{
#if ENABLE_SEMA
if (Cy_IPC_Sema_Set(SEMA_NUM, false) == CY_IPC_SEMA_SUCCESS)
#endif
{
/* Print a message to the console */
Cy_SCB_UART_PutString(CYBSP_UART_HW, "Running CAPSENSE ON CM0+\r\n");
initialize_led();
initialize_capsense_tuner();
/* Initialize CapSense */
result = initialize_capsense();
if (CYRET_SUCCESS != result)
{
/* Halt the CPU if CapSense initialization failed */
CY_ASSERT(0);
}
/* Initiate first scan */
Cy_CapSense_ScanAllWidgets(&cy_capsense_context);
for (;;)
{
if (capsense_scan_complete)
{
/* Process all widgets */
Cy_CapSense_ProcessAllWidgets(&cy_capsense_context);
/* Process touch input */
process_touch();
/* Establishes synchronized operation between the CapSense
* middleware and the CapSense Tuner tool.
*/
Cy_CapSense_RunTuner(&cy_capsense_context);
/* Initiate next scan */
Cy_CapSense_ScanAllWidgets(&cy_capsense_context);
capsense_scan_complete = false;
}
}
}
#if ENABLE_SEMA
while (CY_IPC_SEMA_SUCCESS != Cy_IPC_Sema_Clear(SEMA_NUM, false));
#endif
}
}
}
}
/*******************************************************************************
* Function Name: initialize_capsense
********************************************************************************
* Summary:
* This function initializes the CapSense and configure the CapSense
* interrupt.
* Parameters:
* none
*
* Return
* uint32_t status - status of operation
*
*******************************************************************************/
static uint32_t initialize_capsense(void)
{
uint32_t status = CYRET_SUCCESS;
/* CapSense interrupt configuration parameters */
static const cy_stc_sysint_t capSense_intr_config =
{
.intrSrc = NvicMux3_IRQn,
.cm0pSrc = csd_interrupt_IRQn,
.intrPriority = CAPSENSE_INTR_PRIORITY,
};
/* Capture the CSD HW block and initialize it to the default state. */
status = Cy_CapSense_Init(&cy_capsense_context);
if (CYRET_SUCCESS != status)
{
return status;
}
/* Initialize CapSense interrupt */
Cy_SysInt_Init(&capSense_intr_config, capsense_isr);
NVIC_ClearPendingIRQ(capSense_intr_config.intrSrc);
NVIC_EnableIRQ(capSense_intr_config.intrSrc);
/* Initialize the CapSense firmware modules. */
status = Cy_CapSense_Enable(&cy_capsense_context);
if (CYRET_SUCCESS != status)
{
return status;
}
/* Assign a callback function to indicate end of CapSense scan. */
status = Cy_CapSense_RegisterCallback(CY_CAPSENSE_END_OF_SCAN_E,
capsense_callback, &cy_capsense_context);
if (CYRET_SUCCESS != status)
{
return status;
}
return status;
}
/*******************************************************************************
* Function Name: capsense_isr
********************************************************************************
* Summary:
* Wrapper function for handling interrupts from CapSense block.
*
* Parameters:
* none
*
* Return
* none
*
*******************************************************************************/
static void capsense_isr(void)
{
Cy_CapSense_InterruptHandler(CYBSP_CSD_HW, &cy_capsense_context);
}
/*******************************************************************************
* Function Name: ezi2c_isr
********************************************************************************
* Summary:
* Wrapper function for handling interrupts from EZI2C block.
*
*******************************************************************************/
static void ezi2c_isr(void)
{
Cy_SCB_EZI2C_Interrupt(CYBSP_EZI2C_HW, &ezi2c_context);
}
/*******************************************************************************
* Function Name: capsense_callback()
********************************************************************************
* Summary:
* This function sets a flag to indicate end of a CapSense scan.
*
* Parameters:
* cy_stc_active_scan_sns_t* : pointer to active sensor details.
*
* Return
* none
*
*******************************************************************************/
static void capsense_callback(cy_stc_active_scan_sns_t * ptrActiveScan)
{
capsense_scan_complete = true;
}
/*******************************************************************************
* Function Name: process_touch
********************************************************************************
* Summary:
* Gets the details of touch position detected, processes the touch input
* and updates the LED status.
*
* Parameters:
* none
*
* Return
* none
*
*******************************************************************************/
static void process_touch(void)
{
uint32_t button0_status;
uint32_t button1_status;
cy_stc_capsense_touch_t *slider_touch_info;
uint16_t slider_pos;
uint8_t slider_touch_status;
bool led_update_req = false;
static uint32_t button0_status_prev;
static uint32_t button1_status_prev;
static uint16_t slider_pos_prev;
static led_data_t led_data = {LED_ON, LED_MAX_BRIGHTNESS};
/* Get button 0 status */
button0_status = Cy_CapSense_IsSensorActive(
CY_CAPSENSE_BUTTON0_WDGT_ID,
CY_CAPSENSE_BUTTON0_SNS0_ID,
&cy_capsense_context);
/* Get button 1 status */
button1_status = Cy_CapSense_IsSensorActive(
CY_CAPSENSE_BUTTON1_WDGT_ID,
CY_CAPSENSE_BUTTON0_SNS0_ID,
&cy_capsense_context);
/* Get slider status */
slider_touch_info = Cy_CapSense_GetTouchInfo(
CY_CAPSENSE_LINEARSLIDER0_WDGT_ID, &cy_capsense_context);
slider_touch_status = slider_touch_info->numPosition;
slider_pos = slider_touch_info->ptrPosition->x;
/* Detect new touch on Button0 */
if((0u != button0_status) &&
(0u == button0_status_prev))
{
/* Turn USER LED ON */
led_data.state = LED_ON;
led_update_req = true;
}
/* Detect new touch on Button1 */
if((0u != button1_status) &&
(0u == button1_status_prev))
{
/* Turn the USER LED off */
led_data.state = LED_OFF;
led_update_req = true;
}
/* Detect the new touch on slider */
if ((0 != slider_touch_status) &&
(slider_pos != slider_pos_prev))
{
led_data.brightness = (slider_pos * 100)
/ cy_capsense_context.ptrWdConfig[CY_CAPSENSE_LINEARSLIDER0_WDGT_ID].xResolution;
led_update_req = true;
}
/* Update the LED state if requested */
if (led_update_req)
{
update_led_state(&led_data);
}
/* Update previous touch status */
button0_status_prev = button0_status;
button1_status_prev = button1_status;
slider_pos_prev = slider_pos;
}
/*******************************************************************************
* Function Name: initialize_capsense_tuner
********************************************************************************
* Summary:
* Initializes interface between Tuner GUI and PSoC 6 MCU.
*
* Parameters:
* none
*
* Return
* none
*
*******************************************************************************/
static void initialize_capsense_tuner(void)
{
/* EZI2C interrupt configuration structure */
static const cy_stc_sysint_t ezi2c_intr_config =
{
.intrSrc = NvicMux2_IRQn,
.cm0pSrc = CYBSP_EZI2C_IRQ,
.intrPriority = EZI2C_INTR_PRIORITY,
};
/* Initialize EZI2C */
Cy_SCB_EZI2C_Init(CYBSP_EZI2C_HW, &CYBSP_EZI2C_config, &ezi2c_context);
/* Initialize and enable EZI2C interrupts */
Cy_SysInt_Init(&ezi2c_intr_config, ezi2c_isr);
NVIC_EnableIRQ(ezi2c_intr_config.intrSrc);
/* Set up communication data buffer to CapSense data structure to be exposed
* to I2C master at primary slave address request.
*/
Cy_SCB_EZI2C_SetBuffer1(CYBSP_EZI2C_HW, (uint8 *)&cy_capsense_tuner,
sizeof(cy_capsense_tuner), sizeof(cy_capsense_tuner),
&ezi2c_context);
/* Enable EZI2C block */
Cy_SCB_EZI2C_Enable(CYBSP_EZI2C_HW);
}
/* [] END OF FILE */
Code for CM4:
/*******************************************************************************
* File Name: main.c
*
* Description: This is the source code for CM4 in the the Dual CPU IPC Semaphore
* Application for ModusToolbox.
*
* Related Document: See README.md
*
*
********************************************************************************
* Copyright 2020-2022, Cypress Semiconductor Corporation (an Infineon company) or
* an affiliate of Cypress Semiconductor Corporation. All rights reserved.
*
* This software, including source code, documentation and related
* materials ("Software") is owned by Cypress Semiconductor Corporation
* or one of its affiliates ("Cypress") and is protected by and subject to
* worldwide patent protection (United States and foreign),
* United States copyright laws and international treaty provisions.
* Therefore, you may use this Software only as provided in the license
* agreement accompanying the software package from which you
* obtained this Software ("EULA").
* If no EULA applies, Cypress hereby grants you a personal, non-exclusive,
* non-transferable license to copy, modify, and compile the Software
* source code solely for use in connection with Cypress's
* integrated circuit products. Any reproduction, modification, translation,
* compilation, or representation of this Software except as specified
* above is prohibited without the express written permission of Cypress.
*
* Disclaimer: THIS SOFTWARE IS PROVIDED AS-IS, WITH NO WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, NONINFRINGEMENT, IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. Cypress
* reserves the right to make changes to the Software without notice. Cypress
* does not assume any liability arising out of the application or use of the
* Software or any product or circuit described in the Software. Cypress does
* not authorize its products for use in any products where a malfunction or
* failure of the Cypress product may reasonably be expected to result in
* significant property damage, injury or death ("High Risk Product"). By
* including Cypress's product in a High Risk Product, the manufacturer
* of such system or application assumes all risk of such use and in doing
* so agrees to indemnify Cypress against all liability.
********************************************************************************/
#include "cy_pdl.h"
#include "cyhal.h"
#include "cybsp.h"
#include "ipc_def.h"
#include "cy_retarget_io.h"
/*******************************************************************************
* Macros
********************************************************************************/
/* Defines for the ADC channels */
#define THERMISTOR_SENSOR_CHANNEL (1)
#define REF_RESISTOR_CHANNEL (0)
#define ALS_SENSOR_CHANNEL (2)
/* Number of channels used */
#define CHANNEL_COUNT (3)
/* Reference resistor in series with the thermistor is of 10kohm */
#define R_REFERENCE (float)(10000)
/* Beta constant of NCP18XH103F03RB thermistor is 3380 Kelvin. See the thermistor
data sheet for more details. */
#define B_CONSTANT (float)(3380)
/* Resistance of the thermistor is 10K at 25 degrees C (from the data sheet)
Therefore R0 = 10000 Ohm, and T0 = 298.15 Kelvin, which gives
R_INFINITY = R0 e^(-B_CONSTANT / T0) = 0.1192855 */
#define R_INFINITY (float)(0.1192855)
/* Zero Kelvin in degree C */
#define ABSOLUTE_ZERO (float)(-273.15)
/* ALS offset in Percent */
/* To configure this value, begin with offset of 0 and note down the lowest ALS
percent value. Configure the ALS_OFFSET with the lowest observed ALS percent. */
#define ALS_OFFSET (20)
/* ALS low threshold value - if ALS percentage is lower than this value, user
* LED is turned ON */
#define ALS_LOW_THRESHOLD (45)
/* ALS high threshold value - if ALS percentage is higher than this value, user
* LED is turned OFF */
#define ALS_HIGH_THRESHOLD (55)
/*******************************************************************************
* Function Prototypes
********************************************************************************/
/* Function to convert the measured voltage in the thermistor circuit into
* temperature */
double get_temperature(int32 therm_count, int32 ref_count);
/* Function to convert the measured voltage in the ALS circuit into percentage */
uint8 get_light_intensity(int32 adc_count);
/* IIR Filter implementation */
int32 low_pass_filter(int32 input, uint8 data_source);
/* FIFO Interrupt Handler */
void sar_fifo_interrupt_handler(void);
/* Function to initialize analog resources */
/* Resources include SAR ADC and its associated FIFO, analog references and
deep sleep resources */
void init_analog_resources(void);
/*******************************************************************************
* Global Variables
********************************************************************************/
/* IIR Filter variables */
int32 filt_var[CHANNEL_COUNT];
/* FIFO interrupt configuration structure */
/* Source is set to FIFO 0 and Priority as 7 */
const cy_stc_sysint_t fifo_irq_cfg = {
.intrSrc = (IRQn_Type) pass_interrupt_fifo_0_IRQn,
.intrPriority = 7
};
/* This flag is set in the FIFO interrupt handler */
volatile uint8 fifo_intr_flag = false;
#if ENABLE_SEMA
#define LED_STATE CYBSP_LED_STATE_OFF
#else
#define LED_STATE CYBSP_LED_STATE_ON
#endif
int main(void)
{
cy_rslt_t result = CY_RSLT_SUCCESS;
/* Initialize the device and board peripherals */
result = cybsp_init();
if (result != CY_RSLT_SUCCESS)
{
CY_ASSERT(0);
}
/* Enable global interrupts */
__enable_irq();
/* Free the hardware instance object iff initialized by other core
* before initializing the same hardware instance object in this core. */
cyhal_hwmgr_free(&CYBSP_UART_obj);
cyhal_hwmgr_free(&CYBSP_DEBUG_UART_RX_obj);
cyhal_hwmgr_free(&CYBSP_DEBUG_UART_TX_obj);
cyhal_hwmgr_free(&CYBSP_SW2_obj);
/* Initialize retarget-io to use the debug UART port. */
result = cy_retarget_io_init(CYBSP_DEBUG_UART_TX, CYBSP_DEBUG_UART_RX,
CY_RETARGET_IO_BAUDRATE);
CY_ASSERT(result == CY_RSLT_SUCCESS);
/* Initialize the User Button */
result = cyhal_gpio_init(CYBSP_USER_BTN, CYHAL_GPIO_DIR_INPUT, CYHAL_GPIO_DRIVE_PULLUP, CYBSP_BTN_OFF);
CY_ASSERT(result == CY_RSLT_SUCCESS);
/* Initialize the User LED */
result = cyhal_gpio_init(CYBSP_USER_LED, CYHAL_GPIO_DIR_OUTPUT, CYHAL_GPIO_DRIVE_STRONG, LED_STATE);
CY_ASSERT(result == CY_RSLT_SUCCESS);
/* Configure P6[5] - JTAG Data to Analog High Z to avoid leakage current */
/* This pin is logic high by default which causes leakage current on CY8CKIT-062S4 Pioneer Kit. */
cyhal_gpio_configure(P6_5, CYHAL_GPIO_DIR_OUTPUT, CYHAL_GPIO_DRIVE_ANALOG);
/* Variable to capture return value of functions */
cy_rslt_t result;
/* FIFO read structure */
cy_stc_sar_fifo_read_t fifo_data = {0};
/* Variable for filtered reference voltage (thermistor circuit) and als data */
int32 filtered_data[CHANNEL_COUNT];
/* Temperature value in deg C */
double temperature;
/* Light intensity in percentage */
uint8 light_intensity;
/* Variable to initialize IIR filter for the first iteration */
uint8 first_run[CHANNEL_COUNT]= {true, true, true};
/* Variable for number of samples accumulated in FIFO */
uint8 data_count;
uint16 display_delay = 0;
/* Unlock the semaphore and wake-up the CM0+ */
Cy_IPC_Sema_Clear(SEMA_NUM, false);
__SEV();
/* \x1b[2J\x1b[;H - ANSI ESC sequence for clear screen */
printf("\x1b[2J\x1b[;H");
printf("****************** Starting the Device ****************** \r\n\n");
printf("Press the user button to toggle between CM4 or CM0+\r\n\n");
for (;;)
{
if (cyhal_gpio_read(CYBSP_USER_BTN) == CYBSP_BTN_PRESSED)
{
#if ENABLE_SEMA
/* Attempt to lock the semaphore */
if (Cy_IPC_Sema_Set(SEMA_NUM, false) == CY_IPC_SEMA_SUCCESS)
#endif
{
/* Print a message to the console */
printf("Taking Reading of Ambient Light and Temperature\r\n");
/* Enable the timer to start the sampling process */
/* Using the device configurator, trigger interval from the timer is
* set to 2.5ms which results in effective scan rate of 400sps for the SAR ADC.
*/
Cy_SysAnalog_TimerEnable(PASS);
for (;;)
{
/* Wait till printf completes the UART transfer */
while(cyhal_uart_is_tx_active(&cy_retarget_io_uart_obj) == true);
/* Put the device to deep-sleep mode. Device wakes up with the level interrupt from FIFO.
With the effective scan rate of 400sps, level count of 120 and 3 channels, device
wakes up every 120/(400*3) seconds, that is, 100ms. */
Cy_SysPm_CpuEnterDeepSleep(CY_SYSPM_WAIT_FOR_INTERRUPT);
/* Check if the interrupt is from the FIFO */
if(fifo_intr_flag)
{
/* Clear the flag */
fifo_intr_flag = false;
/* Check how many entries to be read. Should be equal to (LEVEL+1) when level
* interrupt is enabled */
data_count = Cy_SAR_FifoGetDataCount(SAR0);
/* Take all the readings from the FIFO and feed through IIR Filter */
while(data_count > 0)
{
data_count--;
/* Read the FIFO */
Cy_SAR_FifoRead(SAR0, &fifo_data);
/* If it is the first time reading the data, initialize the IIR filter
* variable and result variable */
if(first_run[fifo_data.channel] == true)
{
filtered_data[fifo_data.channel] = fifo_data.value;
filt_var[fifo_data.channel] = fifo_data.value << 8;
/* Clear the flag */
first_run[fifo_data.channel] = false;
}
else /* Push the data to the IIR filter */
filtered_data[fifo_data.channel] = low_pass_filter((int16)fifo_data.value, fifo_data.channel);
}
/* Calculate the temperature value */
temperature = get_temperature(filtered_data[THERMISTOR_SENSOR_CHANNEL], filtered_data[REF_RESISTOR_CHANNEL]);
/* Calculate the ambient light intensity in percentage */
light_intensity = get_light_intensity(filtered_data[ALS_SENSOR_CHANNEL]);
/* Control the LED */
if(light_intensity < ALS_LOW_THRESHOLD)
cyhal_gpio_write(CYBSP_USER_LED2, CYBSP_LED_STATE_ON);
else
if(light_intensity > ALS_HIGH_THRESHOLD)
cyhal_gpio_write(CYBSP_USER_LED2, CYBSP_LED_STATE_OFF);
/* Send over UART every 500ms */
if(display_delay == 4)
{
/* Print the temperature and the ambient light value*/
printf("Temperature: %2.1lfC Ambient Light: %d%%\r\n", temperature, light_intensity);
/* Clear the counter */
display_delay = false;
}
else /* Increment the counter */
display_delay++;
}
}
}
#if ENABLE_SEMA
while (CY_IPC_SEMA_SUCCESS != Cy_IPC_Sema_Clear(SEMA_NUM, false));
#endif
}
}
}
}
/* [] END OF FILE */
Summary:
It was a great journey working with the PSoC 62S4 kit. It was a bit challenging and a new thing that I learned especially working with 2 cores & inter core communication.
Hopefully, it was fun & exciting for everyone reading!