nRF9160: Porting the modem library to work with bare metal application

I would like some help with porting the modem library (nrf_modem_lib) to work with my bare metal application.

Besides a custom nrf_modem_os.c, I have made a slightly modified version of nrfx_ipc.c that explicitly uses the non-secure registers for the IPC peripheral along removing various dependencies on the nrfx lib glue, since I would like to have as little nrfx-dependent code as possible in my project.

Be aware that my project is single-threaded, so I do not want to use actual threads - that is also why I have not implemented the semaphore related functions in nrf_modem_os.c.

Bootloader and memory layout

I have implemented a simple bootloader that configures non-secure access to various FLASH and RAM regions, enables non-secure access to various peripherals including the IPC and EGU1, as required by the modem library.

The bootloader then enters non-secure mode and boots up the application image, located at address 0x10000 in the FLASH memory. This all works fine, and I can use the UARTE0 and GPIO peripherals in non-secure mode just fine.

The lower 64 kiB of FLASH and RAM are (for now) reserved for the secure bootloader. The rest is reserved for the application and configured as non-secure during boot. This is reflected in the custom linker scripts for each image (included below).

Furthermore, the lower 32 kiB of the RAM reserved for the application is used as shared memory for the modem library. This is also reflected in the linker scripts and defs.h included below. This should make malloc() and free() operate above the shared modem memory. For allocation inside the shared memory, I have implemented a custom allocator (not included below) that only operates inside the TX region of the shared memory.

The application and the problem

In my application main() function, I call nrf_modem_init() to initialize the modem library - but it never returns.

It does appear to call my custom nrf_modem_os_init() and return back to the nrf_modem_init() function. Before that returns, it seems to get stuck in a loop calling my custom implementation of nrf_modem_os_timedwait(). Using GDB (output included below) it appears to call IPC and RPC related stuff in between the calls to nrf_modem_os_timedwait().

I would like to have my custom nrf_modem_os.c and nrfx_ipc.c reviewed. In particular, I may have misunderstood how nrf_modem_os_timedwait() should be implemented and/or how to configure the IPC and EGU1 interrupts appropriately.

As I understand it, nrf_modem_os_timedwait() should block (not return) until either a timeout occurs or until nrf_modem_os_event_notify() is called, right? The timeout is at the moment implemented in a very crude fashion, but I expect to use an actual timer in the nRF9160 for this purpose later on, if necessary.

Hopefully I can get some hints on what is (or could be) wrong, so I can end up with a nrf_modem_init() call that does not get stuck in a loop. Hopefully I can then move on to test AT command communication :-)

I have included what I believe are the important and relevant files below.

I am using modem firmware version 1.3.3. The version of the SDK and build tools are indicated in the Makefile below.

Note: The documentation found online at https://developer.nordicsemi.com/nRF_Connect_SDK/doc/latest/nrfxlib/nrf_modem/doc/ug_nrf_modem_porting_os.html seems to be outdated or incomplete compared to the .rst files found in the sdk-nrfxlib on Github: https://github.com/nrfconnect/sdk-nrfxlib.

boot.ld

/* Linker script to configure memory regions. */

SEARCH_DIR(.)
GROUP(-lgcc -lc -lnosys)

MEMORY
{
  FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x10000
  RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x10000
}


INCLUDE "nrf_common.ld"

app.ld

/* Linker script to configure memory regions. */

SEARCH_DIR(.)
GROUP(-lgcc -lc -lnosys)

MEMORY
{
  FLASH (rx) : ORIGIN = 0x00010000, LENGTH = 0xF0000
  RAM (rwx) : ORIGIN = 0x20018000, LENGTH = 0x26000
}


INCLUDE "nrf_common.ld"

boot/main.c

// MAIN (secure bootloader)                                     PVH, 2023-01-26
#include "nrfx.h"
#include <arm_cmse.h>

// Typedef for non-secure function call
typedef int __attribute__((cmse_nonsecure_call)) nsfunc(void);

int main()
{
    // Ensure that non-secure access is permitted to all FLASH above 64k
    // (each FLASH region is 32 KiB)
    for (uint32_t i = 2; i < 32; ++i)
        NRF_SPU_S->FLASHREGION[i].PERM &= 
            ~(1 << SPU_FLASHREGION_PERM_SECATTR_Pos);
  
    // Ensure that non-secure access is permitted to all RAM above 64k
    // (each RAM region is 8 KiB)
    for (uint32_t i = 8; i < 32; ++i)
        NRF_SPU_S->RAMREGION[i].PERM &= ~(1 << SPU_RAMREGION_PERM_SECATTR_Pos);
  
    // Ensure that non-secure access is permitted to peripherals
    const uint32_t field = (1 << SPU_PERIPHID_PERM_SECATTR_Pos);
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_CLOCK_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_POWER_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_UARTE0_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_TIMER0_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_TIMER1_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_EGU1_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_IPC_NS)].PERM &= ~field;
    NRF_SPU_S->PERIPHID[NRFX_PERIPHERAL_ID_GET(NRF_P0_NS)].PERM &= ~field;
    
    // Allow non-secure use of all GPIOs
    NRF_SPU_S->GPIOPORT[0].PERM = 0x00000000ul;
    
    // Boot the non-secure application image located at address 0x10000
    SCB_NS->VTOR = 0x10000ul;
    uint32_t* vtor = (uint32_t*)0x10000ul;
    __TZ_set_MSP_NS(vtor[0]);
    nsfunc *ns_reset = (nsfunc*)(vtor[1]); // Pointer to non-secure ResetHandler
    ns_reset();
}

app/main.c

// MAIN (non-secure application)                                PVH, 2023-01-26
#include "defs.h"
#include "delay.h"
#include <string.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdarg.h>

#include "nrfx.h"
#include <nrf_modem.h>

// Initialize UARTE0 for the virtual COM port on the nRF9160 DK
void uarte0_init()
{
    // The primary virtual COM port on nRF9160 DK is using the following pins:
    // P0.26 CTS, P0.27 RTS, P0.28 RXD and P0.29 TXD
    
    // Configure the GPIOs
    NRF_P0_NS->DIRCLR = (1<<28) | (1<<26); // Set RXD and CTS pins as inputs
    NRF_P0_NS->DIRSET = (1<<29) | (1<<27); // Set TXD and RTS pins as outputs
    NRF_P0_NS->OUTSET = (1<<29) | (1<<29); // Set TXD and RTS pins high

    
    // Route the UARTE0 pins to the above GPIOs
    NRF_UARTE0_NS->PSEL.CTS = 26;
    NRF_UARTE0_NS->PSEL.RTS = 27;
    NRF_UARTE0_NS->PSEL.RXD = 28;
    NRF_UARTE0_NS->PSEL.TXD = 29;
    
    // Configure the UART with no hardware flow control, no parity bit, one
    // stop bit and a baud rate of 115200.
    NRF_UARTE0_NS->CONFIG = 0;
    NRF_UARTE0_NS->BAUDRATE = 0x01D60000ul;

    // Enable the UART
    NRF_UARTE0_NS->ENABLE = UARTE_ENABLE_ENABLE_Enabled 
        << UARTE_ENABLE_ENABLE_Pos;
}

// Quick and dirty function that transmits formatted string through UARTE0
void uarte0_printf(const char* str, ...)
{
    static char data[1024];
    
    va_list args;
    va_start (args, str);
    vsprintf (data, str, args);
    va_end (args);
    
    // Set up DMA parameters
    NRF_UARTE0_NS->TXD.MAXCNT = (uint32_t)strlen(data);
    NRF_UARTE0_NS->TXD.PTR = (uint32_t)data;
    
    // Transmit the string
    NRF_UARTE0_NS->TASKS_STARTTX = 1;      // Start the transmission
    while (! NRF_UARTE0_NS->EVENTS_ENDTX); // Wait for transmission to finish
    NRF_UARTE0_NS->EVENTS_ENDTX = 0;       // Clear the ENDTX event
}

// Fault handler for the modem
void nrf_modem_fault_handler(struct nrf_modem_fault_info* fault_info)
{
    uarte0_printf("MODEM FAULT: reason = 0x%lx, program_counter = 0x%lx",
        fault_info->reason, fault_info->program_counter);
}

int main()
{
    
    // Use the HFXO as the high frequency clock
    NRF_CLOCK_NS->TASKS_HFCLKSTART = 1;
    while (! NRF_CLOCK_NS->EVENTS_HFCLKSTARTED); // Wait for the clock to start
    NRF_CLOCK_NS->EVENTS_HFCLKSTARTED = 0;

    uarte0_init();
    
    uarte0_printf("Hello from application!\r\n\r\n");

    // Initialize the modem
    int ret = nrf_modem_init(nrf_modem_get_init_params(), NORMAL_MODE);
    uarte0_printf("nrf_modem_init() returned %d\r\n", ret);
    
    // Make some LEDs blink to indicate that the app is running
    // LED1..4 on the nRF9160 DK are connected to P0.02..P0.05 and are active 
    // high, so we first configure these pins on P0 as outputs
    NRF_P0_NS->DIRSET = (1<<5) | (1<<4) | (1<<3) | (1<<2);

    while (1)
    {
        // In the main loop, we make each of the LEDs light up one at a time
        for (uint32_t i = 0; i < 4; ++i)
        {
            NRF_P0_NS->OUTSET = 1<<(i+2);
            delay_ms(500);
            NRF_P0_NS->OUTCLR = 1<<(i+2);
        }    
    }

    
}

app/defs.h

// DEFS header                                                  PVH, 2023-01-24
#ifndef DEFS_H
#define DEFS_H

// Define the addresses and sizes of the various regions in the shared memory
// for use with the nRF Modem Library. THIS SHOULD MATCH THE LINKER SCRIPT!!!
#define NRF_MODEM_SHMEM_CTRL_BASE  0x20010000
// NRF_MODEM_SHMEM_CTRL_SIZE is already set to 0x4e8 in nrf_modem_platform.h
#define NRF_MODEM_SHMEM_TX_BASE    0x200104e8
#define NRF_MODEM_SHMEM_TX_SIZE    0x00004000
#define NRF_MODEM_SHMEM_RX_BASE    0x200144e8
#define NRF_MODEM_SHMEM_RX_SIZE    0x00002000
#define NRF_MODEM_SHMEM_TRACE_BASE 0x200164E8
#define NRF_MODEM_SHMEM_TRACE_SIZE 0x00000000

#include <nrf_modem_platform.h> // Definition of modem IRQs and other stuff
#include <nrf_modem.h>  // Definition of struct nrf_modem_fault_into

#ifdef __cplusplus
extern "C" {
#endif

// Definition of modem fault handler
void nrf_modem_fault_handler(struct nrf_modem_fault_info* fault_info);
const struct nrf_modem_init_params* nrf_modem_get_init_params();

#ifdef __cplusplus
}
#endif

#endif

app/nrf_modem_os.c

// NRF_MODEM_OS implementation                                  PVH, 2023-01-26
// Custom nrf_modem_os.c file that implements the functions defined in the
// nrf_modem_os.h header found in the sdk-nrfxlib
#include <nrf_modem.h>
#include <nrf_modem_os.h>
#include <nrfx_ipc.h> 
#include <nrf_errno.h>
#include <nrf.h>
#include "errno.h"

#include "defs.h"    // Constants and definition of fault handler function etc.
#include "delay.h"   // For use in nrf_modem_os_busywait()
#include "dyma.h"    // For dynamic memory allocation within the TX shared mem.
#include <stdlib.h>  // For malloc, free
#include <stdbool.h> // For bool

volatile bool nrf_modem_os_inside_isr;  // True while in ISR otherwise false
volatile bool nrf_modem_os_wakeup;  // Set true when a "thread" should wake up

static const struct nrf_modem_init_params init_params =
{
        .ipc_irq_prio = NRF_MODEM_NETWORK_IRQ_PRIORITY,
        .shmem.ctrl = {
                .base = NRF_MODEM_SHMEM_CTRL_BASE,
                .size = NRF_MODEM_SHMEM_CTRL_SIZE,
        },
        .shmem.tx = {
                .base = NRF_MODEM_SHMEM_TX_BASE,
                .size = NRF_MODEM_SHMEM_TX_SIZE,
        },
        .shmem.rx = {
                .base = NRF_MODEM_SHMEM_RX_BASE,
                .size = NRF_MODEM_SHMEM_RX_SIZE,
        },
        .shmem.trace = {
                .base = NRF_MODEM_SHMEM_TRACE_BASE,
                .size = NRF_MODEM_SHMEM_TRACE_SIZE,
        },
        .fault_handler = nrf_modem_fault_handler
};

const struct nrf_modem_init_params* nrf_modem_get_init_params()
{
    return &init_params;
}


void IPC_IRQHandler()
{
    nrf_modem_os_inside_isr = true;
    nrfx_ipc_irq_handler();
	nrf_modem_os_event_notify();
	nrf_modem_os_inside_isr = false;
}

void EGU1_IRQHandler()
{
    nrf_modem_os_inside_isr = true;
    nrf_modem_application_irq_handler();
    nrf_modem_os_event_notify();
    nrf_modem_os_inside_isr = false;
}

void nrf_modem_os_init(void)
{
    /* Initialize the glue layer and required peripherals. */
   
    // Initialize dynamic memory allocation for the TX region in shared memory
    dyma_init((void*)NRF_MODEM_SHMEM_TX_BASE, NRF_MODEM_SHMEM_TX_SIZE);
    
    // Configure and enable soft IRQ (EGU1, priority 6, defined in 
    // nrf_modem_platform.h)
    NVIC_SetPriority(NRF_MODEM_APPLICATION_IRQ, 
        NRF_MODEM_APPLICATION_IRQ_PRIORITY);
    NVIC_ClearPendingIRQ(NRF_MODEM_APPLICATION_IRQ);
    NVIC_EnableIRQ(NRF_MODEM_APPLICATION_IRQ);
    
    nrf_modem_os_inside_isr = false;
}

void nrf_modem_os_shutdown(void)
{
    /* Deinitialize the glue layer.
       When shutdown is called, all pending calls to nrf_modem_os_timedwait
       shall exit and return -NRF_ESHUTDOWN. */

}

void* nrf_modem_os_shm_tx_alloc(size_t bytes)
{
    /* Allocate a buffer on the TX area of shared memory. */
    return dyma_alloc((void*)NRF_MODEM_SHMEM_TX_BASE, bytes);
}

void nrf_modem_os_shm_tx_free(void* mem)
{
    /* Free a shared memory buffer in the TX area. */
    dyma_free(mem);
}

void* nrf_modem_os_alloc(size_t bytes)
{
    /* Allocate a buffer on the library heap. */
    return malloc(bytes);
}

void nrf_modem_os_free(void* mem)
{
    /* Free a memory buffer in the library heap. */
    free(mem);
}

void nrf_modem_os_busywait(int32_t usec)
{
    /* Busy wait for a given amount of microseconds. */
    delay_us(usec);
}

int32_t nrf_modem_os_timedwait(uint32_t context, int32_t* timeout)
{
    if (! nrf_modem_is_initialized())
    {
        return -NRF_ESHUTDOWN;
    }

    /* Put a thread to sleep for a specific time or until an event occurs.
       Wait for the timeout.
       All waiting threads shall be woken by nrf_modem_event_notify.
       A blind return value of zero will cause a blocking wait. */
       
    nrf_modem_os_wakeup = false;
    
    // Wait until a timeout of approximately *timeout milliseconds or until
    // woken up by nrf_modem_os_event_notify()
    volatile uint32_t k = *timeout*4000;
    if (*timeout < 0)
        k = 0xFFFFFFFFul;   // Not infinite but pretty long timeout
        
    while (k > 0)
    {
        // If nrf_modem_os_event_notify() is called, wake up and return
        // the remaining time in *timeout
        if (nrf_modem_os_wakeup)
        {
            nrf_modem_os_wakeup = false;
            *timeout = k / 4000;
            break;
        }
        
        // Countdown the time
        k--;
    }
    
    // Check if the modem has been uninitialized in the meantime
    if (! nrf_modem_is_initialized())
        return -NRF_ESHUTDOWN;
    
    // Check if while loop above was broken by a timeout
    if (k == 0)
        return -NRF_EAGAIN;

    return 0;
}

void nrf_modem_os_event_notify(void)
{
    /* Notify the application that an event has occurred.
       This shall wake all threads sleeping in nrf_modem_os_timedwait. */
       
    nrf_modem_os_wakeup = true;
}

void nrf_modem_os_errno_set(int errno_val)
{
    /* Set OS errno. */
}

bool nrf_modem_os_is_in_isr(void)
{
    /* Check if executing in interrupt context. */
    return nrf_modem_os_inside_isr;
}

int nrf_modem_os_sem_init(void** sem, unsigned int initial_count, 
    unsigned int limit)
{
    /* The function shall allocate and initialize a semaphore and return its 
       address through the `sem` parameter. If an address of an already 
       allocated semaphore is provided as an input, the allocation part is 
       skipped and the semaphore is only reinitialized. */
    return 0;
}

void nrf_modem_os_sem_give(void* sem)
{
    /* Give a semaphore. */
}

int nrf_modem_os_sem_take(void* sem, int timeout)
{
    /* Try to take a semaphore with the given timeout. */
    return 0;
}

unsigned int nrf_modem_os_sem_count_get(void* sem)
{
    /* Get a semaphore's count. */
    return 0;
}

// Set the application IRQ
void nrf_modem_os_application_irq_set()
{
    NVIC_SetPendingIRQ(EGU1_IRQn);
}

// Clear the application IRQ
void nrf_modem_os_application_irq_clear()
{
    NVIC_ClearPendingIRQ(EGU1_IRQn);
}

void nrf_modem_os_log(int level, const char* fmt, ...)
{
    /* Generic logging procedure. */
    /*
    va_list ap;
    va_start(ap, fmt);
    vprintf(fmt, ap);
    printf("\n");
    va_end(ap);
    */
}

void nrf_modem_os_logdump(int level, const char* str, const void* data, 
    size_t len)
{
    /* Log hex representation of object. */
}

app/nrfx_ipc.c

// Custom NRFX IPC implementation                               PVH, 2023-01-26
// Slightly modified version of nrfx/drivers/src/nrfx_ipc.c that is more
// independent of nrfx, and specificially uses the non-secure version of the
// NRF_IPC peripheral

/*
 * Copyright (c) 2019 - 2022, Nordic Semiconductor ASA
 * All rights reserved.
 *
 * SPDX-License-Identifier: BSD-3-Clause
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 *
 * 1. Redistributions of source code must retain the above copyright notice, 
 *    this list of conditions and the following disclaimer.
 *
 * 2. 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.
 *
 * 3. Neither the name of the copyright holder 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 HOLDER 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 <nrfx.h>

//#if NRFX_CHECK(NRFX_IPC_ENABLED)

#include <nrfx_ipc.h>

// Control block - driver instance local data.
typedef struct
{
    nrfx_ipc_handler_t handler;
    nrfx_drv_state_t   state;
    void *             p_context;
} ipc_control_block_t;

static ipc_control_block_t m_ipc_cb;

nrfx_err_t nrfx_ipc_init(uint8_t irq_priority, nrfx_ipc_handler_t handler, 
    void * p_context)
{
    NRFX_ASSERT(handler);
    if (m_ipc_cb.state != NRFX_DRV_STATE_UNINITIALIZED)
    {
        return NRFX_ERROR_ALREADY_INITIALIZED;
    }

    //NRFX_IRQ_PRIORITY_SET(IPC_IRQn, irq_priority);
    NVIC_SetPriority(IPC_IRQn, irq_priority);
    //NRFX_IRQ_ENABLE(IPC_IRQn);
    NVIC_EnableIRQ(IPC_IRQn);

    m_ipc_cb.state = NRFX_DRV_STATE_INITIALIZED;
    m_ipc_cb.handler = handler;
    m_ipc_cb.p_context = p_context;

    return NRFX_SUCCESS;
}

void nrfx_ipc_config_load(const nrfx_ipc_config_t * p_config)
{
    NRFX_ASSERT(p_config);
    NRFX_ASSERT(m_ipc_cb.state == NRFX_DRV_STATE_INITIALIZED);

    uint32_t i;
    for (i = 0; i < IPC_CONF_NUM; ++i)
    {
        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    }

    for (i = 0; i < IPC_CONF_NUM; ++i)
    {
        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
            p_config->receive_event_config[i]);
    }

    nrf_ipc_int_enable(NRF_IPC_NS, p_config->receive_events_enabled);
}

void nrfx_ipc_uninit(void)
{
    NRFX_ASSERT(m_ipc_cb.state == NRFX_DRV_STATE_INITIALIZED);

    uint32_t i;
    for (i = 0; i < IPC_CONF_NUM; ++i)
    {
        nrf_ipc_send_config_set(NRF_IPC_NS, i, 0);
    }

    for (i = 0; i < IPC_CONF_NUM; ++i)
    {
        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 0);
    }

    nrf_ipc_int_disable(NRF_IPC_NS, 0xFFFFFFFF);
    m_ipc_cb.state = NRFX_DRV_STATE_UNINITIALIZED;
}

void nrfx_ipc_receive_event_enable(uint8_t event_index)
{
    NRFX_ASSERT(m_ipc_cb.state == NRFX_DRV_STATE_INITIALIZED);
    nrf_ipc_int_enable(NRF_IPC_NS, (1UL << event_index));
}

void nrfx_ipc_receive_event_disable(uint8_t event_index)
{
    NRFX_ASSERT(m_ipc_cb.state == NRFX_DRV_STATE_INITIALIZED);
    nrf_ipc_int_disable(NRF_IPC_NS, (1UL << event_index));
}

void nrfx_ipc_receive_event_group_enable(uint32_t event_bitmask)
{
    NRFX_ASSERT(m_ipc_cb.state == NRFX_DRV_STATE_INITIALIZED);
    nrf_ipc_int_enable(NRF_IPC_NS, event_bitmask);
}

void nrfx_ipc_receive_event_group_disable(uint32_t event_bitmask)
{
    NRFX_ASSERT(m_ipc_cb.state == NRFX_DRV_STATE_INITIALIZED);
    nrf_ipc_int_disable(NRF_IPC_NS, event_bitmask);
}

void nrfx_ipc_receive_event_channel_assign(uint8_t event_index, 
    uint8_t channel_index)
{
    NRFX_ASSERT(channel_index < IPC_CH_NUM);
    uint32_t channel_bitmask = (1UL << channel_index);
    channel_bitmask |= nrf_ipc_receive_config_get(NRF_IPC_NS, event_index);
    nrf_ipc_receive_config_set(NRF_IPC_NS, event_index, channel_bitmask);
}

void nrfx_ipc_send_task_channel_assign(uint8_t send_index, 
    uint8_t channel_index)
{
    NRFX_ASSERT(channel_index < IPC_CH_NUM);
    uint32_t channel_bitmask = (1UL << channel_index);
    channel_bitmask |= nrf_ipc_send_config_get(NRF_IPC_NS, send_index);
    nrf_ipc_send_config_set(NRF_IPC_NS, send_index, channel_bitmask);
}

void nrfx_ipc_irq_handler(void)
{
    // Get the information about events that fire this interrupt
    uint32_t events_map = nrf_ipc_int_pending_get(NRF_IPC_NS);

    // Clear these events
    uint32_t bitmask = events_map;
    while (bitmask)
    {
        uint8_t event_idx = __CLZ(__RBIT(bitmask)); // NRF_CTZ(bitmask);
        bitmask &= ~(1UL << event_idx);
        nrf_ipc_event_clear(NRF_IPC_NS, nrf_ipc_receive_event_get(event_idx));
    }

    // Execute interrupt handler to provide information about events to app
    m_ipc_cb.handler(events_map, m_ipc_cb.p_context);
}

//#endif // NRFX_CHECK(NRFX_IPC_ENABLED)

Makefile

# Makefile for nRF9160 bare metal programming                 PVH, January 2023

# Arm GNU toolchain can be found here (look for gcc-arm-none-eabi)
# https://developer.arm.com/Tools%20and%20Software/GNU%20Toolchain
# nrfx is available at https://github.com/NordicSemiconductor/nrfx
# and the SDK at https://github.com/nrfconnect/sdk-nrfxlib
# CMSIS can be found at https://github.com/ARM-software/CMSIS_5


# Specify project name, build directory and linker script
TARGET = test
BUILDDIR = ./build
LDSCRIPT = app.ld
BOOTLDSCRIPT = boot.ld

# Paths to toolchain and SDK
TOOLSPATH = /opt/gcc-arm-none-eabi-9-2020-q2-update
CMSISPATH = /opt/CMSIS_5/CMSIS
NRFXPATH = /opt/nrfx-2.10.0
SDKPATH = /opt/sdk-nrfxlib-2.1.3

# Shortcuts for various tools
CC  = ${TOOLSPATH}/bin/arm-none-eabi-gcc
CPP = ${TOOLSPATH}/bin/arm-none-eabi-g++
AS  = ${TOOLSPATH}/bin/arm-none-eabi-g++
LD  = ${TOOLSPATH}/bin/arm-none-eabi-g++
DB  = ${TOOLSPATH}/bin/arm-none-eabi-gdb
OBJCOPY = ${TOOLSPATH}/bin/arm-none-eabi-objcopy
SIZETOOL = ${TOOLSPATH}/bin/arm-none-eabi-size
MERGEHEX = /opt/nrf-command-line-tools/bin/mergehex
NRFJPROG = /opt/nrf-command-line-tools/bin/nrfjprog

# List of source files for the application
SOURCES = \
    ${NRFXPATH}/mdk/gcc_startup_nrf9160.S \
    ${NRFXPATH}/mdk/system_nrf9160.c \
    app/dyma.c \
    app/delay.c \
    app/nrf_modem_os.c \
    app/nrfx_ipc.c \
    app/main.c \
    
# List of source files for the bootloader
BOOTSOURCES = \
    ${NRFXPATH}/mdk/gcc_startup_nrf9160.S \
    ${NRFXPATH}/mdk/system_nrf9160.c \
    boot/main.c

# List of include directories
INCLUDEDIRS = \
    ${CMSISPATH}/Core/Include \
    ${NRFXPATH} \
    ${NRFXPATH}/templates \
    ${NRFXPATH}/mdk \
    ${NRFXPATH}/hal \
    ${NRFXPATH}/drivers/include \
    ${SDKPATH}/nrf_modem/include

# Directories to search for libraries in the linking process
LDDIRS = \
    ${NRFXPATH}/mdk \
    $(SDKPATH)/nrf_modem/lib/cortex-m33/hard-float \
    
# Libraries for the application
LIBS = -lmodem -Wl,--start-group -lgcc -lc -lnosys -Wl,--end-group

# Libraries for the bootloader
BOOTLIBS = -Wl,--start-group -lgcc -lc -lnosys -Wl,--end-group

# Additional objects for the linker
LDOBJECTS =

# Common flags for CC, CPP, AS and LD
FLAGS = -mcpu=cortex-m33 -mthumb -mfloat-abi=hard -mabi=aapcs
FLAGS += -mfpu=fpv5-sp-d16 -DNRF9160_XXAA
FLAGS += -DCONFIG_GPIO_AS_PINRESET -DFLOAT_ABI_HARD

# Common flags for secure code
SFLAGS = -mcmse

# Common flags for non-secure code
NSFLAGS = -DNRF_TRUSTZONE_NONSECURE

# Flags for the C compiler
CFLAGS = ${FLAGS} -std=c99 -Wall

# Flags for the C++ compiler
CPPFLAGS = ${FLAGS} -std=c++11 -Wall

# Flags for the assembler
AFLAGS = ${FLAGS} -x assembler-with-cpp

# Linker flags
LDFLAGS = ${FLAGS} -T "$(LDSCRIPT)" -Xlinker
LDFLAGS += --gc-sections -Xlinker -Map="$(BUILDDIR)/$(TARGET)_app.map" 
LDFLAGS += --specs=nano.specs

BOOTLDFLAGS = ${FLAGS} -T "$(BOOTLDSCRIPT)" -Xlinker
BOOTLDFLAGS += --gc-sections -Xlinker -Map="$(BUILDDIR)/$(TARGET)_boot.map" 
BOOTLDFLAGS += --specs=nano.specs

# Check whether to optimize or build for debugging
DEBUG ?= 0
ifeq ($(DEBUG), 1)
	CFLAGS += -Og -g3 -gdwarf-2
	CPPFLAGS += -Og -g3 -gdwarf-2
	AFLAGS += -g3 -gdwarf-2
	LDFLAGS += -g3
else
	CFLAGS += -O3
	CPPFLAGS += -O3
endif

# Construct list of object files by appending the suffix .o to all source files
OBJECTS := $(addsuffix .o,$(SOURCES))

# Replace NRFX paths since objects here are going to be build in the build dir.
OBJECTS := $(subst $(NRFXPATH),app/nrfx,$(OBJECTS))
OBJECTS := $(subst $(SDKPATH),app/sdk-nrfxlib,$(OBJECTS))

# Finally, add build directory prefix
OBJECTS := $(addprefix $(BUILDDIR)/,$(OBJECTS))

# And we to the same to the bootloader
BOOTOBJECTS := $(addsuffix .o,$(BOOTSOURCES))
BOOTOBJECTS := $(subst $(NRFXPATH),boot/nrfx,$(BOOTOBJECTS))
BOOTOBJECTS := $(subst $(SDKPATH),boot/sdk-nrfxlib,$(BOOTOBJECTS))
BOOTOBJECTS := $(addprefix $(BUILDDIR)/,$(BOOTOBJECTS))

# Add -I prefix to INCLUDEDIRS and insert them into CFLAGS, CPPFLAGS and AFLAGS
CFLAGS := $(CFLAGS) $(addprefix -I,$(INCLUDEDIRS)) 
CPPFLAGS := $(CPPFLAGS) $(addprefix -I,$(INCLUDEDIRS))
AFLAGS := $(AFLAGS) $(addprefix -I,$(INCLUDEDIRS)) 

# Add -L prefix to LDDIRS and and insert them into LDFLAGS along with LIBS
LDFLAGS := $(addprefix -L,$(LDDIRS)) $(LIBS) $(LDFLAGS)
BOOTLDFLAGS := $(addprefix -L,$(LDDIRS)) $(BOOTLIBS) $(BOOTLDFLAGS)

all: $(BUILDDIR)/$(TARGET).hex

$(BUILDDIR)/$(TARGET).hex: $(BUILDDIR)/$(TARGET)_boot.axf $(BUILDDIR)/$(TARGET)_app.axf
	@echo "[MERGEHEX] $^ -> $@"
	@$(MERGEHEX) -m $^ -o $@
	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET).bin"
	@objcopy -I ihex -O binary $@ $(BUILDDIR)/$(TARGET).bin
	
$(BUILDDIR)/$(TARGET)_boot.axf: $(BOOTOBJECTS)
	@echo "[LD] Linking boot image $@"
	@$(LD) $(BOOTLDFLAGS) -o $@ $(BOOTOBJECTS) $(LIBS)
	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_boot.hex"
	@objcopy -O ihex $@ $(BUILDDIR)/$(TARGET)_boot.hex
	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_boot.bin"
	@objcopy -I ihex -O binary $(BUILDDIR)/$(TARGET)_boot.hex $(BUILDDIR)/$(TARGET)_boot.bin
	@$(SIZETOOL) $@
	
$(BUILDDIR)/$(TARGET)_app.axf: $(OBJECTS) 
	@echo "[LD] Linking app image $@"
	@$(LD) $(LDFLAGS) -DNRF_TRUSTZONE_NONSECURE -o $@ $(OBJECTS) $(LIBS)
	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_app.hex"
	@objcopy -O ihex $@ $(BUILDDIR)/$(TARGET)_app.hex
	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_app.bin"
	@objcopy -I ihex -O binary $(BUILDDIR)/$(TARGET)_app.hex $(BUILDDIR)/$(TARGET)_app.bin
	@$(SIZETOOL) $@
	
# Recipe for building C objects in the bootloader
$(BUILDDIR)/boot/%.c.o: boot/%.c
	@echo "[CC] $< -> $@"
	@mkdir -p $(@D)
	$(CC) $(SFLAGS) $(CFLAGS) -c $< -o $@

# Recipe for building C++ objects in the bootloader
$(BUILDDIR)/boot/%.cpp.o: boot/%.cpp
	@echo "[CPP] $< -> $@"
	@mkdir -p $(@D)
	@$(CPP) $(SFLAGS) $(CPPFLAGS) -c $< -o $@

# Recipe for assembling objects in the bootloader
$(BUILDDIR)/boot/%.S.o: /boot/%.S
	@echo "[AS] $< -> $@"
	@mkdir -p $(@D)
	@$(AS) $(SFLAGS) $(AFLAGS) -c $< -o $@

# Recipe for building C objects in $(NRFXPATH) for the bootloader
$(BUILDDIR)/boot/nrfx/%.c.o: $(NRFXPATH)/%.c
	@echo "[CC] $< -> $@"
	@mkdir -p $(@D)
	@$(CC) $(SFLAGS) $(CFLAGS) -c $< -o $@

# Recipe for assembling objects in $(NRFXPATH) for the bootloader
$(BUILDDIR)/boot/nrfx/%.S.o: $(NRFXPATH)/%.S
	@echo "[AS] $< -> $@"
	@mkdir -p $(@D)
	@$(AS) $(SFLAGS) $(AFLAGS) -c $< -o $@

# Recipe for building C objects in the application
$(BUILDDIR)/app/%.c.o: app/%.c
	@echo "[CC] $< -> $@"
	@mkdir -p $(@D)
	@$(CC) $(NSFLAGS) $(CFLAGS) -c $< -o $@
	
# Recipe for building C++ objects in the application
$(BUILDDIR)/app/%.cpp.o: app/%.cpp
	@echo "[CPP] $< -> $@"
	@mkdir -p $(@D)
	@$(CPP) $(NSFLAGS) $(CPPFLAGS) -c $< -o $@

# Recipe for assembling objects in the application
$(BUILDDIR)/app/%.S.o: app/%.S
	@echo "[AS] $< -> $@"
	@mkdir -p $(@D)
	@$(AS) $(NSFLAGS) $(AFLAGS) -c $< -o $@

# Recipe for building C objects in $(NRFXPATH) for the application
$(BUILDDIR)/app/nrfx/%.c.o: $(NRFXPATH)/%.c
	@echo "[CC] $< -> $@"
	@mkdir -p $(@D)
	@$(CC) $(NSFLAGS) $(CFLAGS) -c $< -o $@

# Recipe for assembling objects in $(NRFXPATH) for the application
$(BUILDDIR)/app/nrfx/%.S.o: $(NRFXPATH)/%.S
	@echo "[AS] $< -> $@"
	@mkdir -p $(@D)
	@$(AS) $(NSFLAGS) $(AFLAGS) -c $< -o $@

.PHONY: clean flash erase debug

# Remove all build files
clean:
	@echo "Removing $(BUILDDIR)"
	@rm -dfr $(BUILDDIR)
	
# Flash the program
flash: $(BUILDDIR)/$(TARGET).hex
	@echo Flashing $(BUILDDIR)/$(TARGET).hex
	@$(NRFJPROG) -f nrf91 --program $(BUILDDIR)/$(TARGET).hex --sectorerase \
	--verify --reset

# Erase all flash
erase:
	@echo Erasing all flash
	@nrfjprog -f nrf91 --eraseall

# Shortcut for debugging
debug: $(BUILDDIR)/$(TARGET).hex
	@echo "Run /opt/SEGGER/JLink/JLinkGDBServerCLExe -device nrf9160_xxaa -if swd -port 2331"
	@$(DB) -x gdb_cmds.txt

GDB output with manual stepping just before nrf_modem_os_init() function returns:

Target interface speed set to 2000 kHz
Flash download enabled
Loading section .sec1, size 0xa74 lma 0x0
Loading section .sec2, size 0x28d8 lma 0x10000
Start address 0x0, load size 13132
Transfer rate: 105056 bits in <1 sec, 6566 bytes/write.
Breakpoint 1 at 0x7d4: main. (2 locations)
Resets core & peripherals via SYSRESETREQ & VECTRESET bit.

Breakpoint 1, main () at boot/main.c:9
9	{
(gdb) break app/nrf_modem_os.c:78
Breakpoint 2 at 0x106c6: file app/nrf_modem_os.c, line 78.
(gdb) continue
Continuing.

Breakpoint 1, main () at app/main.c:68
68	{
(gdb) continue
Continuing.

Breakpoint 2, nrf_modem_os_init () at app/nrf_modem_os.c:78
78	    nrf_modem_os_inside_isr = false;
(gdb) step
nrf_modem_init (params=0x12538 <init_params>, mode=mode@entry=NORMAL_MODE) at ./platform/nrf_modem.c:217
217	./platform/nrf_modem.c: No such file or directory.
(gdb) step
nrf_modem_platform_init (params=0x12538 <init_params>) at ./platform/nrf_modem.c:217
217	in ./platform/nrf_modem.c
(gdb) step
66	in ./platform/nrf_modem.c
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:706
706	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
nrfx_ipc_init (irq_priority=0 '\000', handler=handler@entry=0x10b99 <ipc_irq_handler>, p_context=p_context@entry=0x0 <__isr_vector>) at app/nrfx_ipc.c:59
59	    if (m_ipc_cb.state != NRFX_DRV_STATE_UNINITIALIZED)
(gdb) step
65	    NVIC_SetPriority(IPC_IRQn, irq_priority);
(gdb) step
__NVIC_SetPriority (priority=0, IRQn=IPC_IRQn) at /opt/CMSIS_5/CMSIS/Core/Include/core_cm33.h:2591
2591	    NVIC->IPR[((uint32_t)IRQn)]               = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
(gdb) step
nrfx_ipc_init (irq_priority=<optimized out>, handler=handler@entry=0x10b99 <ipc_irq_handler>, p_context=p_context@entry=0x0 <__isr_vector>) at app/nrfx_ipc.c:67
67	    NVIC_EnableIRQ(IPC_IRQn);
(gdb) step
__NVIC_EnableIRQ (IRQn=IPC_IRQn) at /opt/CMSIS_5/CMSIS/Core/Include/core_cm33.h:2395
2395	    NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
(gdb) step
nrfx_ipc_init (irq_priority=<optimized out>, handler=handler@entry=0x10b99 <ipc_irq_handler>, p_context=p_context@entry=0x0 <__isr_vector>) at app/nrfx_ipc.c:69
69	    m_ipc_cb.state = NRFX_DRV_STATE_INITIALIZED;
(gdb) step
70	    m_ipc_cb.handler = handler;
(gdb) step
71	    m_ipc_cb.p_context = p_context;
(gdb) step
73	    return NRFX_SUCCESS;
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:708
708	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
732	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=0, index=0 '\000', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=2, index=1 '\001', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=0, index=2 '\002', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=8, index=3 '\003', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=0, index=4 '\004', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=32, index=5 '\005', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=0, index=6 '\006', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
(gdb) step
nrf_ipc_send_config_set (channels_mask=0, index=7 '\a', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
444	    p_reg->SEND_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:82
82	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=1, index=0 '\000', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=0, index=1 '\001', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=4, index=2 '\002', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=0, index=3 '\003', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=16, index=4 '\004', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=0, index=5 '\005', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=64, index=6 '\006', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
(gdb) step
nrf_ipc_receive_config_set (channels_mask=128, index=7 '\a', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
456	    p_reg->RECEIVE_CNF[index] = channels_mask;
(gdb) step
nrfx_ipc_config_load (p_config=p_config@entry=0x2003df6c) at app/nrfx_ipc.c:87
87	    for (i = 0; i < IPC_CONF_NUM; ++i)
(gdb) step
93	    nrf_ipc_int_enable(NRF_IPC_NS, p_config->receive_events_enabled);
(gdb) step
nrf_ipc_int_enable (mask=213, p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:396
396	    p_reg->INTENSET = mask;
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:734
734	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
rpc_transport_ipc_shmem_init (cfg=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:734
734	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
596	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
602	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
__memset_ichk (len=1256, src=0, dst=0x20010000) at /home/ncs/toolchains/v2.0.0/opt/zephyr-sdk/arm-zephyr-eabi/arm-zephyr-eabi/sys-include/ssp/string.h:86
86	/home/ncs/toolchains/v2.0.0/opt/zephyr-sdk/arm-zephyr-eabi/arm-zephyr-eabi/sys-include/ssp/string.h: No such file or directory.
(gdb) step
rpc_transport_ipc_shmem_init (cfg=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:607
607	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
608	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
610	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
611	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
614	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
620	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_shmem_init (cfg=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:655
655	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
657	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
664	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
667	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
668	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
675	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:676
676	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/test_fw-nrfconnect-libmodem_main/modules/hal/nordic/nrfx/hal/nrf_ipc.h:470
470	/jenkins_workspace/workspace/test_fw-nrfconnect-libmodem_main/modules/hal/nordic/nrfx/hal/nrf_ipc.h: No such file or directory.
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
555	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
nrf_modem_reset_clear () at ../../../include/nrf_modem_control.h:87
87	../../../include/nrf_modem_control.h: No such file or directory.
(gdb) step
90	in ../../../include/nrf_modem_control.h
(gdb) step
91	in ../../../include/nrf_modem_control.h
(gdb) step
96	in ../../../include/nrf_modem_control.h
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:556
556	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:557
557	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
558	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df64) at app/nrf_modem_os.c:121
121	    if (! nrf_modem_is_initialized())
(gdb) step
nrf_modem_is_initialized () at ./platform/nrf_modem.c:252
252	./platform/nrf_modem.c: No such file or directory.
(gdb) step
nrf_modem_state_is_initialized () at ./platform/nrf_modem_state.c:23
23	./platform/nrf_modem_state.c: No such file or directory.
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:559
559	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
556	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:557
557	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
558	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df64) at app/nrf_modem_os.c:121
121	    if (! nrf_modem_is_initialized())
(gdb) step
nrf_modem_is_initialized () at ./platform/nrf_modem.c:252
252	./platform/nrf_modem.c: No such file or directory.
(gdb) step
nrf_modem_state_is_initialized () at ./platform/nrf_modem_state.c:23
23	./platform/nrf_modem_state.c: No such file or directory.
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:559
559	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
556	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:557
557	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
558	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df64) at app/nrf_modem_os.c:121
121	    if (! nrf_modem_is_initialized())
(gdb) step
nrf_modem_is_initialized () at ./platform/nrf_modem.c:252
252	./platform/nrf_modem.c: No such file or directory.
(gdb) step
nrf_modem_state_is_initialized () at ./platform/nrf_modem_state.c:23
23	./platform/nrf_modem_state.c: No such file or directory.
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:559
559	./rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
(gdb) step
556	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_init (init_param=init_param@entry=0x2003dfd8) at ./rpc/transport/ipc/rpc_transport_ipc.c:739
739	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
rpc_transport_ipc_handshake () at ./rpc/transport/ipc/rpc_transport_ipc.c:557
557	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
558	in ./rpc/transport/ipc/rpc_transport_ipc.c
(gdb) step
nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df64) at app/nrf_modem_os.c:121
121	    if (! nrf_modem_is_initialized())

  • Hi,

    I'll need a bit more time to look into this.

    In the mean time, could you explain what you think is outdated with the documentation?

    Best regards,

    Didrik

  • Yes, of course - thank you very much for looking into this :-)

    Regarding the documentation, it appears that the online documentation (version 2.2.99) is identical to the .rst files found in the main branch of the GitHub repository.

    However, the documentation I get when I download the latest release (version 2.1.3) is more comprehensive and "complete" compared to the online documentation.

    The documentation in the v2.1-branch appears identical or at least very similar to the one I get when I download the 2.1.3 release. I refer to this version as the "offline documentation" below.

    I have listed some of the major and important differences here:

    • No mentioning of the EGU1 interrupt at all in the online documentation
    • The functions nrf_modem_os_application_irq_set() and nrf_modem_os_application_irq_clear() are not listed in the section Specification and are not shown in the Template section either
    • The Initialization sequence diagram is more detailed in the offline documentation and shows how to configure the EGU1 interrupt - the online version does not.
    • The Timedwait message sequence diagram shown in 2. Handling a timeout or sleep is also different. For example, the IPC interrupt is indicated in the diagram in the online documentation, but the offline version shows the EGU1 interrupt instead.
    • The offline documentation includes an extra sequence diagram labeled Event handling, lowering priority that is not shown in the online documentation

    Perhaps the nrf_modem_os_application_irq functions and the EGU1 interrupt are no longer needed in version 2.2.99 (the main branch?), and I am supposed to download the main branch instead of the latest release?

  • PVH said:
    I am supposed to download the main branch instead of the latest release?

    Correct. The "latest" or x.y.99 version of the documentation is taken from the main branch of the respective repositories.

    The most recent version of the modem lib (2.2.1) is the one that is documented in the "online" documentation.

    Particularly, there were some big changes in how modem_lib v2.2.0 works, which interrupts it uses, etc.: https://developer.nordicsemi.com/nRF_Connect_SDK/doc/latest/nrfxlib/nrf_modem/doc/CHANGELOG.html#nrf-modem-2-2-0

    So some of the documentation you feel is "missing", is simply not necessary anymore, with the most recent versions of the modem_lib.

    ...

    Looking at the history of releases, 2.1.3 was released after 2.2.0, hence why Github thins it is the latest: https://github.com/nrfconnect/sdk-nrfxlib/releases

  • Thank you for making this clear. I was quite confused, but now it makes sense. I should have paid more attention to the changelog :-)

    I am going to try version 2.2.1 of the modem library and change the code accordingly - then I will post the result here, hopefully within a few days.

  • I have now downloaded version 2.2.0 of sdk-nrfxlib (that contains version 2.2.1 of the modem library), changed the Makefile to use the newer version and updated nrf_modem_os.c and defs.h as well. All other files are as before.

    Anything related to the EGU1 interrupt has been removed from my nrf_modem_os.c, including the functions nrf_modem_os_application_irq_set() and nrf_modem_os_application_irq_clear() that are not needed anymore. Since nrf_modem_platform.h does not exist in the newer version of the modem library, I had to make some changes to defs.h so that NRF_MODEM_NETWORK_IRQ_PRIORITY is defined. This is set to 0 as before.

    Lastly, I have updated the modem firmware from version 1.3.3 to 1.3.4 as required in the changelog for version 2.2.1 of the modem library.

    The changes did not make it work. I believe it is the same exact problem as before, where nrf_modem_init() is stuck in a loop involving nrf_modem_os_timedwait(), and some RPC/IPC related functions inside the modem library. It still does not return.

    Below is an output from GDB where I break the execution a few times to see where it is stuck:

    Target interface speed set to 2000 kHz
    Flash download enabled
    Loading section .sec1, size 0xa74 lma 0x0
    Loading section .sec2, size 0x29a0 lma 0x10000
    Start address 0x0, load size 13332
    Transfer rate: 106656 bits in <1 sec, 6666 bytes/write.
    Breakpoint 1 at 0x7d4: main. (2 locations)
    Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
    
    Breakpoint 1, main () at boot/main.c:9
    9	{
    (gdb) continue
    Continuing.
    
    Breakpoint 1, main () at app/main.c:68
    68	{
    (gdb) continue
    Continuing.
    ^C
    Program received signal SIGTRAP, Trace/breakpoint trap.
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:103
    103	{
    (gdb) where
    #0  nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:103
    #1  0x00010fdc in rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:535
    #2  rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    #3  0x00010c40 in rpc_init (init_param=init_param@entry=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c:117
    #4  0x00010aca in nrf_modem_platform_init (params=0x125c8 <init_params>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:73
    #5  nrf_modem_init (params=0x125c8 <init_params>, mode=mode@entry=NORMAL_MODE) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:237
    #6  0x00010a22 in main () at app/main.c:80
    #7  0x00010496 in _start ()
    Backtrace stopped: previous frame inner to this frame (corrupt stack?)
    (gdb) continue
    Continuing.
    ^C
    Program received signal SIGTRAP, Trace/breakpoint trap.
    0x00010756 in nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:142
    142	    if (k == 0)
    (gdb) where
    #0  0x00010756 in nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:142
    #1  0x00010fdc in rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:535
    #2  rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    #3  0x00010c40 in rpc_init (init_param=init_param@entry=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c:117
    #4  0x00010aca in nrf_modem_platform_init (params=0x125c8 <init_params>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:73
    #5  nrf_modem_init (params=0x125c8 <init_params>, mode=mode@entry=NORMAL_MODE) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:237
    #6  0x00010a22 in main () at app/main.c:80
    #7  0x00010496 in _start ()
    Backtrace stopped: previous frame inner to this frame (corrupt stack?)
    (gdb) continue
    Continuing.
    ^C
    Program received signal SIGTRAP, Trace/breakpoint trap.
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) where
    #0  nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    #1  0x00010b60 in nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    #2  0x00010702 in nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    #3  0x00010fdc in rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:535
    #4  rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    #5  0x00010c40 in rpc_init (init_param=init_param@entry=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c:117
    #6  0x00010aca in nrf_modem_platform_init (params=0x125c8 <init_params>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:73
    #7  nrf_modem_init (params=0x125c8 <init_params>, mode=mode@entry=NORMAL_MODE) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:237
    #8  0x00010a22 in main () at app/main.c:80
    #9  0x00010496 in _start ()
    Backtrace stopped: previous frame inner to this frame (corrupt stack?)
    (gdb) continue
    Continuing.
    ^C
    Program received signal SIGTRAP, Trace/breakpoint trap.
    0x00010fd4 in rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) where
    #0  0x00010fd4 in rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    #1  rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    #2  0x00010c40 in rpc_init (init_param=init_param@entry=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c:117
    #3  0x00010aca in nrf_modem_platform_init (params=0x125c8 <init_params>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:73
    #4  nrf_modem_init (params=0x125c8 <init_params>, mode=mode@entry=NORMAL_MODE) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:237
    #5  0x00010a22 in main () at app/main.c:80
    #6  0x00010496 in _start ()
    Backtrace stopped: previous frame inner to this frame (corrupt stack?)
    (gdb)


    The changed files are included below, as well as a longer GDB output where I do manual stepping like in my original question above.

    app/defs.h

    // DEFS header                                                  PVH, 2023-01-24
    #ifndef DEFS_H
    #define DEFS_H
    
    // Define the addresses and sizes of the various regions in the shared memory
    // for use with the nRF Modem Library. THIS SHOULD MATCH THE LINKER SCRIPT!!!
    #define NRF_MODEM_SHMEM_CTRL_BASE  0x20010000
    // NRF_MODEM_SHMEM_CTRL_SIZE is already set to 0x4e8 in nrf_modem.h
    #define NRF_MODEM_SHMEM_TX_BASE    0x200104e8
    #define NRF_MODEM_SHMEM_TX_SIZE    0x00004000
    #define NRF_MODEM_SHMEM_RX_BASE    0x200144e8
    #define NRF_MODEM_SHMEM_RX_SIZE    0x00002000
    #define NRF_MODEM_SHMEM_TRACE_BASE 0x200164E8
    #define NRF_MODEM_SHMEM_TRACE_SIZE 0x00000000
    
    // This was defined in nrf_modem_platform.h that no longer exists in
    // version 2.2.1 version of the modem library, so we define it here instead
    #define NRF_MODEM_NETWORK_IRQ_PRIORITY 0
    
    #include <nrf_modem.h>  // Definition of struct nrf_modem_fault_into
    
    #ifdef __cplusplus
    extern "C" {
    #endif
    
    // Definition of modem fault handler
    void nrf_modem_fault_handler(struct nrf_modem_fault_info* fault_info);
    const struct nrf_modem_init_params* nrf_modem_get_init_params();
    
    #ifdef __cplusplus
    }
    #endif
    
    #endif

    app/nrf_modem_os.c

    // NRF_MODEM_OS implementation                                  PVH, 2023-01-26
    // Custom nrf_modem_os.c file that implements the functions defined in the
    // nrf_modem_os.h header found in the sdk-nrfxlib
    #include <nrf_modem.h>
    #include <nrf_modem_os.h>
    #include <nrfx_ipc.h> 
    #include <nrf_errno.h>
    #include <nrf.h>
    #include "errno.h"
    
    #include "defs.h"    // Constants and definition of fault handler function etc.
    #include "delay.h"   // For use in nrf_modem_os_busywait()
    #include "dyma.h"    // For dynamic memory allocation within the TX shared mem.
    #include <stdlib.h>  // For malloc, free
    #include <stdbool.h> // For bool
    
    volatile bool nrf_modem_os_inside_isr;  // True while in ISR otherwise false
    volatile bool nrf_modem_os_wakeup;  // Set true when a "thread" should wake up
    
    static const struct nrf_modem_init_params init_params =
    {
            .ipc_irq_prio = NRF_MODEM_NETWORK_IRQ_PRIORITY,
            .shmem.ctrl = {
                    .base = NRF_MODEM_SHMEM_CTRL_BASE,
                    .size = NRF_MODEM_SHMEM_CTRL_SIZE,
            },
            .shmem.tx = {
                    .base = NRF_MODEM_SHMEM_TX_BASE,
                    .size = NRF_MODEM_SHMEM_TX_SIZE,
            },
            .shmem.rx = {
                    .base = NRF_MODEM_SHMEM_RX_BASE,
                    .size = NRF_MODEM_SHMEM_RX_SIZE,
            },
            .shmem.trace = {
                    .base = NRF_MODEM_SHMEM_TRACE_BASE,
                    .size = NRF_MODEM_SHMEM_TRACE_SIZE,
            },
            .fault_handler = nrf_modem_fault_handler
    };
    
    const struct nrf_modem_init_params* nrf_modem_get_init_params()
    {
        return &init_params;
    }
    
    void IPC_IRQHandler()
    {
        nrf_modem_os_inside_isr = true;
        nrfx_ipc_irq_handler();
    	nrf_modem_os_event_notify();
    	nrf_modem_os_inside_isr = false;
    }
    
    void nrf_modem_os_init(void)
    {
        /* Initialize the glue layer and required peripherals. */
       
        // Initialize dynamic memory allocation for the TX region in shared memory
        dyma_init((void*)NRF_MODEM_SHMEM_TX_BASE, NRF_MODEM_SHMEM_TX_SIZE);
        
        nrf_modem_os_inside_isr = false;
    }
    
    void nrf_modem_os_shutdown(void)
    {
        /* Deinitialize the glue layer.
           When shutdown is called, all pending calls to nrf_modem_os_timedwait
           shall exit and return -NRF_ESHUTDOWN. */
    }
    
    void* nrf_modem_os_shm_tx_alloc(size_t bytes)
    {
        /* Allocate a buffer on the TX area of shared memory. */
        return dyma_alloc((void*)NRF_MODEM_SHMEM_TX_BASE, bytes);
    }
    
    void nrf_modem_os_shm_tx_free(void* mem)
    {
        /* Free a shared memory buffer in the TX area. */
        dyma_free(mem);
    }
    
    void* nrf_modem_os_alloc(size_t bytes)
    {
        /* Allocate a buffer on the library heap. */
        return malloc(bytes);
    }
    
    void nrf_modem_os_free(void* mem)
    {
        /* Free a memory buffer in the library heap. */
        free(mem);
    }
    
    void nrf_modem_os_busywait(int32_t usec)
    {
        /* Busy wait for a given amount of microseconds. */
        delay_us(usec);
    }
    
    int32_t nrf_modem_os_timedwait(uint32_t context, int32_t* timeout)
    {
        if (! nrf_modem_is_initialized())
        {
            return -NRF_ESHUTDOWN;
        }
    
        /* Put a thread to sleep for a specific time or until an event occurs.
           Wait for the timeout.
           All waiting threads shall be woken by nrf_modem_event_notify.
           A blind return value of zero will cause a blocking wait. */
           
        nrf_modem_os_wakeup = false;
        
        // Wait until a timeout of approximately *timeout milliseconds or until
        // woken up by nrf_modem_os_event_notify()
        volatile uint32_t k = *timeout*4000;
        if (*timeout < 0)
            k = 0xFFFFFFFFul;   // Not infinite but pretty long timeout
            
        while (k > 0)
        {
            // If nrf_modem_os_event_notify() is called, wake up and return
            // the remaining time in *timeout
            if (nrf_modem_os_wakeup)
            {
                nrf_modem_os_wakeup = false;
                *timeout = k / 4000;
                break;
            }
            
            // Countdown the time
            k--;
        }
        
        // Check if the modem has been uninitialized in the meantime
        if (! nrf_modem_is_initialized())
            return -NRF_ESHUTDOWN;
        
        // Check if while loop above was broken by a timeout
        if (k == 0)
            return -NRF_EAGAIN;
    
        return 0;
    }
    
    void nrf_modem_os_event_notify(void)
    {
        /* Notify the application that an event has occurred.
           This shall wake all threads sleeping in nrf_modem_os_timedwait. */
           
        nrf_modem_os_wakeup = true;
    }
    
    void nrf_modem_os_errno_set(int errno_val)
    {
        /* Set OS errno. */
    }
    
    bool nrf_modem_os_is_in_isr(void)
    {
        /* Check if executing in interrupt context. */
        return nrf_modem_os_inside_isr;
    }
    
    int nrf_modem_os_sem_init(void** sem, unsigned int initial_count, 
        unsigned int limit)
    {
        /* The function shall allocate and initialize a semaphore and return its 
           address through the `sem` parameter. If an address of an already 
           allocated semaphore is provided as an input, the allocation part is 
           skipped and the semaphore is only reinitialized. */
        return 0;
    }
    
    void nrf_modem_os_sem_give(void* sem)
    {
        /* Give a semaphore. */
    }
    
    int nrf_modem_os_sem_take(void* sem, int timeout)
    {
        /* Try to take a semaphore with the given timeout. */
        return 0;
    }
    
    unsigned int nrf_modem_os_sem_count_get(void* sem)
    {
        /* Get a semaphore's count. */
        return 0;
    }
    
    void nrf_modem_os_log(int level, const char* fmt, ...)
    {
        /* Generic logging procedure. */
        /*
        va_list ap;
        va_start(ap, fmt);
        vprintf(fmt, ap);
        printf("\n");
        va_end(ap);
        */
    }
    
    void nrf_modem_os_logdump(int level, const char* str, const void* data, 
        size_t len)
    {
        /* Log hex representation of object. */
    }

    Makefile

    # Makefile for nRF9160 bare metal programming                 PVH, January 2023
    
    # Arm GNU toolchain can be found here (look for gcc-arm-none-eabi)
    # https://developer.arm.com/Tools%20and%20Software/GNU%20Toolchain
    # nrfx is available at https://github.com/NordicSemiconductor/nrfx
    # and the SDK at https://github.com/nrfconnect/sdk-nrfxlib
    # CMSIS can be found at https://github.com/ARM-software/CMSIS_5
    
    
    # Specify project name, build directory and linker script
    TARGET = test
    BUILDDIR = ./build
    LDSCRIPT = app.ld
    BOOTLDSCRIPT = boot.ld
    
    # Paths to toolchain and SDK
    TOOLSPATH = /opt/gcc-arm-none-eabi-9-2020-q2-update
    CMSISPATH = /opt/CMSIS_5/CMSIS
    NRFXPATH = /opt/nrfx-2.10.0
    SDKPATH = /opt/sdk-nrfxlib-2.2.0
    
    # Shortcuts for various tools
    CC  = ${TOOLSPATH}/bin/arm-none-eabi-gcc
    CPP = ${TOOLSPATH}/bin/arm-none-eabi-g++
    AS  = ${TOOLSPATH}/bin/arm-none-eabi-g++
    LD  = ${TOOLSPATH}/bin/arm-none-eabi-g++
    DB  = ${TOOLSPATH}/bin/arm-none-eabi-gdb
    OBJCOPY = ${TOOLSPATH}/bin/arm-none-eabi-objcopy
    SIZETOOL = ${TOOLSPATH}/bin/arm-none-eabi-size
    MERGEHEX = /opt/nrf-command-line-tools/bin/mergehex
    NRFJPROG = /opt/nrf-command-line-tools/bin/nrfjprog
    
    # List of source files for the application
    SOURCES = \
        ${NRFXPATH}/mdk/gcc_startup_nrf9160.S \
        ${NRFXPATH}/mdk/system_nrf9160.c \
        app/dyma.c \
        app/delay.c \
        app/nrf_modem_os.c \
        app/nrfx_ipc.c \
        app/main.c \
        
    # List of source files for the bootloader
    BOOTSOURCES = \
        ${NRFXPATH}/mdk/gcc_startup_nrf9160.S \
        ${NRFXPATH}/mdk/system_nrf9160.c \
        boot/main.c
    
    # List of include directories
    INCLUDEDIRS = \
        ${CMSISPATH}/Core/Include \
        ${NRFXPATH} \
        ${NRFXPATH}/templates \
        ${NRFXPATH}/mdk \
        ${NRFXPATH}/hal \
        ${NRFXPATH}/drivers/include \
        ${SDKPATH}/nrf_modem/include
    
    # Directories to search for libraries in the linking process
    LDDIRS = \
        ${NRFXPATH}/mdk \
        $(SDKPATH)/nrf_modem/lib/cortex-m33/hard-float \
        
    # Libraries for the application
    LIBS = -lmodem -Wl,--start-group -lgcc -lc -lnosys -Wl,--end-group
    
    # Libraries for the bootloader
    BOOTLIBS = -Wl,--start-group -lgcc -lc -lnosys -Wl,--end-group
    
    # Additional objects for the linker
    LDOBJECTS =
    
    # Common flags for CC, CPP, AS and LD
    FLAGS = -mcpu=cortex-m33 -mthumb -mfloat-abi=hard -mabi=aapcs
    FLAGS += -mfpu=fpv5-sp-d16 -DNRF9160_XXAA
    FLAGS += -DCONFIG_GPIO_AS_PINRESET -DFLOAT_ABI_HARD
    
    # Common flags for secure code
    SFLAGS = -mcmse
    
    # Common flags for non-secure code
    NSFLAGS = -DNRF_TRUSTZONE_NONSECURE
    
    # Flags for the C compiler
    CFLAGS = ${FLAGS} -std=c99 -Wall
    
    # Flags for the C++ compiler
    CPPFLAGS = ${FLAGS} -std=c++11 -Wall
    
    # Flags for the assembler
    AFLAGS = ${FLAGS} -x assembler-with-cpp
    
    # Linker flags
    LDFLAGS = ${FLAGS} -T "$(LDSCRIPT)" -Xlinker
    LDFLAGS += --gc-sections -Xlinker -Map="$(BUILDDIR)/$(TARGET)_app.map" 
    LDFLAGS += --specs=nano.specs
    
    BOOTLDFLAGS = ${FLAGS} -T "$(BOOTLDSCRIPT)" -Xlinker
    BOOTLDFLAGS += --gc-sections -Xlinker -Map="$(BUILDDIR)/$(TARGET)_boot.map" 
    BOOTLDFLAGS += --specs=nano.specs
    
    # Check whether to optimize or build for debugging
    DEBUG ?= 0
    ifeq ($(DEBUG), 1)
    	CFLAGS += -Og -g3 -gdwarf-2
    	CPPFLAGS += -Og -g3 -gdwarf-2
    	AFLAGS += -g3 -gdwarf-2
    	LDFLAGS += -g3
    else
    	CFLAGS += -O3
    	CPPFLAGS += -O3
    endif
    
    # Construct list of object files by appending the suffix .o to all source files
    OBJECTS := $(addsuffix .o,$(SOURCES))
    
    # Replace NRFX paths since objects here are going to be build in the build dir.
    OBJECTS := $(subst $(NRFXPATH),app/nrfx,$(OBJECTS))
    OBJECTS := $(subst $(SDKPATH),app/sdk-nrfxlib,$(OBJECTS))
    
    # Finally, add build directory prefix
    OBJECTS := $(addprefix $(BUILDDIR)/,$(OBJECTS))
    
    # And we to the same to the bootloader
    BOOTOBJECTS := $(addsuffix .o,$(BOOTSOURCES))
    BOOTOBJECTS := $(subst $(NRFXPATH),boot/nrfx,$(BOOTOBJECTS))
    BOOTOBJECTS := $(subst $(SDKPATH),boot/sdk-nrfxlib,$(BOOTOBJECTS))
    BOOTOBJECTS := $(addprefix $(BUILDDIR)/,$(BOOTOBJECTS))
    
    # Add -I prefix to INCLUDEDIRS and insert them into CFLAGS, CPPFLAGS and AFLAGS
    CFLAGS := $(CFLAGS) $(addprefix -I,$(INCLUDEDIRS)) 
    CPPFLAGS := $(CPPFLAGS) $(addprefix -I,$(INCLUDEDIRS))
    AFLAGS := $(AFLAGS) $(addprefix -I,$(INCLUDEDIRS)) 
    
    # Add -L prefix to LDDIRS and and insert them into LDFLAGS along with LIBS
    LDFLAGS := $(addprefix -L,$(LDDIRS)) $(LIBS) $(LDFLAGS)
    BOOTLDFLAGS := $(addprefix -L,$(LDDIRS)) $(BOOTLIBS) $(BOOTLDFLAGS)
    
    all: $(BUILDDIR)/$(TARGET).hex
    
    $(BUILDDIR)/$(TARGET).hex: $(BUILDDIR)/$(TARGET)_boot.axf $(BUILDDIR)/$(TARGET)_app.axf
    	@echo "[MERGEHEX] $^ -> $@"
    	@$(MERGEHEX) -m $^ -o $@
    	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET).bin"
    	@objcopy -I ihex -O binary $@ $(BUILDDIR)/$(TARGET).bin
    	
    $(BUILDDIR)/$(TARGET)_boot.axf: $(BOOTOBJECTS)
    	@echo "[LD] Linking boot image $@"
    	@$(LD) $(BOOTLDFLAGS) -o $@ $(BOOTOBJECTS) $(LIBS)
    	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_boot.hex"
    	@objcopy -O ihex $@ $(BUILDDIR)/$(TARGET)_boot.hex
    	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_boot.bin"
    	@objcopy -I ihex -O binary $(BUILDDIR)/$(TARGET)_boot.hex $(BUILDDIR)/$(TARGET)_boot.bin
    	@$(SIZETOOL) $@
    	
    $(BUILDDIR)/$(TARGET)_app.axf: $(OBJECTS) 
    	@echo "[LD] Linking app image $@"
    	@$(LD) $(LDFLAGS) -DNRF_TRUSTZONE_NONSECURE -o $@ $(OBJECTS) $(LIBS)
    	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_app.hex"
    	@objcopy -O ihex $@ $(BUILDDIR)/$(TARGET)_app.hex
    	@echo "[OBJCOPY] $@ -> $(BUILDDIR)/$(TARGET)_app.bin"
    	@objcopy -I ihex -O binary $(BUILDDIR)/$(TARGET)_app.hex $(BUILDDIR)/$(TARGET)_app.bin
    	@$(SIZETOOL) $@
    	
    # Recipe for building C objects in the bootloader
    $(BUILDDIR)/boot/%.c.o: boot/%.c
    	@echo "[CC] $< -> $@"
    	@mkdir -p $(@D)
    	$(CC) $(SFLAGS) $(CFLAGS) -c $< -o $@
    
    # Recipe for building C++ objects in the bootloader
    $(BUILDDIR)/boot/%.cpp.o: boot/%.cpp
    	@echo "[CPP] $< -> $@"
    	@mkdir -p $(@D)
    	@$(CPP) $(SFLAGS) $(CPPFLAGS) -c $< -o $@
    
    # Recipe for assembling objects in the bootloader
    $(BUILDDIR)/boot/%.S.o: /boot/%.S
    	@echo "[AS] $< -> $@"
    	@mkdir -p $(@D)
    	@$(AS) $(SFLAGS) $(AFLAGS) -c $< -o $@
    
    # Recipe for building C objects in $(NRFXPATH) for the bootloader
    $(BUILDDIR)/boot/nrfx/%.c.o: $(NRFXPATH)/%.c
    	@echo "[CC] $< -> $@"
    	@mkdir -p $(@D)
    	@$(CC) $(SFLAGS) $(CFLAGS) -c $< -o $@
    
    # Recipe for assembling objects in $(NRFXPATH) for the bootloader
    $(BUILDDIR)/boot/nrfx/%.S.o: $(NRFXPATH)/%.S
    	@echo "[AS] $< -> $@"
    	@mkdir -p $(@D)
    	@$(AS) $(SFLAGS) $(AFLAGS) -c $< -o $@
    
    # Recipe for building C objects in the application
    $(BUILDDIR)/app/%.c.o: app/%.c
    	@echo "[CC] $< -> $@"
    	@mkdir -p $(@D)
    	@$(CC) $(NSFLAGS) $(CFLAGS) -c $< -o $@
    	
    # Recipe for building C++ objects in the application
    $(BUILDDIR)/app/%.cpp.o: app/%.cpp
    	@echo "[CPP] $< -> $@"
    	@mkdir -p $(@D)
    	@$(CPP) $(NSFLAGS) $(CPPFLAGS) -c $< -o $@
    
    # Recipe for assembling objects in the application
    $(BUILDDIR)/app/%.S.o: app/%.S
    	@echo "[AS] $< -> $@"
    	@mkdir -p $(@D)
    	@$(AS) $(NSFLAGS) $(AFLAGS) -c $< -o $@
    
    # Recipe for building C objects in $(NRFXPATH) for the application
    $(BUILDDIR)/app/nrfx/%.c.o: $(NRFXPATH)/%.c
    	@echo "[CC] $< -> $@"
    	@mkdir -p $(@D)
    	@$(CC) $(NSFLAGS) $(CFLAGS) -c $< -o $@
    
    # Recipe for assembling objects in $(NRFXPATH) for the application
    $(BUILDDIR)/app/nrfx/%.S.o: $(NRFXPATH)/%.S
    	@echo "[AS] $< -> $@"
    	@mkdir -p $(@D)
    	@$(AS) $(NSFLAGS) $(AFLAGS) -c $< -o $@
    
    .PHONY: clean flash erase debug
    
    # Remove all build files
    clean:
    	@echo "Removing $(BUILDDIR)"
    	@rm -dfr $(BUILDDIR)
    	
    # Flash the program
    flash: $(BUILDDIR)/$(TARGET).hex
    	@echo Flashing $(BUILDDIR)/$(TARGET).hex
    	@$(NRFJPROG) -f nrf91 --program $(BUILDDIR)/$(TARGET).hex --sectorerase \
    	--verify --reset
    
    # Erase all flash
    erase:
    	@echo Erasing all flash
    	@$(NRFJPROG) -f nrf91 --eraseall
    
    # Shortcut for debugging
    debug: $(BUILDDIR)/$(TARGET).hex
    	@echo "Run /opt/SEGGER/JLink/JLinkGDBServerCLExe -device nrf9160_xxaa -if swd -port 2331"
    	@$(DB) -x gdb_cmds.txt
    

    Long GDB output with manual stepping

    Target interface speed set to 2000 kHz
    Flash download enabled
    Loading section .sec1, size 0xa74 lma 0x0
    Loading section .sec2, size 0x29a0 lma 0x10000
    Start address 0x0, load size 13332
    Transfer rate: 106656 bits in <1 sec, 6666 bytes/write.
    Breakpoint 1 at 0x7d4: main. (2 locations)
    Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
    
    Breakpoint 1, main () at boot/main.c:9
    9	{
    (gdb) break app/nrf_modem_os.c:62
    Breakpoint 2 at 0x106b4: file app/nrf_modem_os.c, line 62.
    (gdb) continue
    Continuing.
    
    Breakpoint 1, main () at app/main.c:68
    68	{
    (gdb) continue
    Continuing.
    
    Breakpoint 2, nrf_modem_os_init () at app/nrf_modem_os.c:62
    62	    nrf_modem_os_inside_isr = false;
    (gdb) step
    nrf_modem_init (params=0x125c8 <init_params>, mode=mode@entry=NORMAL_MODE) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:237
    237	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_platform_init (params=0x125c8 <init_params>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:237
    237	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c
    (gdb) step
    73	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c
    (gdb) step
    rpc_init (init_param=init_param@entry=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c:111
    111	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c: No such file or directory.
    (gdb) step
    nrf_modem_os_sem_init (sem=sem@entry=0x200184d0 <rpc_ready_sem>, initial_count=initial_count@entry=0, limit=limit@entry=1) at app/nrf_modem_os.c:174
    174	    return 0;
    (gdb) step
    rpc_init (init_param=init_param@entry=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c:112
    112	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c: No such file or directory.
    (gdb) step
    117	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/framework/rpc_framework.c
    (gdb) step
    rpc_transport_init (init_param=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/rpc_transport.c:47
    47	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/rpc_transport.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_init (init_param=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:683
    683	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    nrfx_ipc_init (irq_priority=0 '\000', handler=handler@entry=0x1110d <ipc_irq_handler>, p_context=p_context@entry=0x0 <__isr_vector>) at app/nrfx_ipc.c:59
    59	    if (m_ipc_cb.state != NRFX_DRV_STATE_UNINITIALIZED)
    (gdb) step
    65	    NVIC_SetPriority(IPC_IRQn, irq_priority);
    (gdb) step
    __NVIC_SetPriority (priority=0, IRQn=IPC_IRQn) at /opt/CMSIS_5/CMSIS/Core/Include/core_cm33.h:2591
    2591	    NVIC->IPR[((uint32_t)IRQn)]               = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
    (gdb) step
    nrfx_ipc_init (irq_priority=<optimized out>, handler=handler@entry=0x1110d <ipc_irq_handler>, p_context=p_context@entry=0x0 <__isr_vector>) at app/nrfx_ipc.c:67
    67	    NVIC_EnableIRQ(IPC_IRQn);
    (gdb) step
    __NVIC_EnableIRQ (IRQn=IPC_IRQn) at /opt/CMSIS_5/CMSIS/Core/Include/core_cm33.h:2395
    2395	    NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
    (gdb) step
    nrfx_ipc_init (irq_priority=<optimized out>, handler=handler@entry=0x1110d <ipc_irq_handler>, p_context=p_context@entry=0x0 <__isr_vector>) at app/nrfx_ipc.c:69
    69	    m_ipc_cb.state = NRFX_DRV_STATE_INITIALIZED;
    (gdb) step
    70	    m_ipc_cb.handler = handler;
    (gdb) step
    71	    m_ipc_cb.p_context = p_context;
    (gdb) step
    73	    return NRFX_SUCCESS;
    (gdb) step
    rpc_transport_ipc_init (init_param=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:685
    685	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    709	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=0, index=0 '\000', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=2, index=1 '\001', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=0, index=2 '\002', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=8, index=3 '\003', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=0, index=4 '\004', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=32, index=5 '\005', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=0, index=6 '\006', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    84	        nrf_ipc_send_config_set(NRF_IPC_NS, i, p_config->send_task_config[i]);
    (gdb) step
    nrf_ipc_send_config_set (channels_mask=0, index=7 '\a', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:444
    444	    p_reg->SEND_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:82
    82	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=1, index=0 '\000', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=0, index=1 '\001', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=4, index=2 '\002', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=0, index=3 '\003', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=16, index=4 '\004', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=0, index=5 '\005', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=64, index=6 '\006', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    89	        nrf_ipc_receive_config_set(NRF_IPC_NS, i, 
    (gdb) step
    nrf_ipc_receive_config_set (channels_mask=128, index=7 '\a', p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:456
    456	    p_reg->RECEIVE_CNF[index] = channels_mask;
    (gdb) step
    nrfx_ipc_config_load (p_config=p_config@entry=0x2003df5c) at app/nrfx_ipc.c:87
    87	    for (i = 0; i < IPC_CONF_NUM; ++i)
    (gdb) step
    93	    nrf_ipc_int_enable(NRF_IPC_NS, p_config->receive_events_enabled);
    (gdb) step
    nrf_ipc_int_enable (mask=213, p_reg=0x4002a000) at /opt/nrfx-2.10.0/hal/nrf_ipc.h:396
    396	    p_reg->INTENSET = mask;
    (gdb) step
    rpc_transport_ipc_init (init_param=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:711
    711	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_shmem_init (cfg=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:711
    711	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    573	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    579	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    __memset_ichk (len=1256, src=0, dst=0x20010000) at /tools/ncs/toolchains/v2.1.0/opt/zephyr-sdk/arm-zephyr-eabi/arm-zephyr-eabi/sys-include/ssp/string.h:86
    86	/tools/ncs/toolchains/v2.1.0/opt/zephyr-sdk/arm-zephyr-eabi/arm-zephyr-eabi/sys-include/ssp/string.h: No such file or directory.
    (gdb) step
    rpc_transport_ipc_shmem_init (cfg=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:584
    584	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    585	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    587	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    588	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    591	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    597	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_shmem_init (cfg=0x2003dfd8) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:632
    632	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    634	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    641	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    642	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    643	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    644	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    645	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    652	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:653
    653	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_shmem_init (cfg=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:671
    671	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrfx_ipc_gpmem_set (data=536936448, mem_index=0 '\000') at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:671
    671	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_ipc_gpmem_set (data=536936448, index=0 '\000', p_reg=0x4002a000) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/modules/hal/nordic/nrfx/hal/nrf_ipc.h:470
    470	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/modules/hal/nordic/nrfx/hal/nrf_ipc.h: No such file or directory.
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:716
    716	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    717	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_reset_clear () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:532
    532	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_reset_clear () at ../../../include/nrf_modem_control.h:67
    67	../../../include/nrf_modem_control.h: No such file or directory.
    (gdb) step
    70	in ../../../include/nrf_modem_control.h
    (gdb) step
    71	in ../../../include/nrf_modem_control.h
    (gdb) step
    75	in ../../../include/nrf_modem_control.h
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:533
    533	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) step
    nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    279	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:536
    536	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    533	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) step
    nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    279	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:536
    536	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    533	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) step
    nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    279	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:536
    536	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    533	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) step
    nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    279	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:536
    536	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    533	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) step
    nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    279	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:536
    536	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    533	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) step
    nrf_modem_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c:279
    279	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem.c: No such file or directory.
    (gdb) step
    nrf_modem_state_is_initialized () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c:23
    23	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/platform/nrf_modem_state.c: No such file or directory.
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:536
    536	/jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c: No such file or directory.
    (gdb) step
    533	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_init (init_param=<optimized out>) at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:719
    719	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    rpc_transport_ipc_handshake () at /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c:534
    534	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    535	in /jenkins_workspace/workspace/_nrfconnect-libmodem_v2.2-branch/libmodem/rpc/transport/ipc/rpc_transport_ipc.c
    (gdb) step
    nrf_modem_os_timedwait (context=context@entry=0, timeout=timeout@entry=0x2003df54) at app/nrf_modem_os.c:104
    104	    if (! nrf_modem_is_initialized())
    (gdb) 
    

Related