no-OS
|
Implementation of AD7768-1 Driver. More...
#include "stdio.h"
#include "stdlib.h"
#include "stdbool.h"
#include <string.h>
#include "ad77681.h"
#include "no_os_error.h"
#include "no_os_delay.h"
#include "no_os_alloc.h"
Functions | |
uint8_t | ad77681_compute_crc8 (uint8_t *data, uint8_t data_size, uint8_t init_val) |
uint8_t | ad77681_compute_xor (uint8_t *data, uint8_t data_size, uint8_t init_val) |
int32_t | ad77681_spi_reg_read (struct ad77681_dev *dev, uint8_t reg_addr, uint8_t *reg_data) |
int32_t | ad77681_spi_reg_write (struct ad77681_dev *dev, uint8_t reg_addr, uint8_t reg_data) |
int32_t | ad77681_spi_read_mask (struct ad77681_dev *dev, uint8_t reg_addr, uint8_t mask, uint8_t *data) |
int32_t | ad77681_spi_write_mask (struct ad77681_dev *dev, uint8_t reg_addr, uint8_t mask, uint8_t data) |
uint8_t | ad77681_get_rx_buf_len (struct ad77681_dev *dev) |
uint8_t | ad77681_get_frame_byte (struct ad77681_dev *dev) |
int32_t | ad77681_spi_read_adc_data (struct ad77681_dev *dev, uint8_t *adc_data, enum ad77681_data_read_mode mode) |
int32_t | ad77681_CRC_status_handling (struct ad77681_dev *dev, uint16_t *data_buffer) |
int32_t | ad77681_data_to_voltage (struct ad77681_dev *dev, uint32_t *raw_code, double *voltage) |
int32_t | ad77681_update_sample_rate (struct ad77681_dev *dev) |
int32_t | ad77681_SINC3_ODR (struct ad77681_dev *dev, uint16_t *sinc3_dec_reg, float sinc3_odr) |
int32_t | ad77681_set_power_mode (struct ad77681_dev *dev, enum ad77681_power_mode mode) |
int32_t | ad77681_set_mclk_div (struct ad77681_dev *dev, enum ad77681_mclk_div clk_div) |
int32_t | ad77681_set_VCM_output (struct ad77681_dev *dev, enum ad77681_VCM_out VCM_out) |
int32_t | ad77681_set_AINn_buffer (struct ad77681_dev *dev, enum ad77681_AINn_precharge AINn) |
int32_t | ad77681_set_AINp_buffer (struct ad77681_dev *dev, enum ad77681_AINp_precharge AINp) |
int32_t | ad77681_set_REFn_buffer (struct ad77681_dev *dev, enum ad77681_REFn_buffer REFn) |
int32_t | ad77681_set_REFp_buffer (struct ad77681_dev *dev, enum ad77681_REFp_buffer REFp) |
int32_t | ad77681_set_filter_type (struct ad77681_dev *dev, enum ad77681_sinc5_fir_decimate decimate, enum ad77681_filter_type filter, uint16_t sinc3_osr) |
int32_t | ad77681_set_50HZ_rejection (struct ad77681_dev *dev, uint8_t enable) |
int32_t | ad77681_set_continuos_read (struct ad77681_dev *dev, enum ad77681_continuous_read continuous_enable) |
int32_t | ad77681_power_down (struct ad77681_dev *dev, enum ad77681_sleep_wake sleep_wake) |
int32_t | ad77681_set_conv_mode (struct ad77681_dev *dev, enum ad77681_conv_mode conv_mode, enum ad77681_conv_diag_mux diag_mux_sel, bool conv_diag_sel) |
int32_t | ad77681_set_convlen (struct ad77681_dev *dev, enum ad77681_conv_len conv_len) |
int32_t | ad77681_set_crc_sel (struct ad77681_dev *dev, enum ad77681_crc_sel crc_sel) |
int32_t | ad77681_set_status_bit (struct ad77681_dev *dev, bool status_bit) |
int32_t | ad77681_soft_reset (struct ad77681_dev *dev) |
int32_t | ad77681_initiate_sync (struct ad77681_dev *dev) |
int32_t | ad77681_apply_offset (struct ad77681_dev *dev, uint32_t value) |
int32_t | ad77681_apply_gain (struct ad77681_dev *dev, uint32_t value) |
int32_t | ad77681_programmable_filter (struct ad77681_dev *dev, const float *coeffs, uint8_t num_coeffs) |
int32_t | ad77681_gpio_read (struct ad77681_dev *dev, uint8_t *value, enum ad77681_gpios gpio_number) |
int32_t | ad77681_gpio_write (struct ad77681_dev *dev, uint8_t value, enum ad77681_gpios gpio_number) |
int32_t | ad77681_gpio_inout (struct ad77681_dev *dev, uint8_t direction, enum ad77681_gpios gpio_number) |
int32_t | ad77681_global_gpio (struct ad77681_dev *dev, enum ad77681_gobal_gpio_enable gpio_enable) |
int32_t | ad77681_scratchpad (struct ad77681_dev *dev, uint8_t *sequence) |
int32_t | ad77681_gpio_open_drain (struct ad77681_dev *dev, enum ad77681_gpios gpio_number, enum ad77681_gpio_output_type output_type) |
int32_t | ad77681_clear_error_flags (struct ad77681_dev *dev) |
int32_t | ad77681_error_flags_enabe (struct ad77681_dev *dev) |
int32_t | ad77681_status (struct ad77681_dev *dev, struct ad77681_status_registers *status) |
int32_t | ad77681_setup (struct ad77681_dev **device, struct ad77681_init_param init_param, struct ad77681_status_registers **status) |
Implementation of AD7768-1 Driver.
Copyright 2017(c) Analog Devices, Inc.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES, INC. “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 ANALOG DEVICES, INC. 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.
int32_t ad77681_apply_gain | ( | struct ad77681_dev * | dev, |
uint32_t | value | ||
) |
Write to gain registers
dev | - The device structure. |
value | - The desired value of the whole 24-bit gain register |
int32_t ad77681_apply_offset | ( | struct ad77681_dev * | dev, |
uint32_t | value | ||
) |
Write to offset registers
dev | The device structure. |
value | The desired value of the whole 24-bit offset register |
int32_t ad77681_clear_error_flags | ( | struct ad77681_dev * | dev | ) |
Clear all error flags at once
dev | - The device structure. |
uint8_t ad77681_compute_crc8 | ( | uint8_t * | data, |
uint8_t | data_size, | ||
uint8_t | init_val | ||
) |
Compute CRC8 checksum.
data | - The data buffer. |
data_size | - The size of the data buffer. |
init_val | - CRC initial value. |
uint8_t ad77681_compute_xor | ( | uint8_t * | data, |
uint8_t | data_size, | ||
uint8_t | init_val | ||
) |
Compute XOR checksum.
data | - The data buffer. |
data_size | - The size of the data buffer. |
init_val | - CRC initial value. |
int32_t ad77681_CRC_status_handling | ( | struct ad77681_dev * | dev, |
uint16_t * | data_buffer | ||
) |
CRC and status bit handling after each readout form the ADC
dev | - The device structure. |
*data_buffer | - 16-bit buffer readed from the ADC containing the CRC, data and the stattus bit. |
int32_t ad77681_data_to_voltage | ( | struct ad77681_dev * | dev, |
uint32_t * | raw_code, | ||
double * | voltage | ||
) |
Conversion from measured data to voltage
dev | - The device structure. |
raw_code | - ADC raw code measurements |
voltage | - Converted ADC code to voltage |
int32_t ad77681_error_flags_enabe | ( | struct ad77681_dev * | dev | ) |
Enabling error flags. All error flags enabled by default
dev | - The device structure. |
uint8_t ad77681_get_frame_byte | ( | struct ad77681_dev * | dev | ) |
Helper function to get the number of SPI 16bit frames for INTERRUPT ADC DATA READ
dev | - The device structure. |
uint8_t ad77681_get_rx_buf_len | ( | struct ad77681_dev * | dev | ) |
Helper function to get the number of rx bytes
dev | - The device structure. |
int32_t ad77681_global_gpio | ( | struct ad77681_dev * | dev, |
enum ad77681_gobal_gpio_enable | gpio_enable | ||
) |
Enable global GPIO bit. This bit must be set high to change GPIO settings.
dev | - The device structure. |
gpio_enable | - Enable or diable the global GPIO pin Accepted values: AD77681_GLOBAL_GPIO_ENABLE AD77681_GLOBAL_GPIO_DISABLE |
int32_t ad77681_gpio_inout | ( | struct ad77681_dev * | dev, |
uint8_t | direction, | ||
enum ad77681_gpios | gpio_number | ||
) |
Set AD7768-1s GPIO as input or output.
dev | - The device structure. |
direction | - Direction of the GPIO Accepted values: NO_OS_GPIO_IN NO_OS_GPIO_OUT 4-bit value for all gpios |
gpio_number | - Number of GPIO, which will be affected Accepted values: AD77681_GPIO0 AD77681_GPIO1 AD77681_GPIO2 AD77681_GPIO3 AD77681_ALL_GPIOS |
int32_t ad77681_gpio_open_drain | ( | struct ad77681_dev * | dev, |
enum ad77681_gpios | gpio_number, | ||
enum ad77681_gpio_output_type | output_type | ||
) |
Set AD7768-1s GPIO output type between strong driver and open drain. GPIO3 can not be accessed!
dev | - The device structure. |
gpio_number | - AD7768-1s GPIO to be affected (Only GPIO0, GPIO1 and GPIO2) Accepted values: AD77681_GPIO0 AD77681_GPIO1 AD77681_GPIO2 AD77681_ALL_GPIOS |
output_type | - Output type of the GPIO Accepted values: AD77681_GPIO_STRONG_DRIVER AD77681_GPIO_OPEN_DRAIN |
int32_t ad77681_gpio_read | ( | struct ad77681_dev * | dev, |
uint8_t * | value, | ||
enum ad77681_gpios | gpio_number | ||
) |
Read value from GPIOs present in AD7768-1 separately, or all GPIOS at once.
dev | - The device structure. |
value | - Readed value. |
gpio_number | - Number of GPIO, the value will be written into Accepted values: AD77681_GPIO0 AD77681_GPIO1 AD77681_GPIO2 AD77681_GPIO3 AD77681_ALL_GPIOS |
int32_t ad77681_gpio_write | ( | struct ad77681_dev * | dev, |
uint8_t | value, | ||
enum ad77681_gpios | gpio_number | ||
) |
Write value to GPIOs present in AD7768-1 separately, or all GPIOS at once.
dev | - The device structure. |
value | - Value to be written into GPIO Accepted values: NO_OS_GPIO_HIGH NO_OS_GPIO_LOW 4-bit value for all gpios |
gpio_number | - Number of GPIO, the value will be written into Accepted values: AD77681_GPIO0 AD77681_GPIO1 AD77681_GPIO2 AD77681_GPIO3 AD77681_ALL_GPIOS |
int32_t ad77681_initiate_sync | ( | struct ad77681_dev * | dev | ) |
Initiate a SYNC_OUT pulse over spi
dev | - The device structure. |
int32_t ad77681_power_down | ( | struct ad77681_dev * | dev, |
enum ad77681_sleep_wake | sleep_wake | ||
) |
Power down / power up the device
dev | - The device structure. |
sleep_wake | - Power down, or power up the ADC Accepted values: AD77681_SLEEP AD77681_WAKE |
int32_t ad77681_programmable_filter | ( | struct ad77681_dev * | dev, |
const float * | coeffs, | ||
uint8_t | num_coeffs | ||
) |
Upload sequence for Programmamble FIR filter
dev | - The device structure. |
coeffs | - Pointer to the desired filter coefficients array to be written |
num_coeffs | - Count of active filter coeffs |
int32_t ad77681_scratchpad | ( | struct ad77681_dev * | dev, |
uint8_t * | sequence | ||
) |
Read and write from ADC scratchpad register to check SPI Communication in the very beginning, during inicialization.
dev | - The device structure. |
sequence | - The sequence which will be written into scratchpad and the readed sequence will be returned |
int32_t ad77681_set_50HZ_rejection | ( | struct ad77681_dev * | dev, |
uint8_t | enable | ||
) |
Enable 50/60 Hz rejection
dev | - The device structure. |
enable | - The positive reference buffer selector Accepted values: true false |
int32_t ad77681_set_AINn_buffer | ( | struct ad77681_dev * | dev, |
enum ad77681_AINn_precharge | AINn | ||
) |
Set the AIN- precharge buffer.
dev | - The device structure. |
AINn | - The negative analog input precharge buffer selector Accepted values: AD77681_AINn_ENABLED AD77681_AINn_DISABLED |
int32_t ad77681_set_AINp_buffer | ( | struct ad77681_dev * | dev, |
enum ad77681_AINp_precharge | AINp | ||
) |
Set the AIN+ precharge buffer.
dev | - The device structure. |
AINp | - The positive analog input precharge buffer selector Accepted values: AD77681_AINp_ENABLED AD77681_AINp_DISABLED |
int32_t ad77681_set_continuos_read | ( | struct ad77681_dev * | dev, |
enum ad77681_continuous_read | continuous_enable | ||
) |
Set the REF- reference buffer
dev | - The device structure. |
continuous_enable | - Continous read enable Accepted values: AD77681_CONTINUOUS_READ_ENABLE AD77681_CONTINUOUS_READ_DISABLE |
int32_t ad77681_set_conv_mode | ( | struct ad77681_dev * | dev, |
enum ad77681_conv_mode | conv_mode, | ||
enum ad77681_conv_diag_mux | diag_mux_sel, | ||
bool | conv_diag_sel | ||
) |
Conversion mode and source select
dev | - The device structure. |
conv_mode | - Sets the conversion mode of the ADC Accepted values: AD77681_CONV_CONTINUOUS AD77681_CONV_ONE_SHOT AD77681_CONV_SINGLE AD77681_CONV_PERIODIC |
diag_mux_sel | - Selects which signal to route through diagnostic mux Accepted values: AD77681_TEMP_SENSOR AD77681_AIN_SHORT AD77681_POSITIVE_FS AD77681_NEGATIVE_FS |
conv_diag_sel | - Select the input for conversion as AIN or diagnostic mux Accepted values: true false |
int32_t ad77681_set_convlen | ( | struct ad77681_dev * | dev, |
enum ad77681_conv_len | conv_len | ||
) |
Set the Conversion Result Output Length.
dev | - The device structure. |
conv_len | - The MCLK divider. Accepted values: AD77681_CONV_24BIT AD77681_CONV_16BIT |
int32_t ad77681_set_crc_sel | ( | struct ad77681_dev * | dev, |
enum ad77681_crc_sel | crc_sel | ||
) |
Activates CRC on all SPI transactions and Selects CRC method as XOR or 8-bit polynomial
dev | - The device structure. |
crc_sel | - The CRC type. Accepted values: AD77681_CRC AD77681_XOR AD77681_NO_CRC |
int32_t ad77681_set_filter_type | ( | struct ad77681_dev * | dev, |
enum ad77681_sinc5_fir_decimate | decimate, | ||
enum ad77681_filter_type | filter, | ||
uint16_t | sinc3_osr | ||
) |
Set filter type and decimation ratio
dev | - The device structure. |
decimate | - Decimation ratio of filter Accepted values: AD77681_SINC5_FIR_DECx32 AD77681_SINC5_FIR_DECx64 AD77681_SINC5_FIR_DECx128 AD77681_SINC5_FIR_DECx256 AD77681_SINC5_FIR_DECx512 AD77681_SINC5_FIR_DECx1024 |
filter | - Select filter type Accepted values: AD77681_SINC5 AD77681_SINC5_DECx8 AD77681_SINC5_DECx16 AD77681_SINC3 AD77681_FIR |
sinc3_osr | - Select decimation ratio for SINC3 filter separately as integer from 0 to 8192. See the AD7768-1 datasheet for more info |
int32_t ad77681_set_mclk_div | ( | struct ad77681_dev * | dev, |
enum ad77681_mclk_div | clk_div | ||
) |
Set the MCLK divider.
dev | - The device structure. |
clk_div | - The MCLK divider. Accepted values: AD77681_MCLK_DIV_16 AD77681_MCLK_DIV_8 AD77681_MCLK_DIV_4 AD77681_MCLK_DIV_2 |
int32_t ad77681_set_power_mode | ( | struct ad77681_dev * | dev, |
enum ad77681_power_mode | mode | ||
) |
Set the power consumption mode of the ADC core.
dev | - The device structure. |
mode | - The power mode. Accepted values: AD77681_ECO AD77681_MEDIAN AD77681_FAST |
int32_t ad77681_set_REFn_buffer | ( | struct ad77681_dev * | dev, |
enum ad77681_REFn_buffer | REFn | ||
) |
Set the REF- reference buffer
dev | - The device structure. |
REFn | - The negative reference buffer selector Accepted values: AD77681_BUFn_DISABLED AD77681_BUFn_ENABLED AD77681_BUFn_FULL_BUFFER_ON |
int32_t ad77681_set_REFp_buffer | ( | struct ad77681_dev * | dev, |
enum ad77681_REFp_buffer | REFp | ||
) |
Set the REF+ reference buffer
dev | - The device structure. |
REFp | - The positive reference buffer selector Accepted values: AD77681_BUFp_DISABLED AD77681_BUFp_ENABLED AD77681_BUFp_FULL_BUFFER_ON |
int32_t ad77681_set_status_bit | ( | struct ad77681_dev * | dev, |
bool | status_bit | ||
) |
Enables Status bits output
dev | - The device structure. |
status_bit | - enable or disable status bit Accepted values: true false |
int32_t ad77681_set_VCM_output | ( | struct ad77681_dev * | dev, |
enum ad77681_VCM_out | VCM_out | ||
) |
Set the VCM output.
dev | - The device structure. |
VCM_out | - The VCM output voltage. Accepted values: AD77681_VCM_HALF_VCC AD77681_VCM_2_5V AD77681_VCM_2_05V AD77681_VCM_1_9V AD77681_VCM_1_65V AD77681_VCM_1_1V AD77681_VCM_0_9V AD77681_VCM_OFF |
int32_t ad77681_setup | ( | struct ad77681_dev ** | device, |
struct ad77681_init_param | init_param, | ||
struct ad77681_status_registers ** | status | ||
) |
Initialize the device.
device | - The device structure. |
init_param | - The structure that contains the device initial parameters. |
status | - The structure that will contains the ADC status |
int32_t ad77681_SINC3_ODR | ( | struct ad77681_dev * | dev, |
uint16_t * | sinc3_dec_reg, | ||
float | sinc3_odr | ||
) |
Get SINC3 filter oversampling ratio register value based on user's inserted output data rate ODR
dev | - The device structure. |
sinc3_dec_reg | - Returned closest value of SINC3 register |
sinc3_odr | - Desired output data rage |
int32_t ad77681_soft_reset | ( | struct ad77681_dev * | dev | ) |
Device reset over SPI.
dev | - The device structure. |
int32_t ad77681_spi_read_adc_data | ( | struct ad77681_dev * | dev, |
uint8_t * | adc_data, | ||
enum ad77681_data_read_mode | mode | ||
) |
Read conversion result from device.
dev | - The device structure. |
adc_data | - The conversion result data |
mode | - Data read mode Accepted values: AD77681_REGISTER_DATA_READ AD77681_CONTINUOUS_DATA_READ |
int32_t ad77681_spi_read_mask | ( | struct ad77681_dev * | dev, |
uint8_t | reg_addr, | ||
uint8_t | mask, | ||
uint8_t * | data | ||
) |
SPI read from device using a mask.
dev | - The device structure. |
reg_addr | - The register address. |
mask | - The mask. |
data | - The register data. |
int32_t ad77681_spi_reg_read | ( | struct ad77681_dev * | dev, |
uint8_t | reg_addr, | ||
uint8_t * | reg_data | ||
) |
Read from device.
dev | - The device structure. |
reg_addr | - The register address. |
reg_data | - The register data. |
int32_t ad77681_spi_reg_write | ( | struct ad77681_dev * | dev, |
uint8_t | reg_addr, | ||
uint8_t | reg_data | ||
) |
Write to device.
dev | - The device structure. |
reg_addr | - The register address. |
reg_data | - The register data. |
int32_t ad77681_spi_write_mask | ( | struct ad77681_dev * | dev, |
uint8_t | reg_addr, | ||
uint8_t | mask, | ||
uint8_t | data | ||
) |
SPI write to device using a mask.
dev | - The device structure. |
reg_addr | - The register address. |
mask | - The mask. |
data | - The register data. |
int32_t ad77681_status | ( | struct ad77681_dev * | dev, |
struct ad77681_status_registers * | status | ||
) |
Read from all ADC status registers
dev | - The device structure. |
status | - Structure with all satuts bits |
int32_t ad77681_update_sample_rate | ( | struct ad77681_dev * | dev | ) |
Update ADCs sample rate depending on MCLK, MCLK_DIV and filter settings
dev | - The device structure. |