Proswift with BLE EV-BL652ARDZ

Fork of ADISense1000_Example_FW by Analog Devices

src/adi_sense_1000.c

Committer:
seanwilson10
Date:
2018-01-25
Revision:
0:76fed7dd9235

File content as of revision 0:76fed7dd9235:

/*!
 ******************************************************************************
 * @file:  adi_sense_1000.c
 * @brief: ADI Sense API implementation for ADI Sense 1000
 *-----------------------------------------------------------------------------
 */

/******************************************************************************
Copyright 2017 (c) Analog Devices, Inc.

All rights reserved.

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
  - Redistributions of source code must retain the above copyright
    notice, this list of conditions and the following disclaimer.
  - Redistributions in binary form must reproduce the above copyright
    notice, this list of conditions and the following disclaimer in
    the documentation and/or other materials provided with the
    distribution.
  - Neither the name of Analog Devices, Inc. nor the names of its
    contributors may be used to endorse or promote products derived
    from this software without specific prior written permission.
  - The use of this software may or may not infringe the patent rights
    of one or more patent holders. This license does not release you
    from the requirement that you obtain separate licenses from these
    patent holders to use this software.
  - Use of the software either in source or binary form, must be run
    on or directly connected to an Analog Devices Inc. component.

THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, 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 <float.h>
#include <math.h>
#include <string.h>

#include "inc/adi_sense_platform.h"
#include "inc/adi_sense_api.h"
#include "inc/adi_sense_1000/adi_sense_1000_api.h"

#include "adi_sense_1000/ADISENSE1000_REGISTERS_typedefs.h"
#include "adi_sense_1000/ADISENSE1000_REGISTERS.h"
#include "adi_sense_1000/adi_sense_1000_lut_data.h"
#include "adi_sense_1000/adi_sense_1000_calibration.h"

#include "crc16.h"

/*
 * The host is expected to transfer a 16-bit command, followed by data bytes, in 2
 * separate transfers delineated by the CS signal and a short delay in between.
 *
 * The 16-bit command contains a right-justified 11-bit register address (offset),
 * and the remaining upper 5 bits are reserved as command bits assigned as follows:
 * [15:11] 10000b = write command, 01000b = read command, anything else is invalid
 * [10:0]  register address (0-2047)
 */

/* Register address space is limited to 2048 bytes (11 bit address) */
#define REG_COMMAND_MASK 0xF800
#define REG_ADDRESS_MASK 0x07FF

/*
 * The following commands are currently supported, anything else is treated
 * as an error
 */
#define REG_WRITE_COMMAND 0x8000
#define REG_READ_COMMAND  0x4000

/*
 * The following bytes are sent back to the host when a command is recieved,
 * to be used by the host to verify that we were ready to receive the command.
 */
#define REG_COMMAND_RESP_0 0xF0
#define REG_COMMAND_RESP_1 0xE1

/*
 * The following minimum delay must be inserted after each SPI transfer to allow
 * time for it to be processed by the device
 */
#define POST_SPI_TRANSFER_DELAY_USEC (20)

/*
 * The following macros are used to encapsulate the register access code
 * to improve readability in the functions further below in this file
 */
#define STRINGIFY(name) #name

/* Expand the full name of the reset value macro for the specified register */
#define REG_RESET_VAL(_name) REG_ADISENSE_##_name##_RESET

/* Checks if a value is outside the bounds of the specified register field */
#define CHECK_REG_FIELD_VAL(_field, _val)                               \
    do {                                                                \
        uint32_t _mask  = BITM_ADISENSE_##_field;                       \
        uint32_t _shift = BITP_ADISENSE_##_field;                       \
        if ((((_val) << _shift) & ~(_mask)) != 0) {                     \
            ADI_SENSE_LOG_ERROR("Value 0x%08X invalid for register field %s", \
                                (uint32_t)(_val),                       \
                                STRINGIFY(ADISENSE_##_field));          \
            return ADI_SENSE_INVALID_PARAM;                             \
        }                                                               \
    } while(false)

/*
 * Encapsulates the write to a specified register
 * NOTE - this will cause the calling function to return on error
 */
#define WRITE_REG(_hdev, _val, _name, _type)                            \
    do {                                                                \
        ADI_SENSE_RESULT _res;                                          \
        _type _regval = _val;                                           \
        _res = adi_sense_1000_WriteRegister((_hdev),                    \
                                            REG_ADISENSE_##_name,       \
                                            &_regval, sizeof(_regval)); \
        if (_res != ADI_SENSE_SUCCESS)                                  \
            return _res;                                                \
    } while(false)

/* Wrapper macro to write a value to a uint32_t register */
#define WRITE_REG_U32(_hdev, _val, _name)       \
    WRITE_REG(_hdev, _val, _name, uint32_t)
/* Wrapper macro to write a value to a uint16_t register */
#define WRITE_REG_U16(_hdev, _val, _name)       \
    WRITE_REG(_hdev, _val, _name, uint16_t)
/* Wrapper macro to write a value to a uint8_t register */
#define WRITE_REG_U8(_hdev, _val, _name)        \
    WRITE_REG(_hdev, _val, _name, uint8_t)
/* Wrapper macro to write a value to a float32_t register */
#define WRITE_REG_FLOAT(_hdev, _val, _name)     \
    WRITE_REG(_hdev, _val, _name, float32_t)

/*
 * Encapsulates the read from a specified register
 * NOTE - this will cause the calling function to return on error
 */
#define READ_REG(_hdev, _val, _name, _type)                             \
    do {                                                                \
        ADI_SENSE_RESULT _res;                                          \
        _type _regval;                                                  \
        _res = adi_sense_1000_ReadRegister((_hdev),                     \
                                           REG_ADISENSE_##_name,        \
                                           &_regval, sizeof(_regval));  \
        if (_res != ADI_SENSE_SUCCESS)                                  \
            return _res;                                                \
        _val = _regval;                                                 \
    } while(false)

/* Wrapper macro to read a value from a uint32_t register */
#define READ_REG_U32(_hdev, _val, _name)        \
    READ_REG(_hdev, _val, _name, uint32_t)
/* Wrapper macro to read a value from a uint16_t register */
#define READ_REG_U16(_hdev, _val, _name)        \
    READ_REG(_hdev, _val, _name, uint16_t)
/* Wrapper macro to read a value from a uint8_t register */
#define READ_REG_U8(_hdev, _val, _name)         \
    READ_REG(_hdev, _val, _name, uint8_t)
/* Wrapper macro to read a value from a float32_t register */
#define READ_REG_FLOAT(_hdev, _val, _name)      \
    READ_REG(_hdev, _val, _name, float32_t)

/*
 * Wrapper macro to write an array of values to a uint8_t register
 * NOTE - this is intended only for writing to a keyhole data register
 */
#define WRITE_REG_U8_ARRAY(_hdev, _arr, _len, _name)                \
    do {                                                            \
        ADI_SENSE_RESULT _res;                                      \
        _res = adi_sense_1000_WriteRegister(_hdev,                  \
                                            REG_ADISENSE_##_name,   \
                                            _arr, _len);            \
        if (_res != ADI_SENSE_SUCCESS)                              \
            return _res;                                            \
    } while(false)

/*
 * Wrapper macro to read an array of values from a uint8_t register
 * NOTE - this is intended only for reading from a keyhole data register
 */
#define READ_REG_U8_ARRAY(_hdev, _arr, _len, _name)                 \
    do {                                                            \
        ADI_SENSE_RESULT _res;                                      \
        _res = adi_sense_1000_ReadRegister((_hdev),                 \
                                           REG_ADISENSE_##_name,    \
                                           _arr, _len);             \
        if (_res != ADI_SENSE_SUCCESS)                              \
            return _res;                                            \
    } while(false)

#define ADI_SENSE_1000_CHANNEL_IS_ADC(c)                                \
    ((c) >= ADI_SENSE_1000_CHANNEL_ID_CJC_0 && (c) <= ADI_SENSE_1000_CHANNEL_ID_CURRENT_0)

#define ADI_SENSE_1000_CHANNEL_IS_ADC_CJC(c)                            \
    ((c) >= ADI_SENSE_1000_CHANNEL_ID_CJC_0 && (c) <= ADI_SENSE_1000_CHANNEL_ID_CJC_1)

#define ADI_SENSE_1000_CHANNEL_IS_ADC_SENSOR(c)                         \
    ((c) >= ADI_SENSE_1000_CHANNEL_ID_SENSOR_0 && (c) <= ADI_SENSE_1000_CHANNEL_ID_SENSOR_3)

#define ADI_SENSE_1000_CHANNEL_IS_ADC_VOLTAGE(c)    \
    ((c) == ADI_SENSE_1000_CHANNEL_ID_VOLTAGE_0)

#define ADI_SENSE_1000_CHANNEL_IS_ADC_CURRENT(c)    \
    ((c) == ADI_SENSE_1000_CHANNEL_ID_CURRENT_0)

#define ADI_SENSE_1000_CHANNEL_IS_VIRTUAL(c)                            \
    ((c) == ADI_SENSE_1000_CHANNEL_ID_SPI_1 || (c) == ADI_SENSE_1000_CHANNEL_ID_SPI_2)

typedef struct
{
    unsigned nDeviceIndex;
    ADI_SENSE_SPI_HANDLE hSpi;
    ADI_SENSE_GPIO_HANDLE hGpio;
} ADI_SENSE_DEVICE_CONTEXT;

static ADI_SENSE_DEVICE_CONTEXT gDeviceCtx[ADI_SENSE_PLATFORM_MAX_DEVICES];

/*
 * Open an ADI Sense device instance.
 */
ADI_SENSE_RESULT adi_sense_Open(
    unsigned                   const nDeviceIndex,
    ADI_SENSE_CONNECTION     * const pConnectionInfo,
    ADI_SENSE_DEVICE_HANDLE  * const phDevice)
{
    ADI_SENSE_DEVICE_CONTEXT *pCtx;
    ADI_SENSE_RESULT eRet;

    if (nDeviceIndex >= ADI_SENSE_PLATFORM_MAX_DEVICES)
        return ADI_SENSE_INVALID_DEVICE_NUM;

    pCtx = &gDeviceCtx[nDeviceIndex];
    pCtx->nDeviceIndex = nDeviceIndex;

    eRet = adi_sense_LogOpen();
    if (eRet != ADI_SENSE_SUCCESS)
        return eRet;

    eRet = adi_sense_GpioOpen(&pConnectionInfo->gpio, &pCtx->hGpio);
    if (eRet != ADI_SENSE_SUCCESS)
        return eRet;

    eRet = adi_sense_SpiOpen(&pConnectionInfo->spi, &pCtx->hSpi);
    if (eRet != ADI_SENSE_SUCCESS)
        return eRet;

    *phDevice = pCtx;
    return ADI_SENSE_SUCCESS;
}

/*
 * Get the current state of the specified GPIO input signal.
 */
ADI_SENSE_RESULT adi_sense_GetGpioState(
    ADI_SENSE_DEVICE_HANDLE   const hDevice,
    ADI_SENSE_GPIO_PIN        const ePinId,
    bool_t                  * const pbAsserted)
{
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;

    return adi_sense_GpioGet(pCtx->hGpio, ePinId, pbAsserted);
}

/*
 * Register an application-defined callback function for GPIO interrupts.
 */
ADI_SENSE_RESULT adi_sense_RegisterGpioCallback(
    ADI_SENSE_DEVICE_HANDLE          const hDevice,
    ADI_SENSE_GPIO_PIN               const ePinId,
    ADI_SENSE_GPIO_CALLBACK          const callbackFunction,
    void                           * const pCallbackParam)
{
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;

    if (callbackFunction)
    {
        return adi_sense_GpioIrqEnable(pCtx->hGpio, ePinId, callbackFunction,
                                       pCallbackParam);
    }
    else
    {
        return adi_sense_GpioIrqDisable(pCtx->hGpio, ePinId);
    }
}

/*
 * Reset the specified ADI Sense device.
 */
ADI_SENSE_RESULT adi_sense_Reset(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;
    ADI_SENSE_RESULT eRet;

    /* Pulse the Reset GPIO pin low for a minimum of 4 microseconds */
    eRet = adi_sense_GpioSet(pCtx->hGpio, ADI_SENSE_GPIO_PIN_RESET, false);
    if (eRet != ADI_SENSE_SUCCESS)
        return eRet;

    adi_sense_TimeDelayUsec(4);

    eRet = adi_sense_GpioSet(pCtx->hGpio, ADI_SENSE_GPIO_PIN_RESET, true);
    if (eRet != ADI_SENSE_SUCCESS)
        return eRet;

    return ADI_SENSE_SUCCESS;
}


/*!
 * @brief Get general status of ADISense module.
 *
 * @param[in]
 * @param[out] pStatus : Pointer to CORE Status struct.
 *
 * @return Status
 *         - #ADI_SENSE_SUCCESS Call completed successfully.
 *         - #ADI_SENSE_FAILURE If status register read fails.
 *
 * @details Read the general status register for the ADISense
 *          module. Indicates Error, Alert conditions, data ready
 *          and command running.
 *
 */
ADI_SENSE_RESULT adi_sense_GetStatus(
    ADI_SENSE_DEVICE_HANDLE    const hDevice,
    ADI_SENSE_STATUS         * const pStatus)
{
    ADI_ADISENSE_CORE_Status_t statusReg;
    READ_REG_U8(hDevice, statusReg.VALUE8, CORE_STATUS);

    memset(pStatus, 0, sizeof(*pStatus));

    if (!statusReg.Cmd_Running) /* Active-low, so invert it */
        pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_BUSY;
    if (statusReg.Drdy)
        pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_DATAREADY;
    if (statusReg.FIFO_Error)
        pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_FIFO_ERROR;
    if (statusReg.Alert_Active)
    {
        pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_ALERT;

        ADI_ADISENSE_CORE_Alert_Code_t alertCodeReg;
        READ_REG_U16(hDevice, alertCodeReg.VALUE16, CORE_ALERT_CODE);
        pStatus->alertCode = alertCodeReg.Alert_Code;

        ADI_ADISENSE_CORE_Channel_Alert_Status_t channelAlertStatusReg;
        READ_REG_U16(hDevice, channelAlertStatusReg.VALUE16,
                     CORE_CHANNEL_ALERT_STATUS);

        for (unsigned i = 0; i < ADI_SENSE_1000_MAX_CHANNELS; i++)
        {
            if (channelAlertStatusReg.VALUE16 & (1 << i))
            {
                ADI_ADISENSE_CORE_Alert_Code_Ch_t channelAlertCodeReg;
                READ_REG_U16(hDevice, channelAlertCodeReg.VALUE16, CORE_ALERT_CODE_CHn(i));
                pStatus->channelAlertCodes[i] = channelAlertCodeReg.Alert_Code_Ch;

                ADI_ADISENSE_CORE_Alert_Detail_Ch_t alertDetailReg;
                READ_REG_U16(hDevice, alertDetailReg.VALUE16,
                             CORE_ALERT_DETAIL_CHn(i));

                if (alertDetailReg.Time_Out)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_TIMEOUT;
                if (alertDetailReg.Under_Range)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_UNDER_RANGE;
                if (alertDetailReg.Over_Range)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_OVER_RANGE;
                if (alertDetailReg.Low_Limit)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_LOW_LIMIT;
                if (alertDetailReg.High_Limit)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_HIGH_LIMIT;
                if (alertDetailReg.Sensor_Open)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_SENSOR_OPEN;
                if (alertDetailReg.Ref_Detect)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_REF_DETECT;
                if (alertDetailReg.Config_Err)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_CONFIG_ERR;
                if (alertDetailReg.LUT_Error_Ch)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_LUT_ERR;
                if (alertDetailReg.Sensor_Not_Ready)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_SENSOR_NOT_READY;
                if (alertDetailReg.Comp_Not_Ready)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_COMP_NOT_READY;
                if (alertDetailReg.Under_Voltage)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_UNDER_VOLTAGE;
                if (alertDetailReg.Over_Voltage)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_OVER_VOLTAGE;
                if (alertDetailReg.Correction_UnderRange)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_LUT_UNDER_RANGE;
                if (alertDetailReg.Correction_OverRange)
                    pStatus->channelAlerts[i] |= ADI_SENSE_CHANNEL_ALERT_LUT_OVER_RANGE;
            }
        }

        ADI_ADISENSE_CORE_Alert_Status_2_t alert2Reg;
        READ_REG_U16(hDevice, alert2Reg.VALUE16, CORE_ALERT_STATUS_2);
        if (alert2Reg.Configuration_Error)
            pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_CONFIG_ERROR;
        if (alert2Reg.LUT_Error)
            pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_LUT_ERROR;
    }

    if (statusReg.Error)
    {
        pStatus->deviceStatus |= ADI_SENSE_DEVICE_STATUS_ERROR;

        ADI_ADISENSE_CORE_Error_Code_t errorCodeReg;
        READ_REG_U16(hDevice, errorCodeReg.VALUE16, CORE_ERROR_CODE);
        pStatus->errorCode = errorCodeReg.Error_Code;

        ADI_ADISENSE_CORE_Diagnostics_Status_t diagStatusReg;
        READ_REG_U16(hDevice, diagStatusReg.VALUE16, CORE_DIAGNOSTICS_STATUS);

        if (diagStatusReg.Diag_Checksum_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_CHECKSUM_ERROR;
        if (diagStatusReg.Diag_Comms_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_COMMS_ERROR;
        if (diagStatusReg.Diag_Supply_Monitor_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_SUPPLY_MONITOR_ERROR;
        if (diagStatusReg.Diag_Supply_Cap_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_SUPPLY_CAP_ERROR;
        if (diagStatusReg.Diag_Ainm_UV_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_AINM_UV_ERROR;
        if (diagStatusReg.Diag_Ainm_OV_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_AINM_OV_ERROR;
        if (diagStatusReg.Diag_Ainp_UV_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_AINP_UV_ERROR;
        if (diagStatusReg.Diag_Ainp_OV_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_AINP_OV_ERROR;
        if (diagStatusReg.Diag_Conversion_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_CONVERSION_ERROR;
        if (diagStatusReg.Diag_Calibration_Error)
            pStatus->diagnosticsStatus |= ADI_SENSE_DIAGNOSTICS_STATUS_CALIBRATION_ERROR;
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_GetCommandRunningState(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    bool_t *pbCommandRunning)
{
    ADI_ADISENSE_CORE_Status_t statusReg;

    READ_REG_U8(hDevice, statusReg.VALUE8, CORE_STATUS);

    /* We should never normally see 0xFF here if the module is operational */
    if (statusReg.VALUE8 == 0xFF)
        return ADI_SENSE_ERR_NOT_INITIALIZED;

    *pbCommandRunning = !statusReg.Cmd_Running; /* Active-low, so invert it */

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT executeCommand(
    ADI_SENSE_DEVICE_HANDLE const hDevice,
    ADI_ADISENSE_CORE_Command_Special_Command const command,
    bool_t const bWaitForCompletion)
{
    ADI_ADISENSE_CORE_Command_t commandReg;
    bool_t bCommandRunning;
    ADI_SENSE_RESULT eRet;

    /*
     * Don't allow another command to be issued if one is already running, but
     * make an exception for ADISENSE_CORE_COMMAND_NOP which can be used to
     * request a running command to be stopped (e.g. continuous measurement)
     */
    if (command != ADISENSE_CORE_COMMAND_NOP)
    {
        eRet = adi_sense_GetCommandRunningState(hDevice, &bCommandRunning);
        if (eRet)
            return eRet;

        if (bCommandRunning)
            return ADI_SENSE_IN_USE;
    }

    commandReg.Special_Command = command;
    WRITE_REG_U8(hDevice, commandReg.VALUE8, CORE_COMMAND);

    if (bWaitForCompletion)
    {
        do {
            /* Allow a minimum 50usec delay for status update before checking */
            adi_sense_TimeDelayUsec(50);

            eRet = adi_sense_GetCommandRunningState(hDevice, &bCommandRunning);
            if (eRet)
                return eRet;
        } while (bCommandRunning);
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_ApplyConfigUpdates(
    ADI_SENSE_DEVICE_HANDLE const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_LATCH_CONFIG, true);
}

/*!
 * @brief Start a measurement cycle.
 *
 * @param[out]
 *
 * @return Status
 *         - #ADI_SENSE_SUCCESS Call completed successfully.
 *         - #ADI_SENSE_FAILURE
 *
 * @details Sends the latch config command. Configuration for channels in
 *          conversion cycle should be completed before this function.
 *          Channel enabled bit should be set before this function.
 *          Starts a conversion and configures the format of the sample.
 *
 */
ADI_SENSE_RESULT adi_sense_StartMeasurement(
    ADI_SENSE_DEVICE_HANDLE    const hDevice,
    ADI_SENSE_MEASUREMENT_MODE const eMeasurementMode)
{
    switch (eMeasurementMode)
    {
    case ADI_SENSE_MEASUREMENT_MODE_HEALTHCHECK:
        return executeCommand(hDevice, ADISENSE_CORE_COMMAND_SYSTEM_CHECK, false);
    case ADI_SENSE_MEASUREMENT_MODE_NORMAL:
        return executeCommand(hDevice, ADISENSE_CORE_COMMAND_CONVERT_WITH_RAW, false);
    case ADI_SENSE_MEASUREMENT_MODE_OMIT_RAW:
        return executeCommand(hDevice, ADISENSE_CORE_COMMAND_CONVERT, false);
    default:
        ADI_SENSE_LOG_ERROR("Invalid measurement mode %d specified",
                            eMeasurementMode);
        return ADI_SENSE_INVALID_PARAM;
    }
}

/*
 * Store the configuration settings to persistent memory on the device.
 * No other command must be running when this is called.
 * Do not power down the device while this command is running.
 */
ADI_SENSE_RESULT adi_sense_SaveConfig(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_SAVE_CONFIG, true);
}

/*
 * Restore the configuration settings from persistent memory on the device.
 * No other command must be running when this is called.
 */
ADI_SENSE_RESULT adi_sense_RestoreConfig(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_LOAD_CONFIG, true);
}

/*
 * Store the LUT data to persistent memory on the device.
 * No other command must be running when this is called.
 * Do not power down the device while this command is running.
 */
ADI_SENSE_RESULT adi_sense_SaveLutData(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_SAVE_LUT2, true);
}

/*
 * Restore the LUT data from persistent memory on the device.
 * No other command must be running when this is called.
 */
ADI_SENSE_RESULT adi_sense_RestoreLutData(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_LOAD_LUT, true);
}

/*
 * Stop the measurement cycles on the device.
 * To be used only if a measurement command is currently running.
 */
ADI_SENSE_RESULT adi_sense_StopMeasurement(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_NOP, true);
}

/*
 * Run built-in diagnostic checks on the device.
 * Diagnostics are executed according to the current applied settings.
 * No other command must be running when this is called.
 */
ADI_SENSE_RESULT adi_sense_RunDiagnostics(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_RUN_DIAGNOSTICS, true);
}

/*
 * Run self-calibration routines on the device.
 * Calibration is executed according to the current applied settings.
 * No other command must be running when this is called.
 */
ADI_SENSE_RESULT adi_sense_RunCalibration(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    return executeCommand(hDevice, ADISENSE_CORE_COMMAND_SELF_CALIBRATION, true);
}

/*
 * Read a set of data samples from the device.
 * This may be called at any time.
 */
ADI_SENSE_RESULT adi_sense_GetData(
    ADI_SENSE_DEVICE_HANDLE    const hDevice,
    ADI_SENSE_MEASUREMENT_MODE const eMeasurementMode,
    ADI_SENSE_DATA_SAMPLE    * const pSamples,
    uint32_t                   const nRequested,
    uint32_t                 * const pnReturned)
{
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;
    uint16_t command = REG_READ_COMMAND |
        (REG_ADISENSE_CORE_DATA_FIFO & REG_ADDRESS_MASK);
    uint8_t commandData[2] = {
        command >> 8,
        command & 0xFF
    };
    uint8_t commandResponse[2];
    unsigned nValidSamples = 0;
    ADI_SENSE_RESULT eRet = ADI_SENSE_SUCCESS;

    do {
        eRet = adi_sense_SpiTransfer(pCtx->hSpi, commandData, commandResponse,
                                     sizeof(command), false);
        if (eRet)
        {
            ADI_SENSE_LOG_ERROR("Failed to send read command for FIFO register");
            return eRet;
        }

        adi_sense_TimeDelayUsec(POST_SPI_TRANSFER_DELAY_USEC);
    } while ((commandResponse[0] != REG_COMMAND_RESP_0) ||
             (commandResponse[1] != REG_COMMAND_RESP_1));

    for (unsigned i = 0; i < nRequested; i++)
    {
        ADI_ADISENSE_CORE_Data_FIFO_t dataFifoReg;
        bool_t bHoldCs = true;
        unsigned readSampleSize = sizeof(dataFifoReg);

        if (eMeasurementMode == ADI_SENSE_MEASUREMENT_MODE_OMIT_RAW)
            readSampleSize -= 3; /* 3B raw value omitted in this case */

        /* Keep the CS signal asserted for all but the last sample */
        if ((i + 1) == nRequested)
            bHoldCs = false;

        eRet = adi_sense_SpiTransfer(pCtx->hSpi, NULL, &dataFifoReg,
                                     readSampleSize, bHoldCs);
        if (eRet)
        {
            ADI_SENSE_LOG_ERROR("Failed to read data from FIFO register");
            return eRet;
        }

        if (! dataFifoReg.Ch_Valid)
        {
            /*
             * Reading an invalid sample indicates that there are no
             * more samples available or we've lost sync with the device.
             * In the latter case, it might be recoverable, but return here
             * to let the application check the device status and decide itself.
             */
            eRet = ADI_SENSE_INCOMPLETE;
            break;
        }

        ADI_SENSE_DATA_SAMPLE *pSample = &pSamples[nValidSamples];

        pSample->status = 0;
        if (dataFifoReg.Ch_Error)
            pSample->status |= ADI_SENSE_DEVICE_STATUS_ERROR;
        if (dataFifoReg.Ch_Alert)
            pSample->status |= ADI_SENSE_DEVICE_STATUS_ALERT;

        if (dataFifoReg.Ch_Raw)
            pSample->rawValue = dataFifoReg.Raw_Sample;
        else
            pSample->rawValue = 0;

        pSample->channelId = dataFifoReg.Channel_ID;
        pSample->processedValue = dataFifoReg.Sensor_Result;

        nValidSamples++;
    }
    *pnReturned = nValidSamples;

    adi_sense_TimeDelayUsec(POST_SPI_TRANSFER_DELAY_USEC);

    return eRet;
}

/*
 * Close the given ADI Sense device.
 */
ADI_SENSE_RESULT adi_sense_Close(
    ADI_SENSE_DEVICE_HANDLE    const hDevice)
{
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;

    adi_sense_GpioClose(pCtx->hGpio);
    adi_sense_SpiClose(pCtx->hSpi);
    adi_sense_LogClose();

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_WriteRegister(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    uint16_t nAddress,
    void *pData,
    unsigned nLength)
{
    ADI_SENSE_RESULT eRet;
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;
    uint16_t command = REG_WRITE_COMMAND | (nAddress & REG_ADDRESS_MASK);
    uint8_t commandData[2] = {
        command >> 8,
        command & 0xFF
    };
    uint8_t commandResponse[2];

    do {
        eRet = adi_sense_SpiTransfer(pCtx->hSpi, commandData, commandResponse,
                                     sizeof(command), false);
        if (eRet)
        {
            ADI_SENSE_LOG_ERROR("Failed to send write command for register %u",
                                nAddress);
            return eRet;
        }

        adi_sense_TimeDelayUsec(POST_SPI_TRANSFER_DELAY_USEC);
    } while ((commandResponse[0] != REG_COMMAND_RESP_0) ||
             (commandResponse[1] != REG_COMMAND_RESP_1));

    eRet = adi_sense_SpiTransfer(pCtx->hSpi, pData, NULL, nLength, false);
    if (eRet)
    {
        ADI_SENSE_LOG_ERROR("Failed to write data (%dB) to register %u",
                            nLength, nAddress);
        return eRet;
    }

    adi_sense_TimeDelayUsec(POST_SPI_TRANSFER_DELAY_USEC);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_ReadRegister(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    uint16_t nAddress,
    void *pData,
    unsigned nLength)
{
    ADI_SENSE_RESULT eRet;
    ADI_SENSE_DEVICE_CONTEXT *pCtx = hDevice;
    uint16_t command = REG_READ_COMMAND | (nAddress & REG_ADDRESS_MASK);
    uint8_t commandData[2] = {
        command >> 8,
        command & 0xFF
    };
    uint8_t commandResponse[2];

    do {
        eRet = adi_sense_SpiTransfer(pCtx->hSpi, commandData, commandResponse,
                                     sizeof(command), false);
        if (eRet)
        {
            ADI_SENSE_LOG_ERROR("Failed to send read command for register %u",
                                nAddress);
            return eRet;
        }

        adi_sense_TimeDelayUsec(POST_SPI_TRANSFER_DELAY_USEC);
    } while ((commandResponse[0] != REG_COMMAND_RESP_0) ||
             (commandResponse[1] != REG_COMMAND_RESP_1));

    eRet = adi_sense_SpiTransfer(pCtx->hSpi, NULL, pData, nLength, false);
    if (eRet)
    {
        ADI_SENSE_LOG_ERROR("Failed to read data (%uB) from register %u",
                            nLength, nAddress);
        return eRet;
    }

    adi_sense_TimeDelayUsec(POST_SPI_TRANSFER_DELAY_USEC);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_GetDeviceReadyState(
    ADI_SENSE_DEVICE_HANDLE   const hDevice,
    bool_t                  * const bReady)
{
    ADI_ADISENSE_SPI_Chip_Type_t chipTypeReg;

    READ_REG_U8(hDevice, chipTypeReg.VALUE8, SPI_CHIP_TYPE);
    /* If we read this register successfully, assume the device is ready */
    *bReady = (chipTypeReg.VALUE8 == REG_ADISENSE_SPI_CHIP_TYPE_RESET);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_GetDataReadyModeInfo(
    ADI_SENSE_DEVICE_HANDLE         const hDevice,
    ADI_SENSE_MEASUREMENT_MODE      const eMeasurementMode,
    ADI_SENSE_1000_OPERATING_MODE * const peOperatingMode,
    ADI_SENSE_1000_DATAREADY_MODE * const peDataReadyMode,
    uint32_t                      * const pnSamplesPerDataready,
    uint32_t                      * const pnSamplesPerCycle)
{
    unsigned nChannelsEnabled = 0;
    unsigned nSamplesPerCycle = 0;

    for (ADI_SENSE_1000_CHANNEL_ID chId = 0; chId < ADI_SENSE_1000_MAX_CHANNELS; chId++)
    {
        ADI_ADISENSE_CORE_Sensor_Details_t sensorDetailsReg;
        ADI_ADISENSE_CORE_Channel_Count_t channelCountReg;

        if (ADI_SENSE_1000_CHANNEL_IS_VIRTUAL(chId))
            continue;

        READ_REG_U8(hDevice, channelCountReg.VALUE8, CORE_CHANNEL_COUNTn(chId));
        READ_REG_U32(hDevice, sensorDetailsReg.VALUE32, CORE_SENSOR_DETAILSn(chId));

        if (channelCountReg.Channel_Enable && !sensorDetailsReg.Do_Not_Publish)
        {
            ADI_ADISENSE_CORE_Sensor_Type_t sensorTypeReg;
            unsigned nActualChannels = 1;

            READ_REG_U16(hDevice, sensorTypeReg.VALUE16, CORE_SENSOR_TYPEn(chId));

            if (chId == ADI_SENSE_1000_CHANNEL_ID_SPI_0)
            {
                /* Some sensors automatically generate samples on additional "virtual" channels
                 * so these channels must be counted as active when those sensors are selected
                 * and we use the count from the corresponding "physical" channel */
                if (sensorTypeReg.Sensor_Type ==
                    ADISENSE_CORE_SENSOR_TYPE_SENSOR_SPI_ACCELEROMETER_1)
                    nActualChannels += 2;
            }

            nChannelsEnabled += nActualChannels;
            if (eMeasurementMode == ADI_SENSE_MEASUREMENT_MODE_HEALTHCHECK)
                /* Assume a single sample per channel in test mode */
                nSamplesPerCycle += nActualChannels;
            else
                nSamplesPerCycle += nActualChannels *
                    (channelCountReg.Channel_Count + 1);
        }
    }

    if (nChannelsEnabled == 0)
    {
        *pnSamplesPerDataready = 0;
        *pnSamplesPerCycle = 0;
        return ADI_SENSE_SUCCESS;
    }

    ADI_ADISENSE_CORE_Mode_t modeReg;
    READ_REG_U8(hDevice, modeReg.VALUE8, CORE_MODE);

    *pnSamplesPerCycle = nSamplesPerCycle;

    /* Assume DRDY_PER_CONVERSION behaviour in test mode */
    if ((eMeasurementMode == ADI_SENSE_MEASUREMENT_MODE_HEALTHCHECK) ||
        (modeReg.Drdy_Mode == ADISENSE_CORE_MODE_DRDY_PER_CONVERSION))
    {
        *pnSamplesPerDataready = 1;
    }
    else if (modeReg.Drdy_Mode == ADISENSE_CORE_MODE_DRDY_PER_CYCLE)
    {
        *pnSamplesPerDataready = nSamplesPerCycle;
    }
    else
    {
        ADI_ADISENSE_CORE_Fifo_Num_Cycles_t fifoNumCyclesReg;
        READ_REG_U8(hDevice, fifoNumCyclesReg.VALUE8, CORE_FIFO_NUM_CYCLES);

        *pnSamplesPerDataready =
            nSamplesPerCycle * fifoNumCyclesReg.Fifo_Num_Cycles;
    }

    /* Assume SINGLECYCLE in test mode */
    if ((eMeasurementMode == ADI_SENSE_MEASUREMENT_MODE_HEALTHCHECK) ||
        (modeReg.Conversion_Mode == ADISENSE_CORE_MODE_SINGLECYCLE))
        *peOperatingMode = ADI_SENSE_1000_OPERATING_MODE_SINGLECYCLE;
    else if (modeReg.Conversion_Mode == ADISENSE_CORE_MODE_MULTICYCLE)
        *peOperatingMode = ADI_SENSE_1000_OPERATING_MODE_MULTICYCLE;
    else
        *peOperatingMode = ADI_SENSE_1000_OPERATING_MODE_CONTINUOUS;

    /* Assume DRDY_PER_CONVERSION behaviour in test mode */
    if ((eMeasurementMode == ADI_SENSE_MEASUREMENT_MODE_HEALTHCHECK) ||
        (modeReg.Drdy_Mode == ADISENSE_CORE_MODE_DRDY_PER_CONVERSION))
        *peDataReadyMode = ADI_SENSE_1000_DATAREADY_PER_CONVERSION;
    else if (modeReg.Drdy_Mode == ADISENSE_CORE_MODE_DRDY_PER_CYCLE)
        *peDataReadyMode = ADI_SENSE_1000_DATAREADY_PER_CYCLE;
    else
        *peDataReadyMode = ADI_SENSE_1000_DATAREADY_PER_MULTICYCLE_BURST;

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_GetProductID(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_PRODUCT_ID *pProductId)
{
    ADI_ADISENSE_SPI_Product_ID_L_t productIdLoReg;
    ADI_ADISENSE_SPI_Product_ID_H_t productIdHiReg;

    READ_REG_U8(hDevice, productIdLoReg.VALUE8, SPI_PRODUCT_ID_L);
    READ_REG_U8(hDevice, productIdHiReg.VALUE8, SPI_PRODUCT_ID_H);

    *pProductId = (productIdHiReg.VALUE8 << 8) | productIdLoReg.VALUE8;
    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetPowerMode(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_POWER_MODE powerMode)
{
    ADI_ADISENSE_CORE_Power_Config_t powerConfigReg;

    if (powerMode == ADI_SENSE_1000_POWER_MODE_LOW)
    {
        powerConfigReg.Power_Mode_ADC = ADISENSE_CORE_POWER_CONFIG_ADC_LOW_POWER;
        /* TODO - we need an enum in the register map for the MCU power modes */
        powerConfigReg.Power_Mode_MCU = 0x0;
    }
    else if (powerMode == ADI_SENSE_1000_POWER_MODE_MID)
    {
        powerConfigReg.Power_Mode_ADC = ADISENSE_CORE_POWER_CONFIG_ADC_MID_POWER;
        powerConfigReg.Power_Mode_MCU = 0x1;
    }
    else if (powerMode == ADI_SENSE_1000_POWER_MODE_FULL)
    {
        powerConfigReg.Power_Mode_ADC = ADISENSE_CORE_POWER_CONFIG_ADC_FULL_POWER;
        powerConfigReg.Power_Mode_MCU = 0x2;
    }
    else
    {
        ADI_SENSE_LOG_ERROR("Invalid power mode %d specified", powerMode);
        return ADI_SENSE_INVALID_PARAM;
    }

    WRITE_REG_U8(hDevice, powerConfigReg.VALUE8, CORE_POWER_CONFIG);

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetVddVoltage(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    float32_t vddVoltage)
{
    WRITE_REG_FLOAT(hDevice, vddVoltage, CORE_AVDD_VOLTAGE);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetPowerConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_POWER_CONFIG *pPowerConfig)
{
    ADI_SENSE_RESULT eRet;

    eRet = adi_sense_SetPowerMode(hDevice, pPowerConfig->powerMode);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set power mode");
        return eRet;
    }

    eRet = adi_sense_SetVddVoltage(hDevice, pPowerConfig->supplyVoltage);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set AVdd voltage");
        return eRet;
    }

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetMode(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_OPERATING_MODE eOperatingMode,
    ADI_SENSE_1000_DATAREADY_MODE eDataReadyMode)
{
    ADI_ADISENSE_CORE_Mode_t modeReg;

    modeReg.VALUE8 = REG_RESET_VAL(CORE_MODE);

    if (eOperatingMode == ADI_SENSE_1000_OPERATING_MODE_SINGLECYCLE)
    {
        modeReg.Conversion_Mode = ADISENSE_CORE_MODE_SINGLECYCLE;
    }
    else if (eOperatingMode == ADI_SENSE_1000_OPERATING_MODE_CONTINUOUS)
    {
        modeReg.Conversion_Mode = ADISENSE_CORE_MODE_CONTINUOUS;
    }
    else if (eOperatingMode == ADI_SENSE_1000_OPERATING_MODE_MULTICYCLE)
    {
        modeReg.Conversion_Mode = ADISENSE_CORE_MODE_MULTICYCLE;
    }
    else
    {
        ADI_SENSE_LOG_ERROR("Invalid operating mode %d specified",
                            eOperatingMode);
        return ADI_SENSE_INVALID_PARAM;
    }

    if (eDataReadyMode == ADI_SENSE_1000_DATAREADY_PER_CONVERSION)
    {
        modeReg.Drdy_Mode = ADISENSE_CORE_MODE_DRDY_PER_CONVERSION;
    }
    else if (eDataReadyMode == ADI_SENSE_1000_DATAREADY_PER_CYCLE)
    {
        modeReg.Drdy_Mode = ADISENSE_CORE_MODE_DRDY_PER_CYCLE;
    }
    else if (eDataReadyMode == ADI_SENSE_1000_DATAREADY_PER_MULTICYCLE_BURST)
    {
        if (eOperatingMode != ADI_SENSE_1000_OPERATING_MODE_MULTICYCLE)
        {
            ADI_SENSE_LOG_ERROR(
                "Data-ready mode %d cannot be used with operating mode %d",
                eDataReadyMode, eOperatingMode);
            return ADI_SENSE_INVALID_PARAM;
        }
        else
        {
            modeReg.Drdy_Mode = ADISENSE_CORE_MODE_DRDY_PER_FIFO_FILL;
        }
    }
    else
    {
        ADI_SENSE_LOG_ERROR("Invalid data-ready mode %d specified", eDataReadyMode);
        return ADI_SENSE_INVALID_PARAM;
    }

    WRITE_REG_U8(hDevice, modeReg.VALUE8, CORE_MODE);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_SetCycleInterval(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    uint32_t nCycleInterval)
{
    ADI_ADISENSE_CORE_Cycle_Control_t cycleControlReg;

    cycleControlReg.VALUE16 = REG_RESET_VAL(CORE_CYCLE_CONTROL);

    if (nCycleInterval < (1 << 12))
    {
        cycleControlReg.Cycle_Time_Units = ADISENSE_CORE_CYCLE_CONTROL_MICROSECONDS;
    }
    else if (nCycleInterval < (1000 * (1 << 12)))
    {
        cycleControlReg.Cycle_Time_Units = ADISENSE_CORE_CYCLE_CONTROL_MILLISECONDS;
        nCycleInterval /= 1000;
    }
    else
    {
        cycleControlReg.Cycle_Time_Units = ADISENSE_CORE_CYCLE_CONTROL_SECONDS;
        nCycleInterval /= 1000000;
    }

    CHECK_REG_FIELD_VAL(CORE_CYCLE_CONTROL_CYCLE_TIME, nCycleInterval);
    cycleControlReg.Cycle_Time = nCycleInterval;

    WRITE_REG_U16(hDevice, cycleControlReg.VALUE16, CORE_CYCLE_CONTROL);

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetMultiCycleConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_MULTICYCLE_CONFIG *pMultiCycleConfig)
{
    CHECK_REG_FIELD_VAL(CORE_FIFO_NUM_CYCLES_FIFO_NUM_CYCLES,
                        pMultiCycleConfig->cyclesPerBurst);

    WRITE_REG_U8(hDevice, pMultiCycleConfig->cyclesPerBurst,
                 CORE_FIFO_NUM_CYCLES);

    WRITE_REG_U32(hDevice, pMultiCycleConfig->burstInterval,
                  CORE_MULTI_CYCLE_REPEAT_INTERVAL);

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetExternalReferenceValues(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    float32_t externalRef1Value,
    float32_t externalRef2Value)
{
    WRITE_REG_FLOAT(hDevice, externalRef1Value, CORE_EXTERNAL_REFERENCE1);
    WRITE_REG_FLOAT(hDevice, externalRef2Value, CORE_EXTERNAL_REFERENCE2);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetMeasurementConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_MEASUREMENT_CONFIG *pMeasConfig)
{
    ADI_SENSE_RESULT eRet;

    eRet = adi_sense_SetMode(hDevice,
                            pMeasConfig->operatingMode,
                            pMeasConfig->dataReadyMode);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set operating mode");
        return eRet;
    }

    if (pMeasConfig->operatingMode != ADI_SENSE_1000_OPERATING_MODE_SINGLECYCLE)
    {
        eRet = adi_sense_SetCycleInterval(hDevice, pMeasConfig->cycleInterval);
        if (eRet != ADI_SENSE_SUCCESS)
        {
            ADI_SENSE_LOG_ERROR("Failed to set cycle interval");
            return eRet;
        }
    }

    if (pMeasConfig->operatingMode == ADI_SENSE_1000_OPERATING_MODE_MULTICYCLE)
    {
        eRet = adi_sense_SetMultiCycleConfig(hDevice,
                                            &pMeasConfig->multiCycleConfig);
        if (eRet != ADI_SENSE_SUCCESS)
        {
            ADI_SENSE_LOG_ERROR("Failed to set multi-cycle configuration");
            return eRet;
        }
    }

    eRet = adi_sense_SetExternalReferenceValues(hDevice,
                                                pMeasConfig->externalRef1Value,
                                                pMeasConfig->externalRef2Value);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set external reference values");
        return eRet;
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetDiagnosticsConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_DIAGNOSTICS_CONFIG *pDiagnosticsConfig)
{
    ADI_ADISENSE_CORE_Diagnostics_Control_t diagnosticsControlReg;

    diagnosticsControlReg.VALUE16 = REG_RESET_VAL(CORE_DIAGNOSTICS_CONTROL);

    if (pDiagnosticsConfig->disableGlobalDiag)
        diagnosticsControlReg.Diag_Global_En = 0;
    else
        diagnosticsControlReg.Diag_Global_En = 1;

    if (pDiagnosticsConfig->disableMeasurementDiag)
        diagnosticsControlReg.Diag_Meas_En = 0;
    else
        diagnosticsControlReg.Diag_Meas_En = 1;

    switch (pDiagnosticsConfig->osdFrequency)
    {
    case ADI_SENSE_1000_OPEN_SENSOR_DIAGNOSTICS_DISABLED:
        diagnosticsControlReg.Diag_OSD_Freq = ADISENSE_CORE_DIAGNOSTICS_CONTROL_OCD_OFF;
        break;
    case ADI_SENSE_1000_OPEN_SENSOR_DIAGNOSTICS_PER_CYCLE:
        diagnosticsControlReg.Diag_OSD_Freq = ADISENSE_CORE_DIAGNOSTICS_CONTROL_OCD_PER_1_CYCLE;
        break;
    case ADI_SENSE_1000_OPEN_SENSOR_DIAGNOSTICS_PER_100_CYCLES:
        diagnosticsControlReg.Diag_OSD_Freq = ADISENSE_CORE_DIAGNOSTICS_CONTROL_OCD_PER_100_CYCLES;
        break;
    case ADI_SENSE_1000_OPEN_SENSOR_DIAGNOSTICS_PER_1000_CYCLES:
        diagnosticsControlReg.Diag_OSD_Freq = ADISENSE_CORE_DIAGNOSTICS_CONTROL_OCD_PER_1000_CYCLES;
        break;
    default:
        ADI_SENSE_LOG_ERROR("Invalid open-sensor diagnostic frequency %d specified",
                            pDiagnosticsConfig->osdFrequency);
        return ADI_SENSE_INVALID_PARAM;
    }

    WRITE_REG_U16(hDevice, diagnosticsControlReg.VALUE16, CORE_DIAGNOSTICS_CONTROL);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetChannelCount(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    uint32_t nMeasurementsPerCycle)
{
    ADI_ADISENSE_CORE_Channel_Count_t channelCountReg;

    channelCountReg.VALUE8 = REG_RESET_VAL(CORE_CHANNEL_COUNTn);

    if (nMeasurementsPerCycle > 0)
    {
        nMeasurementsPerCycle -= 1;

        CHECK_REG_FIELD_VAL(CORE_CHANNEL_COUNT_CHANNEL_COUNT,
                            nMeasurementsPerCycle);

        channelCountReg.Channel_Enable = 1;
        channelCountReg.Channel_Count = nMeasurementsPerCycle;
    }
    else
    {
        channelCountReg.Channel_Enable = 0;
    }

    WRITE_REG_U8(hDevice, channelCountReg.VALUE8, CORE_CHANNEL_COUNTn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelAdcSensorType(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_ADC_SENSOR_TYPE sensorType)
{
    ADI_ADISENSE_CORE_Sensor_Type_t sensorTypeReg;

    sensorTypeReg.VALUE16 = REG_RESET_VAL(CORE_SENSOR_TYPEn);

    /* Ensure that the sensor type is valid for this channel */
    switch(sensorType)
    {
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_J_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_K_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_T_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_J_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_K_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_T_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMOCOUPLE_4_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_PT100_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_PT1000_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_PT100_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_PT1000_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_3WIRE_4_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_PT100_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_PT1000_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_PT100_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_PT1000_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_4WIRE_4_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_4WIRE_4_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_BRIDGE_6WIRE_4_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_A_10K_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_B_10K_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_A_10K_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_B_10K_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_THERMISTOR_4_ADV_L2:
        if (! ADI_SENSE_1000_CHANNEL_IS_ADC_SENSOR(eChannelId))
        {
            ADI_SENSE_LOG_ERROR(
                "Invalid ADC sensor type %d specified for channel %d",
                sensorType, eChannelId);
            return ADI_SENSE_INVALID_PARAM;
        }
        break;
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_PT100_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_PT1000_DEF_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_1_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_2_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_3_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_4_DEF_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_PT100_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_PT1000_ADV_L1:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_1_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_2_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_3_ADV_L2:
    case ADI_SENSE_1000_ADC_SENSOR_RTD_2WIRE_4_ADV_L2:
        if (! (ADI_SENSE_1000_CHANNEL_IS_ADC_SENSOR(eChannelId) ||
               ADI_SENSE_1000_CHANNEL_IS_ADC_CJC(eChannelId)))
        {
            ADI_SENSE_LOG_ERROR(
                "Invalid ADC sensor type %d specified for channel %d",
                sensorType, eChannelId);
            return ADI_SENSE_INVALID_PARAM;
        }
        break;
    case ADI_SENSE_1000_ADC_SENSOR_VOLTAGE:
    case ADI_SENSE_1000_ADC_SENSOR_VOLTAGE_PRESSURE_HONEYWELL_TRUSTABILITY:
    case ADI_SENSE_1000_ADC_SENSOR_VOLTAGE_PRESSURE_AMPHENOL_NPA300X:
    case ADI_SENSE_1000_ADC_SENSOR_VOLTAGE_PRESSURE_3_DEF:
        if (! ADI_SENSE_1000_CHANNEL_IS_ADC_VOLTAGE(eChannelId))
        {
            ADI_SENSE_LOG_ERROR(
                "Invalid ADC sensor type %d specified for channel %d",
                sensorType, eChannelId);
            return ADI_SENSE_INVALID_PARAM;
        }
        break;
    case ADI_SENSE_1000_ADC_SENSOR_CURRENT:
    case ADI_SENSE_1000_ADC_SENSOR_CURRENT_PRESSURE_HONEYWELL_PX2:
    case ADI_SENSE_1000_ADC_SENSOR_CURRENT_PRESSURE_2_DEF:
        if (! ADI_SENSE_1000_CHANNEL_IS_ADC_CURRENT(eChannelId))
        {
            ADI_SENSE_LOG_ERROR(
                "Invalid ADC sensor type %d specified for channel %d",
                sensorType, eChannelId);
            return ADI_SENSE_INVALID_PARAM;
        }
        break;
    default:
        ADI_SENSE_LOG_ERROR("Invalid/unsupported ADC sensor type %d specified",
                            sensorType);
        return ADI_SENSE_INVALID_PARAM;
    }

    sensorTypeReg.Sensor_Type = sensorType;

    WRITE_REG_U16(hDevice, sensorTypeReg.VALUE16, CORE_SENSOR_TYPEn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelAdcSensorDetails(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_CHANNEL_CONFIG *pChannelConfig)
/*
 * TODO - it would be nice if the general- vs. ADC-specific sensor details could be split into separate registers
 * General details:
 * - Measurement_Units
 * - Compensation_Channel
 * - CJC_Publish (if "CJC" was removed from the name)
 * ADC-specific details:
 * - PGA_Gain
 * - Reference_Select
 * - Reference_Buffer_Disable
 * - Vbias
 */
{
    ADI_SENSE_1000_ADC_CHANNEL_CONFIG *pAdcChannelConfig = &pChannelConfig->adcChannelConfig;
    ADI_SENSE_1000_ADC_REFERENCE_CONFIG *pRefConfig = &pAdcChannelConfig->reference;
    ADI_ADISENSE_CORE_Sensor_Details_t sensorDetailsReg;

    sensorDetailsReg.VALUE32 = REG_RESET_VAL(CORE_SENSOR_DETAILSn);

    switch(pChannelConfig->measurementUnit)
    {
    case ADI_SENSE_1000_MEASUREMENT_UNIT_FAHRENHEIT:
        sensorDetailsReg.Measurement_Units = ADISENSE_CORE_SENSOR_DETAILS_UNITS_DEGF;
        break;
    case ADI_SENSE_1000_MEASUREMENT_UNIT_CELSIUS:
    case ADI_SENSE_1000_MEASUREMENT_UNIT_DEFAULT:
        sensorDetailsReg.Measurement_Units = ADISENSE_CORE_SENSOR_DETAILS_UNITS_DEGC;
        break;
    default:
        ADI_SENSE_LOG_ERROR("Invalid measurement unit %d specified",
                            pChannelConfig->measurementUnit);
        return ADI_SENSE_INVALID_PARAM;
    }

    sensorDetailsReg.Compensation_Channel = pChannelConfig->compensationChannel;

    switch(pRefConfig->type)
    {
    case ADI_SENSE_1000_ADC_REFERENCE_RESISTOR_INTERNAL_1:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_RINT1;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_RESISTOR_INTERNAL_2:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_RINT2;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_VOLTAGE_INTERNAL:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_INT;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_VOLTAGE_AVDD:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_AVDD;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_RESISTOR_EXTERNAL_1:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_REXT1;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_RESISTOR_EXTERNAL_2:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_REXT2;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_VOLTAGE_EXTERNAL_1:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_VEXT1;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_VOLTAGE_EXTERNAL_2:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_VEXT2;
        break;
    case ADI_SENSE_1000_ADC_REFERENCE_BRIDGE_EXCITATION:
        sensorDetailsReg.Reference_Select = ADISENSE_CORE_SENSOR_DETAILS_REF_EXC;
        break;
    default:
        ADI_SENSE_LOG_ERROR("Invalid ADC reference type %d specified",
                            pRefConfig->type);
        return ADI_SENSE_INVALID_PARAM;
    }

    switch(pAdcChannelConfig->gain)
    {
    case ADI_SENSE_1000_ADC_GAIN_1X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_1;
        break;
    case ADI_SENSE_1000_ADC_GAIN_2X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_2;
        break;
    case ADI_SENSE_1000_ADC_GAIN_4X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_4;
        break;
    case ADI_SENSE_1000_ADC_GAIN_8X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_8;
        break;
    case ADI_SENSE_1000_ADC_GAIN_16X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_16;
        break;
    case ADI_SENSE_1000_ADC_GAIN_32X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_32;
        break;
    case ADI_SENSE_1000_ADC_GAIN_64X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_64;
        break;
    case ADI_SENSE_1000_ADC_GAIN_128X:
        sensorDetailsReg.PGA_Gain = ADISENSE_CORE_SENSOR_DETAILS_PGA_GAIN_128;
        break;
    default:
        ADI_SENSE_LOG_ERROR("Invalid ADC gain %d specified",
                            pAdcChannelConfig->gain);
        return ADI_SENSE_INVALID_PARAM;
    }

    if (pAdcChannelConfig->enableVbias)
        sensorDetailsReg.Vbias = 1;
    else
        sensorDetailsReg.Vbias = 0;

    if (pAdcChannelConfig->reference.disableBuffer)
        sensorDetailsReg.Reference_Buffer_Disable = 1;
    else
        sensorDetailsReg.Reference_Buffer_Disable = 0;

    if (pChannelConfig->disablePublishing)
        sensorDetailsReg.Do_Not_Publish = 1;
    else
        sensorDetailsReg.Do_Not_Publish = 0;

    WRITE_REG_U32(hDevice, sensorDetailsReg.VALUE32, CORE_SENSOR_DETAILSn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelAdcFilter(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_ADC_FILTER_CONFIG *pFilterConfig)
{
    ADI_ADISENSE_CORE_Filter_Select_t filterSelectReg;

    filterSelectReg.VALUE32 = REG_RESET_VAL(CORE_FILTER_SELECTn);

    if (pFilterConfig->type == ADI_SENSE_1000_ADC_FILTER_SINC4)
    {
        filterSelectReg.ADC_Filter_Type = ADISENSE_CORE_FILTER_SELECT_FILTER_SINC4;
        filterSelectReg.ADC_FS = pFilterConfig->fs;
    }
    else if (pFilterConfig->type == ADI_SENSE_1000_ADC_FILTER_FIR_20SPS)
    {
        filterSelectReg.ADC_Filter_Type = ADISENSE_CORE_FILTER_SELECT_FILTER_FIR_20SPS;
    }
    else if (pFilterConfig->type == ADI_SENSE_1000_ADC_FILTER_FIR_25SPS)
    {
        filterSelectReg.ADC_Filter_Type = ADISENSE_CORE_FILTER_SELECT_FILTER_FIR_25SPS;
    }
    else
    {
        ADI_SENSE_LOG_ERROR("Invalid ADC filter type %d specified",
                            pFilterConfig->type);
        return ADI_SENSE_INVALID_PARAM;
    }

    WRITE_REG_U32(hDevice, filterSelectReg.VALUE32, CORE_FILTER_SELECTn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelAdcCurrentConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_ADC_EXC_CURRENT_CONFIG *pCurrentConfig)
{
    ADI_ADISENSE_CORE_Channel_Excitation_t channelExcitationReg;

    channelExcitationReg.VALUE8 = REG_RESET_VAL(CORE_CHANNEL_EXCITATIONn);

    if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_NONE)
    {
        channelExcitationReg.IOUT0_Disable = 1;
        channelExcitationReg.IOUT1_Disable = 1;

        channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_OFF;
    }
    else
    {
        channelExcitationReg.IOUT0_Disable = 0;
        channelExcitationReg.IOUT1_Disable = 0;

        if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_50uA)
            channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_50UA;
        else if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_100uA)
            channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_100UA;
        else if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_250uA)
            channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_250UA;
        else if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_500uA)
            channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_500UA;
        else if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_750uA)
            channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_750UA;
        else if (pCurrentConfig->outputLevel == ADI_SENSE_1000_ADC_EXC_CURRENT_1000uA)
            channelExcitationReg.IOUT_Excitation_Current = ADISENSE_CORE_CHANNEL_EXCITATION_IEXC_1000UA;
        else
        {
            ADI_SENSE_LOG_ERROR("Invalid ADC excitation current %d specified",
                                pCurrentConfig->outputLevel);
            return ADI_SENSE_INVALID_PARAM;
        }

        if (pCurrentConfig->swapOption == ADI_SENSE_1000_ADC_EXC_CURRENT_SWAP_DYNAMIC)
        {
            channelExcitationReg.IOUT_Dont_Swap_3Wire = 0;
            channelExcitationReg.IOUT_Static_Swap_3Wire = 0;
        }
        else if (pCurrentConfig->swapOption == ADI_SENSE_1000_ADC_EXC_CURRENT_SWAP_STATIC)
        {
            channelExcitationReg.IOUT_Dont_Swap_3Wire = 1;
            channelExcitationReg.IOUT_Static_Swap_3Wire = 1;
        }
        else if (pCurrentConfig->swapOption == ADI_SENSE_1000_ADC_EXC_CURRENT_SWAP_NONE)
        {
            channelExcitationReg.IOUT_Dont_Swap_3Wire = 1;
            channelExcitationReg.IOUT_Static_Swap_3Wire = 0;
        }
        else
        {
            ADI_SENSE_LOG_ERROR(
                "Invalid ADC excitation current swap option %d specified",
                pCurrentConfig->swapOption);
            return ADI_SENSE_INVALID_PARAM;
        }
    }

    WRITE_REG_U8(hDevice, channelExcitationReg.VALUE8, CORE_CHANNEL_EXCITATIONn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_SetAdcChannelConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_CHANNEL_CONFIG *pChannelConfig)
{
    ADI_SENSE_RESULT eRet;
    ADI_SENSE_1000_ADC_CHANNEL_CONFIG *pAdcChannelConfig =
        &pChannelConfig->adcChannelConfig;

    eRet = adi_sense_SetChannelAdcSensorType(hDevice, eChannelId,
                                             pAdcChannelConfig->sensor);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set ADC sensor type for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetChannelAdcSensorDetails(hDevice, eChannelId,
                                                pChannelConfig);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set ADC sensor details for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetChannelAdcFilter(hDevice, eChannelId,
                                         &pAdcChannelConfig->filter);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set ADC filter for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetChannelAdcCurrentConfig(hDevice, eChannelId,
                                                &pAdcChannelConfig->current);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set ADC current for channel %d",
                            eChannelId);
        return eRet;
    }

    return ADI_SENSE_SUCCESS;
}


static ADI_SENSE_RESULT adi_sense_SetDigitalSensorCommands(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_DIGITAL_SENSOR_COMMAND *pConfigCommand,
    ADI_SENSE_1000_DIGITAL_SENSOR_COMMAND *pDataRequestCommand)
{
    ADI_ADISENSE_CORE_Digital_Sensor_Num_Cmds_t numCmdsReg;

    numCmdsReg.VALUE8 = REG_RESET_VAL(CORE_DIGITAL_SENSOR_NUM_CMDSn);

    CHECK_REG_FIELD_VAL(CORE_DIGITAL_SENSOR_NUM_CMDS_DIGITAL_SENSOR_NUM_CFG_CMDS,
                        pConfigCommand->commandLength);
    CHECK_REG_FIELD_VAL(CORE_DIGITAL_SENSOR_NUM_CMDS_DIGITAL_SENSOR_NUM_READ_CMDS,
                        pDataRequestCommand->commandLength);

    numCmdsReg.Digital_Sensor_Num_Cfg_Cmds = pConfigCommand->commandLength;
    numCmdsReg.Digital_Sensor_Num_Read_Cmds = pDataRequestCommand->commandLength;

    WRITE_REG_U8(hDevice, numCmdsReg.VALUE8,
                 CORE_DIGITAL_SENSOR_NUM_CMDSn(eChannelId));

    switch (pConfigCommand->commandLength)
    {
        /* NOTE - intentional fall-through cases below */
    case 7:
        WRITE_REG_U8(hDevice, pConfigCommand->command[6],
                     CORE_DIGITAL_SENSOR_COMMAND7n(eChannelId));
    case 6:
        WRITE_REG_U8(hDevice, pConfigCommand->command[5],
                     CORE_DIGITAL_SENSOR_COMMAND6n(eChannelId));
    case 5:
        WRITE_REG_U8(hDevice, pConfigCommand->command[4],
                     CORE_DIGITAL_SENSOR_COMMAND5n(eChannelId));
    case 4:
        WRITE_REG_U8(hDevice, pConfigCommand->command[3],
                     CORE_DIGITAL_SENSOR_COMMAND4n(eChannelId));
    case 3:
        WRITE_REG_U8(hDevice, pConfigCommand->command[2],
                     CORE_DIGITAL_SENSOR_COMMAND3n(eChannelId));
    case 2:
        WRITE_REG_U8(hDevice, pConfigCommand->command[1],
                     CORE_DIGITAL_SENSOR_COMMAND2n(eChannelId));
    case 1:
        WRITE_REG_U8(hDevice, pConfigCommand->command[0],
                     CORE_DIGITAL_SENSOR_COMMAND1n(eChannelId));
    case 0:
    default:
        break;
    };

    switch (pDataRequestCommand->commandLength)
    {
        /* NOTE - intentional fall-through cases below */
    case 7:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[6],
                     CORE_DIGITAL_SENSOR_READ_CMD7n(eChannelId));
    case 6:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[5],
                     CORE_DIGITAL_SENSOR_READ_CMD6n(eChannelId));
    case 5:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[4],
                     CORE_DIGITAL_SENSOR_READ_CMD5n(eChannelId));
    case 4:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[3],
                     CORE_DIGITAL_SENSOR_READ_CMD4n(eChannelId));
    case 3:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[2],
                     CORE_DIGITAL_SENSOR_READ_CMD3n(eChannelId));
    case 2:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[1],
                     CORE_DIGITAL_SENSOR_READ_CMD2n(eChannelId));
    case 1:
        WRITE_REG_U8(hDevice, pDataRequestCommand->command[0],
                     CORE_DIGITAL_SENSOR_READ_CMD1n(eChannelId));
    case 0:
    default:
        break;
    };

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetDigitalSensorFormat(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_DIGITAL_SENSOR_DATA_FORMAT *pDataFormat)
{
    ADI_ADISENSE_CORE_Digital_Sensor_Config_t sensorConfigReg;

    sensorConfigReg.VALUE16 = REG_RESET_VAL(CORE_DIGITAL_SENSOR_CONFIGn);

    if (pDataFormat->coding != ADI_SENSE_1000_DIGITAL_SENSOR_DATA_CODING_NONE)
    {
        if (pDataFormat->frameLength == 0)
        {
            ADI_SENSE_LOG_ERROR("Invalid frame length specified for digital sensor data format");
            return ADI_SENSE_INVALID_PARAM;
        }
        if (pDataFormat->numDataBits == 0)
        {
            ADI_SENSE_LOG_ERROR("Invalid frame length specified for digital sensor data format");
            return ADI_SENSE_INVALID_PARAM;
        }

        CHECK_REG_FIELD_VAL(CORE_DIGITAL_SENSOR_CONFIG_DIGITAL_SENSOR_READ_BYTES,
                            pDataFormat->frameLength - 1);
        CHECK_REG_FIELD_VAL(CORE_DIGITAL_SENSOR_CONFIG_DIGITAL_SENSOR_DATA_BITS,
                            pDataFormat->numDataBits - 1);
        CHECK_REG_FIELD_VAL(CORE_DIGITAL_SENSOR_CONFIG_DIGITAL_SENSOR_BIT_OFFSET,
                            pDataFormat->bitOffset);

        sensorConfigReg.Digital_Sensor_Read_Bytes = pDataFormat->frameLength - 1;
        sensorConfigReg.Digital_Sensor_Data_Bits = pDataFormat->numDataBits - 1;
        sensorConfigReg.Digital_Sensor_Bit_Offset = pDataFormat->bitOffset;
        sensorConfigReg.Digital_Sensor_LeftAligned = pDataFormat->leftJustified ? 1 : 0;
        sensorConfigReg.Digital_Sensor_LittleEndian = pDataFormat->littleEndian ? 1 : 0;

        switch (pDataFormat->coding)
        {
        case ADI_SENSE_1000_DIGITAL_SENSOR_DATA_CODING_UNIPOLAR:
            sensorConfigReg.Digital_Sensor_Coding = ADISENSE_CORE_DIGITAL_SENSOR_CONFIG_CODING_UNIPOLAR;
            break;
        case ADI_SENSE_1000_DIGITAL_SENSOR_DATA_CODING_TWOS_COMPLEMENT:
            sensorConfigReg.Digital_Sensor_Coding = ADISENSE_CORE_DIGITAL_SENSOR_CONFIG_CODING_TWOS_COMPL;
            break;
        case ADI_SENSE_1000_DIGITAL_SENSOR_DATA_CODING_OFFSET_BINARY:
            sensorConfigReg.Digital_Sensor_Coding = ADISENSE_CORE_DIGITAL_SENSOR_CONFIG_CODING_OFFSET_BINARY;
            break;
        default:
            ADI_SENSE_LOG_ERROR("Invalid coding specified for digital sensor data format");
            return ADI_SENSE_INVALID_PARAM;
        }
    }

    WRITE_REG_U16(hDevice, sensorConfigReg.VALUE16,
                  CORE_DIGITAL_SENSOR_CONFIGn(eChannelId));


    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelI2cSensorType(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_I2C_SENSOR_TYPE sensorType)
{
    ADI_ADISENSE_CORE_Sensor_Type_t sensorTypeReg;

    sensorTypeReg.VALUE16 = REG_RESET_VAL(CORE_SENSOR_TYPEn);

    /* Ensure that the sensor type is valid for this channel */
    switch(sensorType)
    {
    case ADI_SENSE_1000_I2C_SENSOR_HUMIDITY_HONEYWELL_HUMIDICON:
        sensorTypeReg.Sensor_Type = ADISENSE_CORE_SENSOR_TYPE_SENSOR_I2C_HUMIDITY_HONEYWELL_HUMIDICON;
        break;
    case ADI_SENSE_1000_I2C_SENSOR_HUMIDITY_SENSIRION_SHT3X:
        sensorTypeReg.Sensor_Type = ADISENSE_CORE_SENSOR_TYPE_SENSOR_I2C_HUMIDITY_SENSIRION_SHT3X;
        break;
    default:
        ADI_SENSE_LOG_ERROR("Unsupported I2C sensor type %d specified", sensorType);
        return ADI_SENSE_INVALID_PARAM;
    }

    WRITE_REG_U16(hDevice, sensorTypeReg.VALUE16, CORE_SENSOR_TYPEn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelI2cSensorAddress(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    uint32_t deviceAddress)
{
    CHECK_REG_FIELD_VAL(CORE_DIGITAL_SENSOR_ADDRESS_DIGITAL_SENSOR_ADDRESS, deviceAddress);
    WRITE_REG_U8(hDevice, deviceAddress, CORE_DIGITAL_SENSOR_ADDRESSn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_SetI2cChannelConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_I2C_CHANNEL_CONFIG *pI2cChannelConfig)
{
    ADI_SENSE_RESULT eRet;

    eRet = adi_sense_SetChannelI2cSensorType(hDevice, eChannelId,
                                            pI2cChannelConfig->sensor);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set I2C sensor type for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetChannelI2cSensorAddress(hDevice, eChannelId,
                                               pI2cChannelConfig->deviceAddress);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set I2C sensor address for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetDigitalSensorCommands(hDevice, eChannelId,
                                              &pI2cChannelConfig->configurationCommand,
                                              &pI2cChannelConfig->dataRequestCommand);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set I2C sensor commands for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetDigitalSensorFormat(hDevice, eChannelId,
                                            &pI2cChannelConfig->dataFormat);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set I2C sensor data format for channel %d",
                            eChannelId);
        return eRet;
    }

    return ADI_SENSE_SUCCESS;
}

static ADI_SENSE_RESULT adi_sense_SetChannelSpiSensorType(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_SPI_SENSOR_TYPE sensorType)
{
    ADI_ADISENSE_CORE_Sensor_Type_t sensorTypeReg;

    sensorTypeReg.VALUE16 = REG_RESET_VAL(CORE_SENSOR_TYPEn);

    /* Ensure that the sensor type is valid for this channel */
    switch(sensorType)
    {
    case ADI_SENSE_1000_SPI_SENSOR_PRESSURE_HONEYWELL_TRUSTABILITY:
        sensorTypeReg.Sensor_Type = ADISENSE_CORE_SENSOR_TYPE_SENSOR_SPI_PRESSURE_HONEYWELL_TRUSTABILITY;
        break;
    case ADI_SENSE_1000_SPI_SENSOR_ACCELEROMETER_ADI_ADXL362:
        sensorTypeReg.Sensor_Type = ADISENSE_CORE_SENSOR_TYPE_SENSOR_SPI_ACCELEROMETER_1;
        break;
    default:
        ADI_SENSE_LOG_ERROR("Unsupported SPI sensor type %d specified", sensorType);
        return ADI_SENSE_INVALID_PARAM;
    }

    WRITE_REG_U16(hDevice, sensorTypeReg.VALUE16, CORE_SENSOR_TYPEn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_SetSpiChannelConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_SPI_CHANNEL_CONFIG *pSpiChannelConfig)
{
    ADI_SENSE_RESULT eRet;

    eRet = adi_sense_SetChannelSpiSensorType(hDevice, eChannelId,
                                             pSpiChannelConfig->sensor);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set SPI sensor type for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetDigitalSensorCommands(hDevice, eChannelId,
                                              &pSpiChannelConfig->configurationCommand,
                                              &pSpiChannelConfig->dataRequestCommand);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set SPI sensor commands for channel %d",
                            eChannelId);
        return eRet;
    }

    eRet = adi_sense_SetDigitalSensorFormat(hDevice, eChannelId,
                                            &pSpiChannelConfig->dataFormat);
    if (eRet != ADI_SENSE_SUCCESS)
    {
        ADI_SENSE_LOG_ERROR("Failed to set SPI sensor data format for channel %d",
                            eChannelId);
        return eRet;
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetChannelThresholdLimits(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    float32_t fHighThresholdLimit,
    float32_t fLowThresholdLimit)
{
    /*
     * If the low/high limits are *both* set to 0 in memory, or NaNs, assume
     * that they are unset, or not required, and use infinity defaults instead
     */
    if (fHighThresholdLimit == 0.0 && fLowThresholdLimit == 0.0)
    {
        fHighThresholdLimit = INFINITY;
        fLowThresholdLimit = -INFINITY;
    }
    else
    {
        if (isnan(fHighThresholdLimit))
            fHighThresholdLimit = INFINITY;
        if (isnan(fLowThresholdLimit))
            fLowThresholdLimit = -INFINITY;
    }

    WRITE_REG_FLOAT(hDevice, fHighThresholdLimit,
                    CORE_HIGH_THRESHOLD_LIMITn(eChannelId));
    WRITE_REG_FLOAT(hDevice, fLowThresholdLimit,
                    CORE_LOW_THRESHOLD_LIMITn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetOffsetGain(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    float32_t fOffsetAdjustment,
    float32_t fGainAdjustment)
{
    /* Replace with default values if NaNs are specified (or 0.0 for gain) */
    if (isnan(fGainAdjustment) || (fGainAdjustment == 0.0))
        fGainAdjustment = 1.0;
    if (isnan(fOffsetAdjustment))
        fOffsetAdjustment = 0.0;

    WRITE_REG_FLOAT(hDevice, fGainAdjustment, CORE_SENSOR_GAINn(eChannelId));
    WRITE_REG_FLOAT(hDevice, fOffsetAdjustment, CORE_SENSOR_OFFSETn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetChannelSettlingTime(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    uint32_t nSettlingTime)
{
    CHECK_REG_FIELD_VAL(CORE_SETTLING_TIME_SETTLING_TIME, nSettlingTime);

    WRITE_REG_U16(hDevice, nSettlingTime, CORE_SETTLING_TIMEn(eChannelId));

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetChannelConfig(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    ADI_SENSE_1000_CHANNEL_ID eChannelId,
    ADI_SENSE_1000_CHANNEL_CONFIG *pChannelConfig)
{
    ADI_SENSE_RESULT eRet;

    if (! ADI_SENSE_1000_CHANNEL_IS_VIRTUAL(eChannelId))
    {
        /* If the channel is not enabled, disable it and return */
        if (! pChannelConfig->enableChannel)
            return adi_sense_1000_SetChannelCount(hDevice, eChannelId, 0);

        eRet = adi_sense_1000_SetChannelCount(hDevice, eChannelId,
                                              pChannelConfig->measurementsPerCycle);
        if (eRet != ADI_SENSE_SUCCESS)
        {
            ADI_SENSE_LOG_ERROR("Failed to set measurement count for channel %d",
                                eChannelId);
            return eRet;
        }

        switch (eChannelId)
        {
        case ADI_SENSE_1000_CHANNEL_ID_CJC_0:
        case ADI_SENSE_1000_CHANNEL_ID_CJC_1:
        case ADI_SENSE_1000_CHANNEL_ID_SENSOR_0:
        case ADI_SENSE_1000_CHANNEL_ID_SENSOR_1:
        case ADI_SENSE_1000_CHANNEL_ID_SENSOR_2:
        case ADI_SENSE_1000_CHANNEL_ID_SENSOR_3:
        case ADI_SENSE_1000_CHANNEL_ID_VOLTAGE_0:
        case ADI_SENSE_1000_CHANNEL_ID_CURRENT_0:
            eRet = adi_sense_SetAdcChannelConfig(hDevice, eChannelId, pChannelConfig);
            break;
        case ADI_SENSE_1000_CHANNEL_ID_I2C_0:
        case ADI_SENSE_1000_CHANNEL_ID_I2C_1:
            eRet = adi_sense_SetI2cChannelConfig(hDevice, eChannelId,
                                                 &pChannelConfig->i2cChannelConfig);
            break;
        case ADI_SENSE_1000_CHANNEL_ID_SPI_0:
            eRet = adi_sense_SetSpiChannelConfig(hDevice, eChannelId,
                                                 &pChannelConfig->spiChannelConfig);
            break;
        default:
            ADI_SENSE_LOG_ERROR("Invalid channel ID %d specified", eChannelId);
            return ADI_SENSE_INVALID_PARAM;
        }

        eRet = adi_sense_1000_SetChannelSettlingTime(hDevice, eChannelId,
                                                     pChannelConfig->extraSettlingTime);
        if (eRet != ADI_SENSE_SUCCESS)
        {
            ADI_SENSE_LOG_ERROR("Failed to set settling time for channel %d",
                                eChannelId);
            return eRet;
        }
    }

    if (pChannelConfig->enableChannel)
    {
        /* Threshold limits can be configured individually for virtual channels */
        eRet = adi_sense_1000_SetChannelThresholdLimits(hDevice, eChannelId,
                                                        pChannelConfig->highThreshold,
                                                        pChannelConfig->lowThreshold);
        if (eRet != ADI_SENSE_SUCCESS)
        {
            ADI_SENSE_LOG_ERROR("Failed to set threshold limits for channel %d",
                                eChannelId);
            return eRet;
        }

        /* Offset and gain can be configured individually for virtual channels */
        eRet = adi_sense_1000_SetOffsetGain(hDevice, eChannelId,
                                            pChannelConfig->offsetAdjustment,
                                            pChannelConfig->gainAdjustment);
        if (eRet != ADI_SENSE_SUCCESS)
        {
            ADI_SENSE_LOG_ERROR("Failed to set offset/gain for channel %d",
                                eChannelId);
            return eRet;
        }
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_SetConfig(
    ADI_SENSE_DEVICE_HANDLE    const hDevice,
    ADI_SENSE_CONFIG         * const pConfig)
{
    ADI_SENSE_1000_CONFIG *pDeviceConfig;
    ADI_SENSE_PRODUCT_ID productId;
    ADI_SENSE_RESULT eRet;

    if (pConfig->productId != ADI_SENSE_PRODUCT_ID_1000)
    {
        ADI_SENSE_LOG_ERROR("Configuration Product ID (0x%X) is not supported (0x%0X)",
                            pConfig->productId, ADI_SENSE_PRODUCT_ID_1000);
        return ADI_SENSE_INVALID_PARAM;
    }

    /* Check that the actual Product ID is a match? */
    eRet = adi_sense_GetProductID(hDevice, &productId);
    if (eRet)
    {
        ADI_SENSE_LOG_ERROR("Failed to read device Product ID register");
        return eRet;
    }
    if (pConfig->productId != productId)
    {
        ADI_SENSE_LOG_ERROR("Configuration Product ID (0x%X) does not match device (0x%0X)",
                            pConfig->productId, productId);
        return ADI_SENSE_INVALID_PARAM;
    }

    pDeviceConfig = &pConfig->adisense1000;

    eRet = adi_sense_1000_SetPowerConfig(hDevice, &pDeviceConfig->power);
    if (eRet)
    {
        ADI_SENSE_LOG_ERROR("Failed to set power configuration");
        return eRet;
    }

    eRet = adi_sense_1000_SetMeasurementConfig(hDevice, &pDeviceConfig->measurement);
    if (eRet)
    {
        ADI_SENSE_LOG_ERROR("Failed to set measurement configuration");
        return eRet;
    }

    eRet = adi_sense_1000_SetDiagnosticsConfig(hDevice, &pDeviceConfig->diagnostics);
    if (eRet)
    {
        ADI_SENSE_LOG_ERROR("Failed to set diagnostics configuration");
        return eRet;
    }

    for (ADI_SENSE_1000_CHANNEL_ID id = 0; id < ADI_SENSE_1000_MAX_CHANNELS; id++)
    {
        eRet = adi_sense_1000_SetChannelConfig(hDevice, id,
                                               &pDeviceConfig->channels[id]);
        if (eRet)
        {
            ADI_SENSE_LOG_ERROR("Failed to set channel %d configuration", id);
            return eRet;
        }
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetLutData(
    ADI_SENSE_DEVICE_HANDLE    const hDevice,
    ADI_SENSE_1000_LUT       * const pLutData)
{
    ADI_SENSE_1000_LUT_HEADER *pLutHeader = &pLutData->header;
    ADI_SENSE_1000_LUT_TABLE *pLutTable = pLutData->tables;
    unsigned actualLength = 0;

    if (pLutData->header.signature != ADI_SENSE_LUT_SIGNATURE)
    {
        ADI_SENSE_LOG_ERROR("LUT signature incorrect (expected 0x%X, actual 0x%X)",
                            ADI_SENSE_LUT_SIGNATURE, pLutHeader->signature);
        return ADI_SENSE_INVALID_SIGNATURE;
    }

    for (unsigned i = 0; i < pLutHeader->numTables; i++)
    {
        ADI_SENSE_1000_LUT_DESCRIPTOR *pDesc = &pLutTable->descriptor;
        ADI_SENSE_1000_LUT_TABLE_DATA *pData = &pLutTable->data;
        unsigned short calculatedCrc;

        switch (pDesc->geometry)
        {
        case ADI_SENSE_1000_LUT_GEOMETRY_COEFFS:
                switch (pDesc->equation)
                {
                case ADI_SENSE_1000_LUT_EQUATION_POLYN:
                case ADI_SENSE_1000_LUT_EQUATION_POLYNEXP:
                case ADI_SENSE_1000_LUT_EQUATION_QUADRATIC:
                case ADI_SENSE_1000_LUT_EQUATION_STEINHART:
                case ADI_SENSE_1000_LUT_EQUATION_LOGARITHMIC:
                case ADI_SENSE_1000_LUT_EQUATION_EXPONENTIAL:
                case ADI_SENSE_1000_LUT_EQUATION_BIVARIATE_POLYN:
                break;
                default:
                    ADI_SENSE_LOG_ERROR("Invalid equation %u specified for LUT table %u",
                                        pDesc->equation, i);
                    return ADI_SENSE_INVALID_PARAM;
                }
            break;
        case ADI_SENSE_1000_LUT_GEOMETRY_NES_1D:
        case ADI_SENSE_1000_LUT_GEOMETRY_NES_2D:
        case ADI_SENSE_1000_LUT_GEOMETRY_ES_1D:
        case ADI_SENSE_1000_LUT_GEOMETRY_ES_2D:
                if (pDesc->equation != ADI_SENSE_1000_LUT_EQUATION_LUT) {
                    ADI_SENSE_LOG_ERROR("Invalid equation %u specified for LUT table %u",
                                        pDesc->equation, i);
                    return ADI_SENSE_INVALID_PARAM;
                }
            break;
        default:
            ADI_SENSE_LOG_ERROR("Invalid geometry %u specified for LUT table %u",
                                pDesc->geometry, i);
            return ADI_SENSE_INVALID_PARAM;
        }

        switch (pDesc->dataType)
        {
        case ADI_SENSE_1000_LUT_DATA_TYPE_FLOAT32:
        case ADI_SENSE_1000_LUT_DATA_TYPE_FLOAT64:
            break;
        default:
            ADI_SENSE_LOG_ERROR("Invalid vector format %u specified for LUT table %u",
                                pDesc->dataType, i);
            return ADI_SENSE_INVALID_PARAM;
        }

        calculatedCrc = crc16_ccitt(pData, pDesc->length);
        if (calculatedCrc != pDesc->crc16)
        {
            ADI_SENSE_LOG_ERROR("CRC validation failed on LUT table %u (expected 0x%04X, actual 0x%04X)",
                                i, pDesc->crc16, calculatedCrc);
            return ADI_SENSE_CRC_ERROR;
        }

        actualLength += sizeof(*pDesc) + pDesc->length;

        /* Move to the next look-up table */
        pLutTable = (ADI_SENSE_1000_LUT_TABLE *)((uint8_t *)pLutTable + sizeof(*pDesc) + pDesc->length);
    }

    if (actualLength != pLutHeader->totalLength)
    {
        ADI_SENSE_LOG_ERROR("LUT table length mismatch (expected %u, actual %u)",
                            pLutHeader->totalLength, actualLength);
        return ADI_SENSE_WRONG_SIZE;
    }

    if (sizeof(*pLutHeader) + pLutHeader->totalLength > ADI_SENSE_LUT_MAX_SIZE)
    {
        ADI_SENSE_LOG_ERROR("Maximum LUT table length (%u bytes) exceeded",
                            ADI_SENSE_LUT_MAX_SIZE);
        return ADI_SENSE_WRONG_SIZE;
    }

    /* Write the LUT data to the device */
    unsigned lutSize = sizeof(*pLutHeader) + pLutHeader->totalLength;
    WRITE_REG_U16(hDevice, 0, CORE_LUT_OFFSET);
    WRITE_REG_U8_ARRAY(hDevice, (uint8_t *)pLutData, lutSize, CORE_LUT_DATA);

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_SetLutDataRaw(
    ADI_SENSE_DEVICE_HANDLE    const hDevice,
    ADI_SENSE_1000_LUT_RAW   * const pLutData)
{
    return adi_sense_1000_SetLutData(hDevice,
                                     (ADI_SENSE_1000_LUT * const)pLutData);
}

static ADI_SENSE_RESULT getLutTableSize(
    ADI_SENSE_1000_LUT_DESCRIPTOR * const pDesc,
    ADI_SENSE_1000_LUT_TABLE_DATA * const pData,
    unsigned *pLength)
{
    switch (pDesc->geometry)
    {
    case ADI_SENSE_1000_LUT_GEOMETRY_COEFFS:
        if (pDesc->equation == ADI_SENSE_1000_LUT_EQUATION_BIVARIATE_POLYN)
            *pLength = ADI_SENSE_1000_LUT_2D_POLYN_COEFF_LIST_SIZE(pData->coeffList2d);
        else
            *pLength = ADI_SENSE_1000_LUT_COEFF_LIST_SIZE(pData->coeffList);
        break;
    case ADI_SENSE_1000_LUT_GEOMETRY_NES_1D:
        *pLength = ADI_SENSE_1000_LUT_1D_NES_SIZE(pData->lut1dNes);
        break;
    case ADI_SENSE_1000_LUT_GEOMETRY_NES_2D:
        *pLength = ADI_SENSE_1000_LUT_2D_NES_SIZE(pData->lut2dNes);
        break;
    case ADI_SENSE_1000_LUT_GEOMETRY_ES_1D:
        *pLength = ADI_SENSE_1000_LUT_1D_ES_SIZE(pData->lut1dEs);
        break;
    case ADI_SENSE_1000_LUT_GEOMETRY_ES_2D:
        *pLength = ADI_SENSE_1000_LUT_2D_ES_SIZE(pData->lut2dEs);
        break;
    default:
        ADI_SENSE_LOG_ERROR("Invalid LUT table geometry %d specified\r\n",
                            pDesc->geometry);
        return ADI_SENSE_INVALID_PARAM;
    }

    return ADI_SENSE_SUCCESS;
}

ADI_SENSE_RESULT adi_sense_1000_AssembleLutData(
    ADI_SENSE_1000_LUT                  * pLutBuffer,
    unsigned                              nLutBufferSize,
    unsigned                        const nNumTables,
    ADI_SENSE_1000_LUT_DESCRIPTOR * const ppDesc[],
    ADI_SENSE_1000_LUT_TABLE_DATA * const ppData[])
{
    ADI_SENSE_1000_LUT_HEADER *pHdr = &pLutBuffer->header;
    uint8_t *pLutTableData = (uint8_t *)pLutBuffer + sizeof(*pHdr);

    if (sizeof(*pHdr) > nLutBufferSize)
    {
        ADI_SENSE_LOG_ERROR("Insufficient LUT buffer size provided");
        return ADI_SENSE_INVALID_PARAM;
    }

    /* First initialise the top-level header */
    pHdr->signature = ADI_SENSE_LUT_SIGNATURE;
    pHdr->version.major = 1;
    pHdr->version.minor = 0;
    pHdr->numTables = 0;
    pHdr->totalLength = 0;

    /*
     * Walk through the list of table pointers provided, appending the table
     * descriptor+data from each one to the provided LUT buffer
     */
    for (unsigned i = 0; i < nNumTables; i++)
    {
        ADI_SENSE_1000_LUT_DESCRIPTOR * const pDesc = ppDesc[i];
        ADI_SENSE_1000_LUT_TABLE_DATA * const pData = ppData[i];
        ADI_SENSE_RESULT res;
        unsigned dataLength = 0;

        /* Calculate the length of the table data */
        res = getLutTableSize(pDesc, pData, &dataLength);
        if (res != ADI_SENSE_SUCCESS)
            return res;

        /* Fill in the table descriptor length and CRC fields */
        pDesc->length = dataLength;
        pDesc->crc16 = crc16_ccitt(pData, dataLength);

        if ((sizeof(*pHdr) + pHdr->totalLength + sizeof(*pDesc) + dataLength) > nLutBufferSize)
        {
            ADI_SENSE_LOG_ERROR("Insufficient LUT buffer size provided");
            return ADI_SENSE_INVALID_PARAM;
        }

        /* Append the table to the LUT buffer (desc + data) */
        memcpy(pLutTableData + pHdr->totalLength, pDesc, sizeof(*pDesc));
        pHdr->totalLength += sizeof(*pDesc);
        memcpy(pLutTableData + pHdr->totalLength, pData, dataLength);
        pHdr->totalLength += dataLength;

        pHdr->numTables++;
    }

    return ADI_SENSE_SUCCESS;
}

#define CAL_TABLE_ROWS ADI_SENSE_1000_CAL_NUM_TABLES
#define CAL_TABLE_COLS ADI_SENSE_1000_CAL_NUM_TEMPS
#define CAL_TABLE_SIZE (sizeof(float) * CAL_TABLE_ROWS * CAL_TABLE_COLS)

ADI_SENSE_RESULT adi_sense_1000_ReadCalTable(
    ADI_SENSE_DEVICE_HANDLE hDevice,
    float *pfBuffer,
    unsigned nMaxLen,
    unsigned *pnDataLen,
    unsigned *pnRows,
    unsigned *pnColumns)
{
    *pnDataLen = sizeof(float) * CAL_TABLE_ROWS * CAL_TABLE_COLS;
    *pnRows = CAL_TABLE_ROWS;
    *pnColumns = CAL_TABLE_COLS;

    if (nMaxLen > *pnDataLen)
        nMaxLen = *pnDataLen;

    WRITE_REG_U16(hDevice, 0, CORE_CAL_OFFSET);
    READ_REG_U8_ARRAY(hDevice, (uint8_t *)pfBuffer, nMaxLen, CORE_CAL_DATA);

    return ADI_SENSE_SUCCESS;
}