ads1115应用电路及驱动程序_ads1115单通道程序-程序员宅基地

技术标签: ads1115驱动  笔记  ads1115采集程序  ads1115应用电路  

应用电路

注意输入串联的电阻499R,以及电容4.7nF

对外的接口都需要上拉电阻(特别注意RDY的上拉电阻)

参考程序

参考程序文件列表

 

 参考程序代码

/**
 * @file hal.h
 *
 * @brief Example of a hardware abstraction layer
 * @warning This software utilizes TI Drivers
 *
 * @copyright Copyright (C) 2021 Texas Instruments Incorporated - http://www.ti.com/
 *
 *  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 Texas Instruments Incorporated nor the names of
 *    its contributors may be used to endorse or promote products derived
 *    from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
 *  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
 *  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
 *  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
 *  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 *  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
 *  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 *
 */


#ifndef HAL_H_
#define HAL_H_

#include "ads1115.h"

//****************************************************************************
//
// Standard libraries
//
//****************************************************************************
#include <stdbool.h>
#include <stdint.h>



//****************************************************************************
//
// Insert processor specific header file(s) here
//
//****************************************************************************

/*  --- INSERT YOUR CODE HERE --- */
#include "ti/devices/msp432e4/driverlib/driverlib.h"


//****************************************************************************
//
// BoosterPack pinout...LP
//
//****************************************************************************
//
//                  LEFT                                RIGHT
//               /--------\                          /--------\
//        +3.3V -|3V3  +5V|- +5V                    -|PG1  GND|- GND
//              -|PD2  GND|- GND                    -|PK4  PM7|-
//              -|PP0  PB4|-                        -|PK5 *PP5|-
//              -|PP1  PB5|-                        -|PM0  PA7|-
//              -|PD4  PK0|-                        -|PM1  RST|-
//              -|PD5  PK1|-                        -|PM2  PQ2|-
//              -|PQ0  PK2|-                        -|PH0  PQ3|-
//              -|PP4* PK3|-                        -|PH1 *PP3|-
//          SCL -|PN5  PA4|-                        -|PK6  PQ1|-
//          SDA -|PN4  PA5|-              ALERT/RDY -|PK7  PM6|-
//               \--------/                          \--------/
//
//****************************************************************************

//*****************************************************************************
//
// Pin definitions (MSP432E401Y)
//
//*****************************************************************************
#define ALERT_RDY_PORT          (GPIO_PORTK_BASE)
#define ALERT_RDY_PIN           (GPIO_PIN_7)
#define ALERT_RDY_INT           (INT_GPIOK7)
#define I2Cbus 0    // Used in TI Drivers implementation
//*****************************************************************************
//
// Function Prototypes
//
//*****************************************************************************
void InitADC(void);
void delay_ms(const uint32_t delay_time_ms);
void delay_us(const uint32_t delay_time_us);

int8_t sendI2CData(uint8_t address, uint8_t *arrayIndex, uint8_t length);
int8_t sendI2CRegPointer(uint8_t address, uint8_t *arrayIndex, uint8_t length);
int8_t receiveI2CData(uint8_t address, uint8_t *arrayIndex, uint8_t length);
int8_t receiveI2CDataNoWrite(uint8_t address, uint8_t *arrayIndex, uint8_t length, bool noWrite);

bool getALERTinterruptStatus(void);
bool waitForALERTinterrupt(const uint32_t timeout_ms);
void setALERTinterruptStatus(const bool value);
void enableALERTinterrupt(const bool intEnable);
void GPIO_ALERT_IRQHandler(uint_least8_t index);

//*****************************************************************************
//
// Macros
//
//*****************************************************************************
/** Alias used for setting GPIOs pins to the logic "high" state */
#define HIGH                ((bool) true)

/** Alias used for setting GPIOs pins to the logic "low" state */
#define LOW                 ((bool) false)



#endif /* HAL_H_ */

/**
 * @file hal.c
 *
 * @brief Example of a hardware abstraction layer
 * @warning This software utilizes TI Drivers
 *
 * @copyright Copyright (C) 2021 Texas Instruments Incorporated - http://www.ti.com/
 *
 *  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 Texas Instruments Incorporated nor the names of
 *    its contributors may be used to endorse or promote products derived
 *    from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
 *  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
 *  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
 *  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
 *  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 *  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
 *  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 *
 */

#include "hal.h"
/* Following statements relate to use of TI Driver implementation */
#include <ti/drivers/I2C.h>
#include <ti/drivers/i2c/I2CMSP432E4.h>
extern I2C_Handle g_I2Chandle;

//****************************************************************************
//
// Internal variables
//
//****************************************************************************
// Flag to indicate if an ALERT/RDY interrupt has occurred
static volatile bool flag_nALERT_INTERRUPT = false;
//****************************************************************************
//
// Internal function prototypes
//
//****************************************************************************
void InitGPIO(void);
void InitI2C(void);

//****************************************************************************
//
// External Functions (prototypes declared in hal.h)
//
//****************************************************************************
/**
 * @brief getALERTinterruptStatus()
 * Gets the current status of ALERT/RDY interrupt flag.
 *
 * @ return boolean status of flag_nALERT_INTERRUPT.
 */
bool getALERTinterruptStatus(void)
{
   return flag_nALERT_INTERRUPT;
}
/**
 * @brief setALERTinterruptStatus(void)
 * Sets the value of the ALERT/RDY interrupt flag.
 *
 * @param[in] value where status is set with true; false clears the status.
 *
 * @return none
 */
void setALERTinterruptStatus(const bool value)
{
    flag_nALERT_INTERRUPT = value;
}
/**
 *
 * @brief enableALERTinterrupt()
 * Enables or disables the ALERT/RDY interrupt.
 *
 * @param[in] intEnable Where interrupt is enabled with true; false disables the interrupt.
 *
 * @return none
 */
void enableALERTinterrupt(const bool intEnable)
{
    /* --- INSERT YOUR CODE HERE --- */

    /* The following code is based on a TI Drivers implementation */
    if(intEnable)
    {
        flag_nALERT_INTERRUPT = false;
        GPIO_clearInt(ALERT_CONST);
        SysCtlDelay(10);
        GPIO_enableInt(ALERT_CONST);
    }
    else GPIO_disableInt(ALERT_CONST);
}
/**
 *
 * @brief InitADC()
 * Initializes MCU peripherals for interfacing with the ADC.
 *
 * @return none
 */
void InitADC(void)
{
    // IMPORTANT: Make sure device is powered before setting GPIOs pins to HIGH state.

    // Initialize GPIOs pins used by ADS1x15
    InitGPIO();
    /* Call driver init functions */
    InitI2C();
    // Run ADC startup function (in ADS1115.c)
    adcStartup();
}

//****************************************************************************
//
// Timing functions
//
//****************************************************************************

/**
 *
 * @brief delay_ms()
 * Provides a timing delay with 'ms' resolution.
 *
 * @param[in] delay_time_ms Is the number of milliseconds to delay.
 *
 * @return none
 */
void delay_ms(const uint32_t delay_time_ms)
{
    /* --- INSERT YOUR CODE HERE --- */

    const uint32_t cycles_per_loop = 3;
    uint32_t delayTime = getSysClockHz() / (cycles_per_loop * 1000u);
    delayTime = delayTime * delay_time_ms;
    MAP_SysCtlDelay( delayTime );
}
/**
 *
 * @brief delay_us()
 * Provides a timing delay with 'us' resolution.
 *
 * @param[in] delay_time_us Is the number of microseconds to delay.
 *
 * @return none
 */
//
void delay_us(const uint32_t delay_time_us)
{
    /* --- INSERT YOUR CODE HERE --- */

    const uint32_t cycles_per_loop = 3;
    uint32_t delayTime = getSysClockHz() / (cycles_per_loop * 1000000u);
    delayTime = delayTime * delay_time_us;
    MAP_SysCtlDelay( delayTime );
}

//****************************************************************************
//
// GPIO initialization
//
//****************************************************************************

/**
 *
 * @brief InitGPIO()
 * Configures the MCU's GPIO pins that interface with the ADC.
 *
 * @return none
 *
 */
void InitGPIO(void)
{
    /* --- INSERT YOUR CODE HERE --- */
    // NOTE: Not all hardware implementations may control each of these pins...

    /* The following code is based on a TI Drivers implementation */

    /* Call driver init functions */
    GPIO_init();

    /* Set the interrupt callback function */
    GPIO_setCallback(ALERT_CONST,GPIO_ALERT_IRQHandler );

}
//*****************************************************************************
//
// Interrupt handler for ALERT/RDY GPIO
//
//*****************************************************************************

/**
 *
 * @brief GPIO_ALERT_IRQHandler()
 * Interrupt handler for ALERT/RDY falling edge interrupt.
 *
 * @param[in] index Position of the interrupt for callback.
 *
 * @return none
 */
void GPIO_ALERT_IRQHandler(uint_least8_t index)
{
    /* --- INSERT YOUR CODE HERE --- */

    /* NOTE: You many need to rename or
     * register this interrupt function for your processor.
     *  - Possible ways to handle this interrupt:
     *  1. If you decide to read data here, you may want to
     *      disable other interrupts to avoid partial data reads.
     *  2. Set a flag to read during a polling loop
     *
     *  In this example we set a flag and exit the interrupt routine.
     *  In the main program loop, your application can examine
     *  all state flags and decide which state (operation) to perform next.
     */

    /* Interrupt action: Set a flag */
    flag_nALERT_INTERRUPT = true;
}

//****************************************************************************
//
// GPIO helper functions
//
//****************************************************************************
/**
 *
 * @brief waitForALERTinterrupt()
 * Waits for the ALERT/RDY interrupt or until the specified timeout occurs.
 *
 * @param[in] timeout_ms Number of milliseconds to wait before timeout event.
 *
 * @return Returns 'true' if ALERT/RDY interrupt occurred before the timeout.
 */
bool waitForALERTinterrupt(const uint32_t timeout_ms)
{
    /* --- INSERT YOUR CODE HERE ---
     *
     * Poll the ALERT/RDY GPIO pin until it goes low. To avoid potential infinite
     * loops, you may also want to implement a timer interrupt to occur after
     * the specified timeout period, in case the ALERT/RDY pin is not active.
     * Return a boolean to indicate if ALERT/RDY went low or if a timeout occurred.
     */

    /* The following code is based on a TI Drivers implementation */

    // Convert ms to a # of loop iterations, OR even better use a timer here...
    uint32_t timeout = timeout_ms * 6000;   // convert to # of loop iterations

    // Reset interrupt flag
    flag_nALERT_INTERRUPT = false;

    // Enable interrupts
    GPIO_clearInt(ALERT_CONST);
    delay_us(1);
    GPIO_enableInt(ALERT_CONST);

    // Wait for nDRDY interrupt or timeout - each iteration is about 20 ticks
    do {
        timeout--;
    } while (!flag_nALERT_INTERRUPT && (timeout > 0));

    GPIO_disableInt(ALERT_CONST);

    // Reset interrupt flag
    flag_nALERT_INTERRUPT = false;

    // Timeout counter greater than zero indicates that an interrupt occurred
    return (timeout > 0);
}
/**
 *
 * @brief InitI2C()
 * Configures the MCU's I2C peripheral, for interfacing with target devices.
 *
 * @return none
 */
void InitI2C(void)
{
    /* --- INSERT YOUR CODE HERE --- */

    //
    // Enabling I2C2 peripheral.
    //

    //
    // Configuring the pin muxing for I2C2 functions.
    //

    //
    // Enabling and initializing the I2C2 master module.
    //

    /* The following code is based on a TI Drivers implementation */

    /* Call driver init functions */
    I2C_init();
}

/**
 *
 * @brief sendI2CData()
 * Configures the MCU's I2C peripheral, for interfacing with target devices.
 *
 * @param[in] address Of target device.
 * @param[in] arrayIndex Is pointer to an array of data to be transmitted.
 * @param[in] length Of the data array.
 *
 * @return 0 is communication success; < 0 is communication failure.
 */
int8_t sendI2CData(uint8_t address, uint8_t *arrayIndex, uint8_t length)
{
    /* --- INSERT YOUR CODE HERE --- */

    /* The following code is based on a TI Drivers implementation */
    int8_t retStatus = 0;
    uint8_t wData[256];
    uint8_t rData[1];
    wData[0] = address;
    uint16_t i;
    // Copy the data array
    for(i = 1; i < (length + 1); i++)
    {
        wData[i] = arrayIndex[i-1];
    }
    //
    // Initialize the optional I2C bus parameters
    //
    I2C_Params params;
    I2C_Params_init(&params);
    params.bitRate = I2C_400kHz;
    //
    // Open the I2C bus for usage
    //
    I2C_Handle i2cHandle = I2C_open(I2Cbus, &params);
    //
    // Initialize the slave address for transactions
    //
    I2C_Transaction transaction = {0};
    transaction.slaveAddress = ADS1115_ADDRESS;
    transaction.readBuf = rData;
    transaction.readCount = 0;
    transaction.writeBuf = wData;
    transaction.writeCount = length + 1;
    retStatus = I2C_transfer(i2cHandle, &transaction);

    //
    // Return error, if read failed
    //
    if (retStatus == false)
    {
        /* Send error response here then close the port */
        I2C_close(i2cHandle);
        return -1;
    }

    I2C_close(i2cHandle);

    return 0;
}
/**
 *
 * @brief sendI2CRegPointer()
 * Write to set the desired pointer position for reading/writing register data.
 *
 * @param[in] address Of target device.
 * @param[in] arrayIndex Is pointer to an array of data to be transmitted.
 * @param[in] length Of the data array.
 *
 * @return 0 is communication success; < 0 is communication failure.
 */
int8_t sendI2CRegPointer(uint8_t address, uint8_t *arrayIndex, uint8_t length)
{
    /* --- INSERT YOUR CODE HERE --- */

    /* The following code is based on a TI Drivers implementation */

    int8_t retStatus = 0;
    uint8_t wData[256];
    uint8_t rData[1];
    wData[0] = address;
    uint16_t i;

    for(i = 1; i < (length + 1); i++)
    {
        wData[i] = arrayIndex[i-1];
    }

    //
    // Initialize the slave address for transactions
    //
    I2C_Transaction transaction = {0};
    transaction.slaveAddress = ADS1115_ADDRESS;

    transaction.readBuf = rData;
    transaction.readCount = 0;
    transaction.writeBuf = wData;
    transaction.writeCount = length + 1;
    retStatus = I2C_transfer(g_I2Chandle, &transaction);

    //
    // Return error, if read failed
    //
    if (retStatus == false)
    {
        // Add error handling routine
        return -1;
    }

    return 0;
}
/**
 *
 * @brief receiveI2CData()
 * Read data from the desired pointer position for register data.
 *
 * @param[in] address Of target device.
 * @param[out] arrayIndex Is pointer to an array of data to be transmitted.
 * @param[in] length Of the data array.
 *
 * @return 0 is communication success; < 0 is communication failure.
 */
int8_t receiveI2CData(uint8_t address, uint8_t *arrayIndex, uint8_t length)
{
    /* --- INSERT YOUR CODE HERE --- */

    /* The following code is based on a TI Drivers implementation */

    int8_t retStatus = 0;
    uint8_t wData[1];
    uint8_t rData[256];
    wData[0] = address;
    uint16_t i;
    //
    // Initialize the optional I2C bus parameters
    //
    I2C_Params params;
    I2C_Params_init(&params);
    params.bitRate = I2C_400kHz;
    //
    // Open the I2C bus for usage
    //
    I2C_Handle i2cHandle = I2C_open(I2Cbus, &params);
    //
    // Initialize the slave address for transactions
    //
    I2C_Transaction transaction = {0};
    transaction.slaveAddress = ADS1115_ADDRESS;

    transaction.readBuf = rData ;
    transaction.readCount = length;
    transaction.writeBuf = wData;
    transaction.writeCount = 1;
    retStatus = I2C_transfer(i2cHandle, &transaction);

    //
    // Return error, if read failed
    //
    if (retStatus == false)
    {
        I2C_close(i2cHandle);
        // Insert error handling routine
        return -1;
    }

    I2C_close(i2cHandle);

    for(i = 0; i < length; i++)
    {
        arrayIndex[i] = rData[i];
    }

    return 0;
}
/**
 *
 * @brief receiveI2CDataNoWrite()
 * Read data from the desired pointer position for register data.
 *
 * @param[in] address Of target device.
 * @param[out] arrayIndex Is pointer to an array of data to be transmitted.
 * @param[in] length Of the data array.
 * @param[in] noWrite Boolean of condition if write command is required.
 * false = no write of device address, true = write device address
 *
 * @return 0 is communication success; < 0 is communication failure.
 */
int8_t receiveI2CDataNoWrite(uint8_t address, uint8_t *arrayIndex, uint8_t length, bool noWrite)
{
    /* --- INSERT YOUR CODE HERE --- */

    /* The following code is based on a TI Drivers implementation */

    int8_t retStatus = 0;
    uint8_t wData[1];
    uint8_t rData[256];
    wData[0] = address;
    uint16_t i;
    //
    // Initialize the slave address for transactions
    //
    I2C_Transaction transaction = {0};
    transaction.slaveAddress = ADS1115_ADDRESS;

    transaction.readBuf = rData ;
    transaction.readCount = length;
    transaction.writeBuf = wData;
    if(noWrite) transaction.writeCount = 0;
    else transaction.writeCount = 1;
    retStatus = I2C_transfer(g_I2Chandle, &transaction);

    //
    // Return error, if read failed
    //
    if (retStatus == false)
    {
        // Insert error handling routine
        return -1;
    }

    for(i = 0; i < length; i++)
    {
        arrayIndex[i] = rData[i];
    }

    return 0;
}

/**
 * @file ads1115.h
 *
 * @brief This header file contains all register map definitions for the ADS1115 device family.
 * @warning This software utilizes TI Drivers
 *
 * @copyright Copyright (C) 2021 Texas Instruments Incorporated - http://www.ti.com/
 *
 *  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 Texas Instruments Incorporated nor the names of
 *    its contributors may be used to endorse or promote products derived
 *    from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
 *  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
 *  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
 *  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
 *  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 *  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
 *  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 *
 */
#ifndef ADS1115_H_
#define ADS1115_H_

//****************************************************************************
//
// Standard Libraries
//
//****************************************************************************
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
//****************************************************************************
//
// Custom Libraries
//
//****************************************************************************
#include "hal.h"
//****************************************************************************
//
// Global variables
//
//****************************************************************************
extern const char *adcRegisterNames[];
#define ADS1115_ADDRESS 0x48

//**********************************************************************************
//
// Function prototypes
//
//**********************************************************************************
void adcStartup(void);
uint16_t readSingleRegister(uint8_t address);
int32_t readConversionRegister(void);
bool writeSingleRegister(uint8_t address, uint16_t data);
bool writeSingleRegisterNoRead(uint8_t address, uint16_t data);
void delayBeforeRead(void);
bool resetDevice(void);
int16_t readData(void);
uint16_t startAdcConversion(void);
uint16_t stopAdcConversion(void);

// Getter functions
uint16_t getRegisterValue(uint8_t address);

// Helper functions
uint8_t upperByte(uint16_t uint16_Word);
uint8_t lowerByte(uint16_t uint16_Word);
uint16_t combineBytes(uint8_t upperByte, uint8_t lowerByte);
int32_t signExtend(const uint8_t dataBytes[]);

//****************************************************************************
//
// Register macros
//
//****************************************************************************

#define WLENGTH     1

//**********************************************************************************
//
// Device commands
//
//**********************************************************************************

//****************************************************************************
//
// Constants
//
//****************************************************************************
/* The threshold register do not exist on the TLA2024, ADS1013 or ADS1113 
 * ----when using these devices reduce the count by 2
 */
#define NUM_REGISTERS                           ((uint8_t) 4)
/** Maximum register address or address of the last register in the regmap */
#define MAX_REGISTER_ADDRESS                    ((uint8_t) 3)




//**********************************************************************************
//
// Register definitions
//
//**********************************************************************************


/* Register 0x00 (CONVERSION) definition
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |   Bit 15  |   Bit 14  |   Bit 13  |   Bit 12  |   Bit 11  |   Bit 10  |   Bit 9   |   Bit 8   |   Bit 7   |   Bit 6   |   Bit 5   |   Bit 4   |   Bit 3   |   Bit 2   |   Bit 1   |   Bit 0   |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |                                                                                           CONV[15:0]                                                                                          |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 */

    /* CONVERSION register address */
    #define CONVERSION_ADDRESS                                              ((uint16_t) 0x00)

    /* CONVERSION default (reset) value */
    #define CONVERSION_DEFAULT                                              ((uint16_t) 0x0000)

    /* CONVERSION register field masks */
    #define CONVERSION_CONV_MASK                                            ((uint16_t) 0xFFFF)



/* Register 0x01 (CONFIG) definition
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |   Bit 15  |   Bit 14  |   Bit 13  |   Bit 12  |   Bit 11  |   Bit 10  |   Bit 9   |   Bit 8   |   Bit 7   |   Bit 6   |   Bit 5   |   Bit 4   |   Bit 3   |   Bit 2   |   Bit 1   |   Bit 0   |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |     OS    |              MUX[2:0]             |              PGA[2:0]             |    MODE   |              DR[2:0]              | COMP_MODE |  COMP_POL |  COMP_LAT |     COMP_QUE[1:0]     |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 */

    /* CONFIG register address */
    #define CONFIG_ADDRESS                                                  ((uint16_t) 0x01)

    /* CONFIG default (reset) value */
    #define CONFIG_DEFAULT                                                  ((uint16_t) 0x8583)

    /* CONFIG register field masks */
    #define CONFIG_OS_MASK                                                  ((uint16_t) 0x8000)
    #define CONFIG_MUX_MASK                                                 ((uint16_t) 0x7000)
    #define CONFIG_PGA_MASK                                                 ((uint16_t) 0x0E00)
    #define CONFIG_MODE_MASK                                                ((uint16_t) 0x0100)
    #define CONFIG_DR_MASK                                                  ((uint16_t) 0x00E0)
    #define CONFIG_COMP_MODE_MASK                                           ((uint16_t) 0x0010)
    #define CONFIG_COMP_POL_MASK                                            ((uint16_t) 0x0008)
    #define CONFIG_COMP_LAT_MASK                                            ((uint16_t) 0x0004)
    #define CONFIG_COMP_QUE_MASK                                            ((uint16_t) 0x0003)

    /* OS field values */
    #define CONFIG_OS_CONVERTING                                            ((uint16_t) 0x0000)
    #define CONFIG_OS_CONV_START                                            ((uint16_t) 0x8000)

    /* MUX field values */
    #define CONFIG_MUX_AIN0_AIN1                                            ((uint16_t) 0x0000)
    #define CONFIG_MUX_AIN0_AIN3                                            ((uint16_t) 0x1000)
    #define CONFIG_MUX_AIN1_AIN3                                            ((uint16_t) 0x2000)
    #define CONFIG_MUX_AIN2_AIN3                                            ((uint16_t) 0x3000)
    #define CONFIG_MUX_AIN0_GND                                             ((uint16_t) 0x4000)
    #define CONFIG_MUX_AIN1_GND                                             ((uint16_t) 0x5000)
    #define CONFIG_MUX_AIN2_GND                                             ((uint16_t) 0x6000)
    #define CONFIG_MUX_AIN3_GND                                             ((uint16_t) 0x7000)

    /* PGA field values */
    #define CONFIG_PGA_6p144V                                               ((uint16_t) 0x0000)
    #define CONFIG_PGA_4p096V                                               ((uint16_t) 0x0200)
    #define CONFIG_PGA_2p048V                                               ((uint16_t) 0x0400)
    #define CONFIG_PGA_1p024V                                               ((uint16_t) 0x0600)
    #define CONFIG_PGA_0p512V                                               ((uint16_t) 0x0800)
    #define CONFIG_PGA_0p256V                                               ((uint16_t) 0x0A00)
//    #define CONFIG_PGA_                                                     ((uint16_t) 0x0E00)

    /* MODE field values */
    #define CONFIG_MODE_CONT                                                ((uint16_t) 0x0000)
    #define CONFIG_MODE_SS                                                  ((uint16_t) 0x0100)

#ifndef ADS1115
    /* DR field values */
    #define CONFIG_DR_128SPS                                                ((uint16_t) 0x0000)
    #define CONFIG_DR_250SPS                                                ((uint16_t) 0x0020)
    #define CONFIG_DR_490SPS                                                ((uint16_t) 0x0040)
    #define CONFIG_DR_920SPS                                                ((uint16_t) 0x0060)
    #define CONFIG_DR_1600SPS                                               ((uint16_t) 0x0080)
    #define CONFIG_DR_2400SPS                                               ((uint16_t) 0x00A0)
    #define CONFIG_DR_3300_1SPS                                             ((uint16_t) 0x00C0)
    #define CONFIG_DR_3300_2SPS                                             ((uint16_t) 0x00E0)
#else
    /* DR field values */
    #define CONFIG_DR_8SPS                                                  ((uint16_t) 0x0000)
    #define CONFIG_DR_16SPS                                                 ((uint16_t) 0x0020)
    #define CONFIG_DR_32SPS                                                 ((uint16_t) 0x0040)
    #define CONFIG_DR_64SPS                                                 ((uint16_t) 0x0060)
    #define CONFIG_DR_128SPS                                                ((uint16_t) 0x0080)
    #define CONFIG_DR_250SPS                                                ((uint16_t) 0x00A0)
    #define CONFIG_DR_475SPS                                                ((uint16_t) 0x00C0)
    #define CONFIG_DR_860SPS                                                ((uint16_t) 0x00E0)
#endif
    /* COMP_MODE field values */
    #define CONFIG_COMP_MODE_TRAD                                           ((uint16_t) 0x0000)
    #define CONFIG_COMP_MODE_WINDOW                                         ((uint16_t) 0x0010)

    /* COMP_POL field values */
    #define CONFIG_COMP_POL_ACTIVE_LO                                       ((uint16_t) 0x0000)
    #define CONFIG_COMP_POL_ACTIVE_HI                                       ((uint16_t) 0x0008)

    /* COMP_LAT field values */
    #define CONFIG_COMP_LAT_NON_LATCH                                       ((uint16_t) 0x0000)
    #define CONFIG_COMP_LAT_LATCH                                           ((uint16_t) 0x0004)

    /* COMP_QUE field values */
    #define CONFIG_COMP_QUE_ASSERT1                                         ((uint16_t) 0x0000)
    #define CONFIG_COMP_QUE_ASSERT2                                         ((uint16_t) 0x0001)
    #define CONFIG_COMP_QUE_ASSERT4                                         ((uint16_t) 0x0002)
    #define CONFIG_COMP_QUE_DISABLE                                         ((uint16_t) 0x0003)



/* Register 0x02 (LO_THRESH) definition
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |   Bit 15  |   Bit 14  |   Bit 13  |   Bit 12  |   Bit 11  |   Bit 10  |   Bit 9   |   Bit 8   |   Bit 7   |   Bit 6   |   Bit 5   |   Bit 4   |   Bit 3   |   Bit 2   |   Bit 1   |   Bit 0   |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |                                                                                       LO_THRESHOLD[15:0]                                                                                      |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 */

    /* LO_THRESH register address */
    #define LO_THRESH_ADDRESS                                               ((uint16_t) 0x02)

    /* LO_THRESH default (reset) value */
    #define LO_THRESH_DEFAULT                                               ((uint16_t) 0x8000)

    /* LO_THRESH register field masks */
    #define LO_THRESH_LO_THRESHOLD_MASK                                     ((uint16_t) 0xFFFF)



/* Register 0x03 (HI_THRESH) definition
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |   Bit 15  |   Bit 14  |   Bit 13  |   Bit 12  |   Bit 11  |   Bit 10  |   Bit 9   |   Bit 8   |   Bit 7   |   Bit 6   |   Bit 5   |   Bit 4   |   Bit 3   |   Bit 2   |   Bit 1   |   Bit 0   |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 * |                                                                                       HI_THRESHOLD[15:0]                                                                                      |
 * |-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|
 */

    /* HI_THRESH register address */
    #define HI_THRESH_ADDRESS                                               ((uint16_t) 0x03)

    /* HI_THRESH default (reset) value */
    #define HI_THRESH_DEFAULT                                               ((uint16_t) 0x7FFF)

    /* HI_THRESH register field masks */
    #define HI_THRESH_HI_THRESHOLD_MASK                                     ((uint16_t) 0xFFFF)



#endif /* ADS1115_H_ */

/**
 * @file ads1115.c
 *
 * @brief This file contains all basic communication and device setup for the ADS1115 device family.
 * @warning This software utilizes TI Drivers
 *
 * @copyright Copyright (C) 2021 Texas Instruments Incorporated - http://www.ti.com/
 *
 *  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 Texas Instruments Incorporated nor the names of
 *    its contributors may be used to endorse or promote products derived
 *    from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
 *  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
 *  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
 *  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
 *  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 *  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
 *  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 *
 */

#include <evm/ADS1115.h>
#include <ti/devices/msp432e4/driverlib/sysctl.h>
#include <ti/drivers/I2C.h>
#include <ti/drivers/i2c/I2CMSP432E4.h>
#include "settings.h"

const char *adcRegisterNames[NUM_REGISTERS] = {"DATA", "CONFIG", "LO_THRESH", "HI_THRESH"};

//****************************************************************************
//
// Internal variables
//
//****************************************************************************

// Array used to recall device register map configurations */
static uint16_t registerMap[NUM_REGISTERS];

//****************************************************************************
//
// Function Definitions
//
//****************************************************************************
/**
 *
 * @brief restoreRegisterDefaults()
 * Updates the registerMap[] array to its default values.
 *
 * NOTES:
 * - If the MCU keeps a copy of the ADS1x15 register settings in memory,
 * then it is important to ensure that these values remain in sync with the
 * actual hardware settings. In order to help facilitate this, this function
 * should be called after powering up or resetting the device.
 *
 * - Reading back all of the registers after resetting the device can
 * accomplish the same result.
 *
 * @return none
 */
static void restoreRegisterDefaults(void)
{
    registerMap[CONFIG_ADDRESS]       = CONFIG_DEFAULT;
	/* The threshold register do not exist on the TLA2024, ADS1013 or ADS1113 */
    registerMap[LO_THRESH_ADDRESS]    = LO_THRESH_DEFAULT;
    registerMap[HI_THRESH_ADDRESS]    = HI_THRESH_DEFAULT;
}

/**
 *
 * @brief adcStartup()
 * Example start up sequence for the ADS1115.
 *
 * Before calling this function, the device must be powered and
 * the I2C/GPIO pins of the MCU must have already been configured.
 *
 * @return none
 */
void adcStartup(void)
{
    //
    // (OPTIONAL) Provide additional delay time for power supply settling
    //
    delay_ms(50);

    //
    // (REQUIRED) Initialize internal 'registerMap' array with device default settings
    //
    restoreRegisterDefaults();

    //
    // (OPTIONAL) Read back all registers and Check STATUS register (if exists) for faults
    //
    registerMap[CONFIG_ADDRESS] = readSingleRegister(CONFIG_ADDRESS);
}

/**
 *
 * @brief readSingleRegister()
 * Reads the contents of a single register at the specified address.
 *
 * @param[in] address Is the 8-bit address of the register to read.
 *
 * @return The 16-bit register read result as an unsigned value, but conversion
 * is binary 2's complement.
 */
uint16_t readSingleRegister(uint8_t address)
{
    //
    // Check that the register address is in range
    //
    assert(address <= MAX_REGISTER_ADDRESS);
    uint16_t regValue = 0;
    uint8_t regRXdata[4] = {0};
    int8_t retStatus;
    retStatus = receiveI2CData(address, regRXdata, 2);
    if(retStatus != false)
    {
        /* I2C communication error took place...Insert a handling routine here */
        return 0;
    }
    regValue =  combineBytes(regRXdata[0], regRXdata[1]);
    registerMap[address] = regValue;
    return regValue;
}
/**
 *
 * @brief readConversionRegister()
 * Reads the contents of the conversion register.
 *
 * @return the 16-bit register conversion result as an signed 32-bit value
 */
int32_t readConversionRegister(void)
{
    int32_t regValue = 0;
    uint8_t regRXdata[4] = {0};
    int8_t retStatus;
    retStatus = receiveI2CDataNoWrite(CONVERSION_ADDRESS, regRXdata, 2, false);
    if(retStatus != false)
    {
        /* I2C communication error took place...Insert a handling routine here */
        return 0;
    }
    regValue = signExtend(regRXdata);
    return regValue;
}

/**
 *
 * @brief writeSingleRegister()
 * Writes data to a single register and also read it back for internal
 * confirmation.
 *
 * @param[in] address Is the address of the register to write to.
 * @param[in] data Is the value to write.
 *
 * @return when true, data transmitted does not match data read
 */
bool writeSingleRegister(uint8_t address, uint16_t data)
{

    //
    // Check that the register address is in range
    //
    assert(address <= MAX_REGISTER_ADDRESS);
    uint8_t regData[2];

    regData[0] = data>>8;
    regData[1] = data & 0xFF;
    int8_t retStatus;
    uint16_t regValue;
    //
    // Cannot write to the conversion register
    //
    if(address == 0)
    {
        /* Insert a handling routine here */
        return 0;
    }
    retStatus = sendI2CData(address, regData, 2);
    if(retStatus != false)
    {
        /* I2C communication error took place...Insert a handling routine here */
        return 0;
    }

    retStatus = receiveI2CData(address, regData, 2);
    if(retStatus != false)
    {
        /* I2C communication error took place...Insert a handling routine here */
        return 0;
    }

    regValue = combineBytes(regData[0], regData[1]);
    if (address == CONFIG_ADDRESS)
    {
        if ((regValue & 0x7FFF) != (data & 0x7FFF)) return 1;
            registerMap[CONFIG_ADDRESS] = regValue & 0x7FFF;
    }
    else
    {
        if (regValue != data) return 1;
        registerMap[address] = regValue;
    }
    return 0;

}
/**
 *
 * @brief writeSingleRegisterNoRead()
 * Writes data to a single register with no readback
 * confirmation.
 *
 * @param[in] address Is the address of the register to write to.
 * @param[in] data Is the value to write.
 *
 * @return true on success, otherwise false
 */
bool writeSingleRegisterNoRead(uint8_t address, uint16_t data)
{

    //
    // Check that the register address is in range
    //
    assert(address <= MAX_REGISTER_ADDRESS);
    uint8_t regData[2];

    regData[0] = data>>8;
    regData[1] = data & 0xFF;
    int8_t retStatus;
    //
    // Cannot write to the conversion register
    //
    if(address == 0)
    {
        /* Insert a handling routine here */
        return 0;
    }
    retStatus = sendI2CRegPointer(address, regData, 2);
    if(retStatus != false)
    {
        /* I2C communication error took place...Insert a handling routine here */
        return 0;
    }

    registerMap[CONFIG_ADDRESS] = data & 0x7FFF;
    return 1;
}
/**
 *
 * @brief readData()
 * Reads 2 bytes of ADC data.
 *
 * @return signed 16-bit integer
 */
int16_t readData(void)
{
    uint16_t regValue;
    // Get the contents of the config register, we want to keep the configuration just start the conversion
    regValue = 1<<15 | registerMap[CONFIG_ADDRESS];
    uint8_t regData[2];
    int8_t retStatus;
    regData[0] = regValue>>8;
    regData[1] = regValue & 0xFF;
    //
    // Write to the config register and start a conversion
    //
    retStatus = sendI2CData(CONFIG_ADDRESS, regData, 2);
    if(retStatus != false)
    {
        /* I2C communication error took place...Insert a handling routine here */
        return 0;
    }
    //
    // To reduce the polling of communication delay a minimum time before checking
    //  the end of conversion based on the selected data rate
    //
    delayBeforeRead();
    //
    // If operating in single-shot mode check for EOC
    //
    if(regValue & CONFIG_MODE_MASK)
    {
        //
        // Poll for the end of conversion flag in the config register
        //
        regData[0] = 0;
        do
        {
            retStatus = receiveI2CData(CONFIG_ADDRESS, regData, 2);
            if(retStatus != false)
            {
                /* I2C communication error took place...Insert a handling routine here */
                return 0;
            }
        } while (!(regData[0] & 0x80) );

    }

    // Read conversion results
    registerMap[CONVERSION_ADDRESS] = readSingleRegister(CONVERSION_ADDRESS);
    return (int16_t) registerMap[CONVERSION_ADDRESS];
}
/**
 *
 * @brief startAdcConversion()
 * Starts the ADC conversion.
 *
 * @return  uint16_t configuration register
 *
 */
uint16_t startAdcConversion(void)
{
    int8_t retStatus;
    // Get the contents of the config register, we want to keep the configuration just start the conversion
    uint16_t regValue = registerMap[CONFIG_ADDRESS];
    regValue = CONFIG_OS_MASK | regValue;
    retStatus = writeSingleRegisterNoRead(CONFIG_ADDRESS, regValue);
    if(retStatus == false)
    {
        // Add error handling routine
        return 0;
    }
    return regValue;
}
/**
 *
 * @brief stopAdcConversion()
 * Stops the ADC conversion for device in continuous conversion mode.
 *
 * @return  uint16_t configuration register
 *
 */
uint16_t stopAdcConversion(void)
{
    int8_t retStatus;
    // Get the contents of the config register, we want to keep the configuration except for MODE
    uint16_t regValue = registerMap[CONFIG_ADDRESS];
    regValue |= CONFIG_MODE_SS;
    retStatus = writeSingleRegisterNoRead(CONFIG_ADDRESS, regValue);
    if(retStatus == false)
    {
        // Add error handling routine
        return 0;
    }
    registerMap[CONFIG_ADDRESS] = regValue;
    return regValue;
}
/**
 *
 * @brief delayBeforeRead()
 * Delays a specific amount of time before checking for EOC based on data rate.
 *
 * @return  none
 *
 */
void delayBeforeRead(void)
{
    uint16_t regValue = 0;
    // Get the contents of the config register, we want to keep the configuration just start the conversion
    regValue = 1<<15 | registerMap[CONFIG_ADDRESS];
#ifdef ADS1115
    if(regValue & CONFIG_MODE_MASK)
    {   //Conversion is single-shot mode
        switch((regValue & CONFIG_DR_MASK))
        {
            case CONFIG_DR_8SPS:
                delay_us(121399);
                break;
            case CONFIG_DR_16SPS:
                delay_us(59760);
                break;
            case CONFIG_DR_32SPS:
                delay_us(29585);
                break;
            case CONFIG_DR_64SPS:
                delay_us(14610);
                break;
            case CONFIG_DR_128SPS:
                delay_us(7173);
                break;
            case CONFIG_DR_250SPS:
                delay_us(3448);
                break;
            case CONFIG_DR_475SPS:
                delay_us(1659);
                break;
            case CONFIG_DR_860SPS:
                delay_us(758);
                break;
        }
    }
    else
    {
        // Conversion is in continuous conversion mode
        switch((regValue & CONFIG_DR_MASK))
        {
            case CONFIG_DR_8SPS:
                delay_us(120043);
                break;
            case CONFIG_DR_16SPS:
                delay_us(59115);
                break;
            case CONFIG_DR_32SPS:
                delay_us(29485);
                break;
            case CONFIG_DR_64SPS:
                delay_us(14655);
                break;
            case CONFIG_DR_128SPS:
                delay_us(7249);
                break;
            case CONFIG_DR_250SPS:
                delay_us(3631);
                break;
            case CONFIG_DR_475SPS:
                delay_us(1838);
                break;
            case CONFIG_DR_860SPS:
                delay_us(943);
                break;
        }
    }
#else
    if(regValue & CONFIG_MODE_MASK)
    {   //Conversion is single-shot mode
    switch((regValue & CONFIG_DR_MASK))
        {
            case CONFIG_DR_128SPS:
                delay_us(7448);
                break;
            case CONFIG_DR_250SPS:
                delay_us(3635);
                break;
            case CONFIG_DR_490SPS:
                delay_us(1676);
                break;
            case CONFIG_DR_920SPS:
                delay_us(722);
                break;
            case CONFIG_DR_1600SPS:
                delay_us(260);
                break;
            case CONFIG_DR_2400SPS:
                delay_us(52);
                break;
            case CONFIG_DR_3300_1SPS:
            case CONFIG_DR_3300_2SPS:
                break;
        }
    }
    else
    {   // Conversion is in continuous conversion mode
        switch((regValue & CONFIG_DR_MASK))
        {
            case CONFIG_DR_128SPS:
                delay_us(7249);
                break;
            case CONFIG_DR_250SPS:
                delay_us(3627);
                break;
            case CONFIG_DR_490SPS:
                delay_us(1778);
                break;
            case CONFIG_DR_920SPS:
                delay_us(882);
                break;
            case CONFIG_DR_1600SPS:
                delay_us(441);
                break;
            case CONFIG_DR_2400SPS:
                delay_us(241);
                break;
            case CONFIG_DR_3300_1SPS:
            case CONFIG_DR_3300_2SPS:
                delay_us(129);
                break;
        }
    }
#endif
}
/**
 *
 * @brief resetDevice()
 * Resets the device and reinitializes the register map array
 * maintained in firmware to default values.
 *
 * @return  Returns boolean; communication sent is true, otherwise false.
 *
 */
bool resetDevice(void)
{
    uint8_t regData[2];
    regData[0] = 0x06;
    int8_t retStatus;
    //
    // Send a general call reset
    //
    retStatus = sendI2CData(0x00,regData,1);
    if(retStatus!=0) return retStatus;

    //
    // Read the registers to verify reset condition and store
    //
    restoreRegisterDefaults();
    return retStatus;
}

/**
 *
 * @brief getRegisterValue()
 * Getter function to access registerMap array from outside of this module.
 *
 * @param[in] address Of desired register contents to return
 *
 * NOTE: The internal registerMap arrays stores the last known register value,
 * since the last read or write operation to that register. This function
 * does not communicate with the device to retrieve the current register value.
 * For the most up-to-date register data or retrieving the value of a hardware
 * controlled register, it is recommend to use readSingleRegister() to read the
 * current register value.
 *
 * @return unsigned 16-bit register value.
 */
uint16_t getRegisterValue(uint8_t address)
{
    assert(address <= MAX_REGISTER_ADDRESS);
    return registerMap[address];
}

//****************************************************************************
//
// Helper functions
//
//****************************************************************************

/**
 *
 * @brief upperByte()
 * Takes a 16-bit word and returns the most-significant byte.
 *
 * @param[in] uint16_Word Is the original 16-bit word.
 *
 * @return 8-bit most-significant byte.
 */
uint8_t upperByte(uint16_t uint16_Word)
{
    uint8_t msByte;
    msByte = (uint8_t) ((uint16_Word >> 8) & 0x00FF);

    return msByte;
}

/**
 *
 * @brief lowerByte()
 * Takes a 16-bit word and returns the least-significant byte.
 *
 * @param[in] uint16_Word Is the original 16-bit word.
 *
 * @return 8-bit least-significant byte.
 */
uint8_t lowerByte(uint16_t uint16_Word)
{
    uint8_t lsByte;
    lsByte = (uint8_t) (uint16_Word & 0x00FF);

    return lsByte;
}

/**
 *
 * @brief combineBytes()
 * Takes two 8-bit words and returns a concatenated 16-bit word.
 *
 * @param[in] upperByte Is the 8-bit value that will become the MSB of the 16-bit word.
 * @param[in] lowerByte Is the 8-bit value that will become the LSB of the 16-bit word.
 *
 * @return concatenated unsigned 16-bit word.
 */
uint16_t combineBytes(uint8_t upperByte, uint8_t lowerByte)
{
    uint16_t combinedValue;
    combinedValue = ((uint16_t) upperByte << 8) | ((uint16_t) lowerByte);

    return combinedValue;
}

/**
 *
 * @brief combineDataBytes()
 * Combines ADC data bytes into a single signed 32-bit word.
 *
 * @param[in] dataBytes Is a pointer to uint8_t[] where the first element is the MSB.
 *
 * @return Returns the signed-extend 32-bit result.
 */
int32_t signExtend(const uint8_t dataBytes[])
{
    int32_t upperByte   = ((int32_t) dataBytes[0] << 24);
    int32_t lowerByte   = ((int32_t) dataBytes[1] << 16);

    return (((int32_t) (upperByte | lowerByte)) >> 16);                 // Right-shift of signed data maintains signed bit

}

特此记录

anlog

2021年11月12日

版权声明:本文为博主原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。
本文链接:https://blog.csdn.net/anlog/article/details/121280099

智能推荐

两万字《Java完全自学手册》15张导图,送给所有的零基础小白(建议收藏)_java学习路线-程序员宅基地

文章浏览阅读4.9w次,点赞559次,收藏2.4k次。价值一万_java学习路线

SONY VISCA协议及其简单认识_visca协议和rs232的区别-程序员宅基地

文章浏览阅读1.2w次,点赞4次,收藏24次。visca是索尼公司搞出来的,用来控制相机的协议,一般通过rs232来通信(看了些资料,也有用rs485的)。一、命令格式命令通信的基本单元称为包(Packet)。一个包的长度为3到16字节,由头部、消息体和结束符三部分组成。命令包的第一个字节称为命令头(Header)。高半字节由1 (最高位,固定为1)和发送方(控制者)地址(地址一般为0)组成,低半字节由0和设备(相机)地址(或称“编号”)组成..._visca协议和rs232的区别

.net引用DLL出错_.net 发布分程序值 使用dll方法,报错-程序员宅基地

文章浏览阅读747次。最近把WIN7 32位换成64位,重新运行以前编译的程序时报错:“System.Runtime.InteropServices.SEHException”类型的未知错误检查后发现程序是在调用DLL一个函数时报错不得其解,执行另一函数时又报了“Error Loading MIDAS.DLL”,感觉有戏于是下了64位的MIDAS.DLL,放在C:\Windows\SysWOW6_.net 发布分程序值 使用dll方法,报错

DevExpress关于正版和非正版的运行以及发布的问题_devexpress23.2激活-程序员宅基地

文章浏览阅读283次。DevExpress关于正版和非正版的运行以及发布的问题。_devexpress23.2激活

Sql server 使用DBCC Shrinkfile 收缩日志文件-程序员宅基地

文章浏览阅读795次。Sql server 使用DBCC Shrinkfile 收缩日志文件_dbcc shrinkfile 收缩日志

生产计划管理软件有哪些?哪个好_生产计划执行管理有什么目的和意义-程序员宅基地

文章浏览阅读3.6k次。生产计划管理软件有哪些?哪个好?生产计划管理,一般是指企业对生产活动的计划、组织和控制工作。生产计划管理软件可提高生产效率、提升品质、降低成本等。对企业管理意义深远。​生产计划管理软件介绍:MES制造执行系统​MES系统是一套面向制造企业车间执行层的生产信息化管理系统。是生产工业常见的生产管理软件,他可以为企业提供包括制造数据管理、计划生产调度管理、库存管理以及质量管理,同时还有人力资源管理..._生产计划执行管理有什么目的和意义

随便推点

分布式复制块设备DRBD_分布式块设备-程序员宅基地

文章浏览阅读192次。DRBD(Distributed Replicated Block Device,分布式复制块设备)是一个用软件实现的、无共享的、服务器之间镜像块设备内容的存储复制解决方案。DRBD是镜像块设备,是按数据位镜像成一样的数据块。个人理解为分布式RAID(磁盘阵列)解决方案。..._分布式块设备

VS 2019 创建QT窗口、按钮、文本框、输入框、信号和槽_vs窗体设计中添加文字框-程序员宅基地

文章浏览阅读2.9k次,点赞3次,收藏20次。VS 2019 创建QT窗口、按钮、文本框、输入框、信号和槽_vs窗体设计中添加文字框

浅谈nacos脑裂-程序员宅基地

文章浏览阅读1.4k次。nacos 默认采集临时节点ephemeral,满足CAP中 AP原则,各节点是pear to pear 模式,相互直接无感知,因此对于一个集群来说,只要leader存活,即使其他所有follower全部down了,也能正常对外提供服务,基于此,nacos是可能产生脑裂的。follower无法与leader通信,因此会触发新的选举,投票满足过半数原则,因此能正常选举新的leader,且能正常对外提供服务;此时因为leader是状态正常,且与应用之间通信是正常的,因此仍能正常对外提供服务;_nacos脑裂

使用LL库开发STM32:UART进阶使用(DMA循环接收 + UART空闲中断)_stm32 ll uart-程序员宅基地

文章浏览阅读5.1k次,点赞10次,收藏20次。文章目录目的发送处理问题与解决方法个人常用处理方式数据接收与解析总结目的发送处理问题与解决方法个人常用处理方式数据接收与解析总结_stm32 ll uart

Android UI线程和非UI线程_android在ui线程-程序员宅基地

文章浏览阅读3.7k次,点赞2次,收藏9次。UI线程及Android的单线程模型原则  当应用启动,系统会创建一个主线程(main thread)。  这个主线程负责向UI组件分发事件(包括绘制事件),也是在这个主线程里,你的应用和Android的UI组件(components from the Android UI toolkit (components from the android.widget andandroid.vie_android在ui线程

C++:opencv 人脸检测_c++ opencv十字检测-程序员宅基地

文章浏览阅读2.1k次,点赞3次,收藏19次。C++:opencv 人脸检测问题描述:要求输入一张图片;输出圈出人脸的图片;vs2015; opencv3.4.6;效果输入:输出:代码实现:#include "opencv2/objdetect.hpp"#include "opencv2/highgui.hpp"#include "opencv2/imgproc.hpp"#include <iostrea..._c++ opencv十字检测

推荐文章

热门文章

相关标签