SPI driver implementation

This section describes how to implement an SPI driver for QNX and walks through some of the essential functions to get started. Note that the example functions below are simple examples and shouldn't be copied literally.

Here is the interface to implement an SPI driver on QNX. You can find the full interface in hw/io-spi.h:

/* Hardware interface between io-spi and SPI device driver */
struct _spi_funcs {

    /**
     *  @brief             SPI driver cleanup function.
     *  @param  hdl        SPI driver handler.
     *
     *  @return            Void.
     */
    void (*spi_fini)(void *const hdl);

    /**
     *  @brief             Get SPI driver info function.
     *  @param  hdl        SPI driver handler.
     *  @param  info       The pointer where you want to store drvinfo.
     *
     *  @return            Void.
     */
    void (*drvinfo)(const void *const hdl, spi_drvinfo_t *info);

    /**
     *  @brief             Get SPI device info function.
     *  @param  hdl        SPI driver handler.
     *  @param  spi_dev    SPI device structure.
     *  @param  info       The pointer where you want to store devinfo.
     *
     *  @return            Void.
     */
    void (*devinfo)(const void *const hdl, const spi_dev_t *const spi_dev, spi_devinfo_t *const info);

    /**
     *  @brief             Set SPI device configuration.
     *  @param hdl         SPI driver handler.
     *  @param spi_dev     SPI device structure pointer.
     *  @param cfg         The spi_cfg_t structure which stores the config info
     *
     *  @return            EOK --success otherwise fail
     */
    int (*setcfg)(const void *const hdl, spi_dev_t *spi_dev, const spi_cfg_t *const cfg);

    /**
     *  @brief             SPI transfer function.
     *  @param hdl         SPI driver handler.
     *  @param spi_dev     SPI device structure pointer.
     *  @param buf         The buffer which stores the transfer data.
     *  @param tnbytes     The number of transmit bytes.
     *  @param rnbytes     The number of receive bytes.
     *
     *  @return            EOK --success otherwise fail.
     */
    int (*xfer)(void *const hdl, spi_dev_t *const spi_dev, uint8_t *const buf, const uint32_t tnbytes, const uint32_t rnbytes);

    /**
     *  @brief             SPI DMA transfer function.
     *  @param hdl         SPI driver handler.
     *  @param spi_dev     SPI device structure pointer.
     *  @param addr        DMA address pointer.
     *  @param tnbytes     The number of transmit bytes.
     *  @param rnbytes     The number of receive bytes.
     *
     *  @return            EOK --success otherwise fail.
     */
    int (*dma_xfer)(void *const hdl, spi_dev_t *spi_dev, dma_addr_t *addr, const uint32_t tnbytes, const uint32_t rnbytes);

    /**
     *  @brief             Allocate DMA buffer.
     *  @param  hdl        SPI driver handler.
     *  @param  addr       DMA address pointer.
     *  @param  len        DMA buffer size.
     *
     *  @return            EOK --success otherwise fail.
     */
    int (*dma_allocbuf)(void *const hdl, dma_addr_t *addr, const uint32_t len);

    /**
     *  @brief             Free DMA buffer.
     *  @param  hdl        SPI driver handler.
     *  @param  addr       DMA address pointer.
     *
     *  @return            EOK --success otherwise fail.
     */
    int (*dma_freebuf)(void *const hdl, dma_addr_t *addr);
};

Define struct

Before making the functions, you need to define a structure that holds all necessary state information. The struct may look like this:

typedef struct {
    uint64_t    pbase;          // Physical base address
    uintptr_t   vbase;          // Virtual base address
    uint32_t    irq;            // Interrupt number
    int         iid;
    uint64_t    input_clk;      // Input clock frequency
    uint8_t     *pbuf;          // Transfer buffer
    uint32_t    tnbytes;        // Transmit bytes
    uint32_t    rnbytes;        // Receive bytes
    uint32_t    xlen;           // Full transaction length requested by client
    uint32_t    tcnt;           // Transmit counter
    uint32_t    rcnt;           // Receive counter
    uint32_t    dwidth;         // Data width. 1 = 8bits/byte, 2 = 16bits/2 bytes, 4 = 32bits/4 bytes
    spi_ctrl_t  *spi_ctrl;      // The address of spi_ctrl structure
    spi_bus_t   *bus_node;      // The address of bus structure which is passed in by spi_init()
} your_spi_t;

Clean up driver

Your driver cleanup function may look something like this:

void your_fini(void *const hdl) {
    your_spi_t *const spi = hdl;

    if (spi == NULL) {
        return;
    }

    // 1. Disable hardware
    if (spi->vbase != (uintptr_t)MAP_FAILED) {
        // Disable SPI controller
        out32(spi->vbase + YOUR_SPI_CONTROL_REG, 0);

        // Unmap registers
        munmap_device_memory((void *)spi->vbase, YOUR_SPI_REGLEN);
    }

    // 2. Free allocated memory
    free(spi);
}

Setup config driver

You need a setup config driver function to set the configuration of when the device driver starts, or when the application sets the configuration, which may look something like this:

int your_setcfg(const void *const hdl, spi_dev_t *spi_dev,const spi_cfg_t *const cfg)
{
    const your_spi_t *const spi = hdl;
    uintptr_t     const base = spi->vbase;
    uint32_t      devctrl = 0;

    /* Check hardware limitations for word width */
    switch ((cfg->mode & SPI_MODE_WORD_WIDTH_MASK)) {
        case SPI_MODE_WORD_WIDTH_32:
        case SPI_MODE_WORD_WIDTH_8:
            break;
        default:
            spi_slogf(_SLOG_ERROR, "%s: %d-bit word width is not supported by this controller",
                                __func__, cfg->mode & SPI_MODE_WORD_WIDTH_MASK);
            return EINVAL;
    }

    /* Gather default CS and clock polarity related configuration */
    if (cfg->mode & SPI_MODE_CSPOL_HIGH) {
        devctrl |= (SPI_CS_CSPOL_HIGH << SPI_CS_CSPOL);   /* CS Polarity: CS active high */
    }

    if (cfg->mode & SPI_MODE_CPOL_1) {
        devctrl |= (SPI_CS_CPOL_HIGH << SPI_CS_CPOL);     /* Clock Polarity: Rest state of clock high */
    }

    if (cfg->mode & SPI_MODE_CPHA_1) {
        devctrl |= (SPI_CS_CPHA_BEGIN << SPI_CS_CPHA);    /* Clock Phase: SCLK beginning of data bit */
    }

    /* Set SPI_CLK only when it is different than current clock rate */
    if (spi_dev->devinfo.current_clkrate != cfg->clock_rate) {
        uint32_t actual_rate = spi_set_clock(spi, cfg, base);
        if (actual_rate == 0) {
            spi_slogf(_SLOG_ERROR, "%s: Clock configuration failed", __func__);
            return EINVAL;
        }

        /* Update current clock rate with actual achieved rate */
        cfg->clock_rate = actual_rate;
        spi_dev->devinfo.current_clkrate = actual_rate;
    } else {
        spi_slogf(_SLOG_DEBUG2, "%s: Device clock rate is already set to %d", __func__, cfg->clock_rate);
    }

    /* Add Chip Select/Physical device ID */
    devctrl |= spi_dev->devinfo.devno;

    /* Update the SPI device devctrl reg value */
    spi_dev->devctrl = devctrl;

    spi_slogf(_SLOG_DEBUG1, "%s: sclk=%d, devctrl=0x%x", __func__,
              cfg->clock_rate, devctrl);

    return EOK;
}

/*
 * NOTE: The following function must be implemented according to your specific hardware:
 * - spi_set_clock(): Set the SPI clock rate
 */

Exchange data

You need a function to exchange data between the master and the slave. The function may look something like this:

int your_xfer(void *const hdl, spi_dev_t *const spi_dev, uint8_t *const buf, const uint32_t tnbytes, const uint32_t rnbytes)
{
    your_spi_t *const spi = hdl;
    const uintptr_t base = spi->vbase;
    const spi_cfg_t *const cfg = &spi_dev->devinfo.cfg;
    int status = EOK;

    /* Set transfer parameters based on operation type */
    if (tnbytes == 0) {
        /* Read only */
        spi->tnbytes = rnbytes;
        spi->rnbytes = rnbytes;
    } else if (rnbytes == 0) {
        /* Write only */
        spi->tnbytes = tnbytes;
        spi->rnbytes = tnbytes;
    } else {
        /* Bidirectional transaction */
        spi->tnbytes = tnbytes;
        spi->rnbytes = rnbytes;
    }

    /* Capture max transaction length requested by client */
    spi->xlen = max(spi->tnbytes, spi->rnbytes);

    /* Setup transfer parameters */
    spi->dwidth = ((cfg->mode & SPI_MODE_WORD_WIDTH_MASK) >> 3);
    spi->rcnt = 0;
    spi->tcnt = 0;
    spi->pbuf = buf;

    /* Reset the SPI interface
     * Clear both FIFOs
     */
    out32((base + YOUR_SPI_CS), YOUR_SPI_RESET);
    out32((base + YOUR_SPI_CS), YOU_SPI_FIFO_CLEAR);

    /* Enable SPI transfer */
    spi_enable(spi, spi_dev->devctrl);

    /* Fill TX FIFO with data */
    while ((spi->tcnt < spi->tnbytes) && (spi->tcnt < YOUR_SPI_FIFOLEN)) {
        spi_write_fifo(spi, *(spi->pbuf + spi->tcnt));
        spi->tcnt += spi->dwidth;
    }

    /* Wait for transfer completion */
    status = spi_wait_complete(spi);

    /* Disable SPI */
    spi_disable(spi);

    return status;
}

/*
* NOTE: The following functions must be implemented according to your specific hardware:
* - spi_enable(): Enable SPI
* - spi_write_fifo(): Write a byte to the TX FIFO
* - spi_wait_complete(): Wait for transfer completion with appropriate timeout
* - spi_disable(): Disable SPI controller and interrupts
*/

Initialize the driver

Finally, after making the essential functions to make the driver, you can integrate these functions in the spi_init() function to make the driver. This spi_init() function is called when the driver is started by the user. The function may look something like this:

static int init_device(your_spi_t *spi)
{
    int             status;
    uintptr_t       base;
    spi_bus_t       *const bus = spi->bus_node;
    spi_dev_t       *spi_dev = bus->devlist;

    /*
     * Map in SPI registers
     */
    base = (uintptr_t)mmap(NULL, YOUR_SPI_REGLEN, PROT_READ | PROT_WRITE | PROT_NOCACHE, MAP_PHYS | MAP_SHARED, NOFD, (off_t)spi->pbase);
    if (base == (uintptr_t)MAP_FAILED) {
        spi_slogf(_SLOG_ERROR, "%s: Failed to map SPI registers(%s)", __func__, strerror(errno));
        return errno;
    }

    spi->vbase = base;

    /* Reset the SPI interface
     * Clear both FIFOs
     */
    out32((base + YOUR_SPI_CS), YOUR_SPI_RESET);
    out32((base + YOUR_SPI_CS), YOU_SPI_FIFO_CLEAR);

    /*
     * Initial device configuration with defaults from config file
     */
    while (spi_dev != NULL) {
        status = your_setcfg(spi, spi_dev, &spi_dev->devinfo.cfg);
        if (status != EOK) {
            spi_slogf(_SLOG_ERROR, "%s: your_setcfg failed", __func__);
            return status;
        }
        spi_dev = spi_dev->next;
    }

    /* Attach SPI interrupt */
    spi->iid = InterruptAttachEvent(spi->irq, &bus->evt, _NTO_INTR_FLAGS_TRK_MSK);

    return status;
}


int spi_init(spi_bus_t *bus)
{
    your_spi_t *spi = NULL;
    int           status = EOK;

    if (bus == NULL) {
        spi_slogf(_SLOG_ERROR, "%s: SPI bus structure is NULL!", __func__);
        return EINVAL;
    }

    spi = calloc(1, sizeof(your_spi_t));

    /* Save spi_ctrl to driver structure */
    spi->spi_ctrl = bus->spi_ctrl;
    spi->bus_node = bus;

    /* Get other SPI driver functions */
    bus->funcs->spi_fini = your_fini;
    bus->funcs->drvinfo  = your_drvinfo;
    bus->funcs->devinfo = your_devinfo;
    bus->funcs->setcfg = your_setcfg;
    bus->funcs->xfer  = your_xfer;
    bus->funcs->dma_xfer  = NULL;
    bus->funcs->dma_allocbuf = NULL;
    bus->funcs->dma_freebuf = NULL;

    /* Get controller parameters */
    spi->pbase = bus->pbase;
    spi->irq = bus->irq;
    spi->input_clk = bus->input_clk;

    /* Update SPI transaction buffer boundary */
    bus->buf_max = SPI_BUF_MAX_64K;

    spi->iid = -1;
    spi->vbase = (uintptr_t)MAP_FAILED;

    /* Optional: Process custom arguments to your driver to override the defaults */
    if (bus->bs != NULL) {
        status = process_args(spi, bus->bs);
        if (status != EOK) {
            spi_slogf(_SLOG_ERROR, "%s: process_args failed", __func__);
            your_fini(spi);
            return status;
        }
    }

    /* Init SPI device */
    status = init_device(spi);
    if (status != EOK) {
        spi_slogf(_SLOG_ERROR, "%s: init_device failed: %s", __func__, strerror(status));
        your_fini(spi);
        return status;
    }

    /*
     * Create SPI chip select devices
     */
    status = spi_create_devs(bus->devlist);
    if (status != EOK) {
        spi_slogf(_SLOG_ERROR, "%s: spi_create_devs for %s failed", __func__, bus->devlist->devinfo.name);
        your_fini(spi);
        return status;
    }

    /* Save driver structure to drvhdl */
    bus->drvhdl = spi;

    return status;
}

/*
* NOTE: Implement the following function if want your driver to have optional parameters
* - process_args(): Process custom arguments to your driver to override the defaults
*/

Porting Linux SPI driver to QNX

A typical Linux SPI driver may look like the following:

static const struct of_device_id your_spi_match[] = {
    { .compatible = "your-spi", },
    {}
};
MODULE_DEVICE_TABLE(of, your_spi_match);

static struct platform_driver your_spi_driver = {
    .driver     = {
        .name       = your-spi-driver,
        .of_match_table = your_spi_match,
    },
    .probe      = your_spi_probe,
    .remove     = your_spi_remove,
    .shutdown   = your_spi_remove,
};
module_platform_driver(your_spi_driver);

In Linux to initialize the driver and cleanup the driver you would use the probe() and remove() function. You would need to implement these functions on Linux to initialize and cleanup the driver:

static int your_spi_probe(struct platform_device *pdev) {
    /* Implement the initialization function for your driver here */
    return 0;
}
static void your_spi_remove(struct platform_device *pdev) {
    /* Implement the clean up function for your driver here */
}

The probe() and remove() function in Linux is equivalent to QNX's init() and fini() functions you've seen before.

Moreover, the Linux struct to integrate the data transfer function and other functions might look like this:

struct spi_controller {
    struct device   dev;

    struct list_head list;

    /*
     * Other than negative (== assign one dynamically), bus_num is fully
     * board-specific. Usually that simplifies to being SoC-specific.
     * example: one SoC has three SPI controllers, numbered 0..2,
     * and one board's schematics might show it using SPI-2. Software
     * would normally use bus_num=2 for that controller.
     */
    s16         bus_num;

    /*
     * Chipselects will be integral to many controllers; some others
     * might use board-specific GPIOs.
     */
    u16         num_chipselect;

    /* Some SPI controllers pose alignment requirements on DMAable
     * buffers; let protocol drivers know about these requirements.
     */
    u16         dma_alignment;

    /* spi_device.mode flags understood by this controller driver */
    u32         mode_bits;

    /* spi_device.mode flags override flags for this controller */
    u32         buswidth_override_bits;

    /* Bitmask of supported bits_per_word for transfers */
    u32         bits_per_word_mask;
#define SPI_BPW_MASK(bits) BIT((bits) - 1)
#define SPI_BPW_RANGE_MASK(min, max) GENMASK((max) - 1, (min) - 1)

    /* Limits on transfer speed */
    u32         min_speed_hz;
    u32         max_speed_hz;

    /* Other constraints relevant to this driver */
    u16         flags;
#define SPI_CONTROLLER_HALF_DUPLEX  BIT(0)  /* Can't do full duplex */
#define SPI_CONTROLLER_NO_RX        BIT(1)  /* Can't do buffer read */
#define SPI_CONTROLLER_NO_TX        BIT(2)  /* Can't do buffer write */
#define SPI_CONTROLLER_MUST_RX      BIT(3)  /* Requires rx */
#define SPI_CONTROLLER_MUST_TX      BIT(4)  /* Requires tx */
#define SPI_CONTROLLER_GPIO_SS      BIT(5)  /* GPIO CS must select target device */
#define SPI_CONTROLLER_SUSPENDED    BIT(6)  /* Currently suspended */
    /*
     * The spi-controller has multi chip select capability and can
     * assert/de-assert more than one chip select at once.
     */
#define SPI_CONTROLLER_MULTI_CS     BIT(7)

    /* Flag indicating if the allocation of this struct is devres-managed */
    bool            devm_allocated;

    union {
        /* Flag indicating this is an SPI slave controller */
        bool            slave;
        /* Flag indicating this is an SPI target controller */
        bool            target;
    };

    /*
     * On some hardware transfer / message size may be constrained
     * the limit may depend on device transfer settings.
     */
    size_t (*max_transfer_size)(struct spi_device *spi);
    size_t (*max_message_size)(struct spi_device *spi);

    /* I/O mutex */
    struct mutex        io_mutex;

    /* Used to avoid adding the same CS twice */
    struct mutex        add_lock;

    /* Lock and mutex for SPI bus locking */
    spinlock_t      bus_lock_spinlock;
    struct mutex        bus_lock_mutex;

    /* Flag indicating that the SPI bus is locked for exclusive use */
    bool            bus_lock_flag;

    /*
     * Setup mode and clock, etc (SPI driver may call many times).
     *
     * IMPORTANT:  this may be called when transfers to another
     * device are active.  DO NOT UPDATE SHARED REGISTERS in ways
     * which could break those transfers.
     */
    int         (*setup)(struct spi_device *spi);

    /*
     * set_cs_timing() method is for SPI controllers that supports
     * configuring CS timing.
     *
     * This hook allows SPI client drivers to request SPI controllers
     * to configure specific CS timing through spi_set_cs_timing() after
     * spi_setup().
     */
    int (*set_cs_timing)(struct spi_device *spi);

    /*
     * Bidirectional bulk transfers
     *
     * + The transfer() method may not sleep; its main role is
     *   just to add the message to the queue.
     * + For now there's no remove-from-queue operation, or
     *   any other request management
     * + To a given spi_device, message queueing is pure FIFO
     *
     * + The controller's main job is to process its message queue,
     *   selecting a chip (for controllers), then transferring data
     * + If there are multiple spi_device children, the i/o queue
     *   arbitration algorithm is unspecified (round robin, FIFO,
     *   priority, reservations, preemption, etc)
     *
     * + Chipselect stays active during the entire message
     *   (unless modified by spi_transfer.cs_change != 0).
     * + The message transfers use clock and SPI mode parameters
     *   previously established by setup() for this device
     */
    int         (*transfer)(struct spi_device *spi,
                        struct spi_message *mesg);

    /* Called on release() to free memory provided by spi_controller */
    void            (*cleanup)(struct spi_device *spi);

    /*
     * Used to enable core support for DMA handling, if can_dma()
     * exists and returns true then the transfer will be mapped
     * prior to transfer_one() being called.  The driver should
     * not modify or store xfer and dma_tx and dma_rx must be set
     * while the device is prepared.
     */
    bool            (*can_dma)(struct spi_controller *ctlr,
                       struct spi_device *spi,
                       struct spi_transfer *xfer);
    struct device *dma_map_dev;
    struct device *cur_rx_dma_dev;
    struct device *cur_tx_dma_dev;

    /*
     * These hooks are for drivers that want to use the generic
     * controller transfer queueing mechanism. If these are used, the
     * transfer() function above must NOT be specified by the driver.
     * Over time we expect SPI drivers to be phased over to this API.
     */
    bool                queued;
    struct kthread_worker       *kworker;
    struct kthread_work     pump_messages;
    spinlock_t          queue_lock;
    struct list_head        queue;
    struct spi_message      *cur_msg;
    struct completion               cur_msg_completion;
    bool                cur_msg_incomplete;
    bool                cur_msg_need_completion;
    bool                busy;
    bool                running;
    bool                rt;
    bool                auto_runtime_pm;
    bool                            fallback;
    bool                last_cs_mode_high;
    s8              last_cs[SPI_CS_CNT_MAX];
    u32             last_cs_index_mask : SPI_CS_CNT_MAX;
    struct completion               xfer_completion;
    size_t              max_dma_len;

    int (*optimize_message)(struct spi_message *msg);
    int (*unoptimize_message)(struct spi_message *msg);
    int (*prepare_transfer_hardware)(struct spi_controller *ctlr);
    int (*transfer_one_message)(struct spi_controller *ctlr,
                    struct spi_message *mesg);
    int (*unprepare_transfer_hardware)(struct spi_controller *ctlr);
    int (*prepare_message)(struct spi_controller *ctlr,
                   struct spi_message *message);
    int (*unprepare_message)(struct spi_controller *ctlr,
                 struct spi_message *message);
    int (*target_abort)(struct spi_controller *ctlr);

    /*
     * These hooks are for drivers that use a generic implementation
     * of transfer_one_message() provided by the core.
     */
    void (*set_cs)(struct spi_device *spi, bool enable);
    int (*transfer_one)(struct spi_controller *ctlr, struct spi_device *spi,
                struct spi_transfer *transfer);
    void (*handle_err)(struct spi_controller *ctlr,
               struct spi_message *message);

    /* Optimized handlers for SPI memory-like operations. */
    const struct spi_controller_mem_ops *mem_ops;
    const struct spi_controller_mem_caps *mem_caps;

    /* SPI or QSPI controller can set to true if supports SDR/DDR transfer rate */
    bool            dtr_caps;

    struct spi_offload *(*get_offload)(struct spi_device *spi,
                       const struct spi_offload_config *config);
    void (*put_offload)(struct spi_offload *offload);

    /* GPIO chip select */
    struct gpio_desc    **cs_gpiods;
    bool            use_gpio_descriptors;
    s8          unused_native_cs;
    s8          max_native_cs;

    /* Statistics */
    struct spi_statistics __percpu  *pcpu_statistics;

    /* DMA channels for use with core dmaengine helpers */
    struct dma_chan     *dma_tx;
    struct dma_chan     *dma_rx;

    /* Dummy data for full duplex devices */
    void            *dummy_rx;
    void            *dummy_tx;

    int (*fw_translate_cs)(struct spi_controller *ctlr, unsigned cs);

    /*
     * Driver sets this field to indicate it is able to snapshot SPI
     * transfers (needed e.g. for reading the time of POSIX clocks)
     */
    bool            ptp_sts_supported;

    /* Interrupt enable state during PTP system timestamping */
    unsigned long       irq_flags;

    /* Flag for enabling opportunistic skipping of the queue in spi_sync */
    bool            queue_empty;
    bool            must_async;
    bool            defer_optimize_message;
};

And the integrations to the functions you have made typically happens in the probe() function:

static int your_spi_probe(struct platform_device *pdev)
{
    /* Implemention to initialize the driver */

    struct spi_controller *ctlr;

    ctlr->use_gpio_descriptors = true;
    ctlr->mode_bits = YOUR_SPI_MODE_BITS;
    ctlr->bits_per_word_mask = SPI_BPW_MASK(8);
    ctlr->num_chipselect = 3;
    ctlr->max_transfer_size = your_spi_max_transfer_size;
    ctlr->setup = your_spi_setup;
    ctlr->cleanup = your_spi_cleanup;
    ctlr->transfer_one = your_spi_transfer_one;
    ctlr->handle_err = your_spi_handle_err;
    ctlr->prepare_message = your_spi_prepare_message;
    ctlr->dev.of_node = pdev->dev.of_node;

    /* The rest of the implementation */

    return 0;
}

And these functions must be implemented to be integrated into the spi_controller struct. and may look like this:

static int your_spi_setup(struct spi_device *spi)
{
    /* Implement the setup function for your driver here */
    return 0;
}

static int your_spi_transfer_one(struct spi_controller *ctlr,
                    struct spi_device *spi,
                    struct spi_transfer *tfr)
{
    /* Implement the transfer function for your driver here */
    return 0;
}

/* Rest of the functions */

The integration of the driver function in Linux happens in the i2c_algorithm struct. In QNX, to integrate the functions you've created, you have to initialize the function in the spi_bus_t struct inside the spi_init() function, as previously mentioned.

After the Linux driver is developed, the driver is then loaded into the kernel as modules to be used. However, in QNX, you don't have to load it into the kernel. In fact, you can just start the driver just like any other user application.

Page updated: