diff --git a/doc/sphinx/source/drivers/dac/max22007.rst b/doc/sphinx/source/drivers/dac/max22007.rst new file mode 100644 index 00000000000..491dcda0a13 --- /dev/null +++ b/doc/sphinx/source/drivers/dac/max22007.rst @@ -0,0 +1 @@ +.. include:: ../../../../../drivers/dac/max22007/README.rst \ No newline at end of file diff --git a/doc/sphinx/source/projects/dac/max22007.rst b/doc/sphinx/source/projects/dac/max22007.rst new file mode 100644 index 00000000000..0b33c6120b0 --- /dev/null +++ b/doc/sphinx/source/projects/dac/max22007.rst @@ -0,0 +1 @@ +.. include:: ../../../../../projects/max22007/README.rst \ No newline at end of file diff --git a/drivers/dac/max22007/README.rst b/drivers/dac/max22007/README.rst new file mode 100644 index 00000000000..4a5014e9ec2 --- /dev/null +++ b/drivers/dac/max22007/README.rst @@ -0,0 +1,138 @@ +MAX22007 no-OS driver +===================== + +.. no-os-doxygen:: + +Supported Devices +----------------- + +`MAX22007 `_ + +Overview +-------- + +The MAX22007 is a software-configurable four-channel +analog output device that drives a voltage or current output +on each channel. Each output channel of the MAX22007 features a 12-bit +DAC with fast settling time using a shared internal voltage +reference. The MAX22007 communicates with a microcontroller using an +SPI interface at clock rates up to 30MHz with an optional eight-bit CRC for improved data integrity. + + +Applications +------------ + +* Building Automation Analog Outputs +* Configurable Analog Output Cards +* Factory Automation Analog Outputs +* Process Automation +* Programmable Logic Controllers + +MAX22007 Device Configuration +----------------------------- + +Driver Initialization +--------------------- + +In order to be able to use the device, SPI communication needs to be established +between the part and a microcontroller. This is done through the +:func:`max22007_init` function. The function requires a structure of type +:c:struct:`max22007_dev` that contains the SPI configuration information and +the chip select GPIO information. The function returns 0 in case of success +or a negative error code otherwise. + +Channel Mode Configuration +-------------------------- + +The MAX22007 has four channels that can be configured to operate in +different modes. The configuration is done through the +:func:`max22007_set_channel_mode` function. The 2 possible channel modes are: +* Voltage Output Mode +* Current Output Mode + +Channel Power Mode Configuration +-------------------------------- + +The MAX22007 has four channels that can be configured to operate in +different power modes. The configuration is done through the +:func:`max22007_set_channel_power` function. The 2 possible channel power +modes are: +* Power off Mode +* Power on Mode + +DAC Channel Latch Mode Configuration +------------------------------------ + +The MAX22007 has four channels that can be configured to operate in +different latch modes. The configuration is done through the +:func:`max22007_set_latch_mode` function. The 2 possible channel +latch modes are: +* Transparent Mode +* Latched Mode (This mode enables the DAC channels to be updated via an LDAC update (register write/GPIO)) + +Setting the Output Value +------------------------ + +The output value of each channel can be set through the +:func:`max22007_write_channel_data` function. The function requires the channel +number and the output value to be set. The output value is a 12-bit value +that can be set between 0 and 4095. + +Configuring the SPI timeout +--------------------------- + +The SPI timeout can be configured through the +:func:`max22007_set_timeout` function. The status of the Timeout select, timeout configuration and timeout enable +is set through this function. + +After the basic example code has been programmed to the MCU, the outputs of channel 0 and 3 shall be set to 2 and 4v respectively, +as the channels have been configured to operate in voltage output mode. + +MAX22007 Driver Initialization Example +-------------------------------------- + +.. code-block:: c + + struct no_os_spi_init_param max22007_spi_init = { + .device_id = SPI_DEVICE_ID, + .max_speed_hz = 5000000, + .mode = NO_OS_SPI_MODE_0, + .chip_select = GPIO_CS_PIN, + .bit_order = NO_OS_SPI_BIT_ORDER_MSB_FIRST, + .platform_ops = &spi_platform_ops, + .extra = &max22007_spi_extra_ip + }; + + struct max22007_init_param max22007_ip = { + .comm_param = &max22007_spi_init, + .crc_en = false, + .ref_mode = INTERNAL_REF, + .timeout_config = { + .timeout_en = false, + .timeout_sel = MAX22007_TIMEOUT_100MS, + .timeout_cnfg = TIMEOUT_RESET, + }, + .channel_config = { + [0] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = TRANSPARENT_LATCH, + .channel_power = MAX22007_CH_POWER_ON, + }, + [1] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = LDAC_CONTROL, + .channel_power = MAX22007_CH_POWER_OFF, + }, + [2] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = LDAC_CONTROL, + .channel_power = MAX22007_CH_POWER_OFF, + }, + [3] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = LDAC_CONTROL, + .channel_power = MAX22007_CH_POWER_ON, + }, + } + }; + \ No newline at end of file diff --git a/drivers/dac/max22007/max22007.c b/drivers/dac/max22007/max22007.c new file mode 100644 index 00000000000..9b23ea3b80c --- /dev/null +++ b/drivers/dac/max22007/max22007.c @@ -0,0 +1,610 @@ +/***************************************************************************//** + * @file max22007.c + * @brief Source file of MAX22007 Driver. + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of 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. + * + * 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. +*******************************************************************************/ +#include "no_os_print_log.h" +#include "no_os_error.h" +#include "no_os_alloc.h" +#include "no_os_delay.h" +#include "no_os_crc8.h" +#include "no_os_spi.h" +#include "max22007.h" +#include + +#define MAX22007_CRC8_POLYNOMIAL 0x8C +NO_OS_DECLARE_CRC8_TABLE(max22007_crc8_table); + +/** + * @brief Read from a register + * @param dev - MAX22007 device descriptor. + * @param reg_addr - Register address. + * @param reg_data - Register data. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_reg_read(struct max22007_dev *dev, uint8_t reg_addr, + uint16_t *reg_data) +{ + int ret; + uint8_t crc; + uint8_t cmd_byte = no_os_field_prep(MAX22007_ADRR_MASK, + reg_addr) | no_os_field_prep(MAX22007_RW_MASK, 1); + uint8_t crc_data[3] = {cmd_byte, 0, 0}; + struct no_os_spi_msg xfer = { + .tx_buff = dev->buff, + .rx_buff = dev->buff, + .bytes_number = MAX22007_FRAME_SIZE, + .cs_change = 1, + }; + + if (!dev || !reg_data) + return -EINVAL; + + if (dev->crc_en) + xfer.bytes_number++; + + dev->buff[0] = cmd_byte; + + if (dev->crc_en) + dev->buff[3] = no_os_crc8(max22007_crc8_table, dev->buff, xfer.bytes_number, + 0x00); + + ret = no_os_spi_transfer(dev->comm_desc, &xfer, 1); + if (ret) + return ret; + + if (dev->crc_en) { + crc_data[1] = dev->buff[1]; + crc_data[2] = dev->buff[2]; + crc = no_os_crc8(max22007_crc8_table, crc_data, MAX22007_FRAME_SIZE, 0x00); + + if (crc != dev->buff[3]) { + pr_info("CRC mismatch: calculated 0x%02X, received 0x%02X\n", + crc, dev->buff[3]); + return -EINVAL; + } + } + + *reg_data = (dev->buff[1] << 8) | dev->buff[2]; + + return 0; +} + +/** + * @brief Write to a register + * @param dev - MAX22007 device descriptor. + * @param reg_addr - Register address. + * @param reg_data - Register data. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_reg_write(struct max22007_dev *dev, uint8_t reg_addr, + uint16_t reg_data) +{ + struct no_os_spi_msg xfer = { + .tx_buff = dev->buff, + .rx_buff = dev->buff, + .bytes_number = MAX22007_FRAME_SIZE, + .cs_change = 1, + }; + + if (!dev) + return -EINVAL; + + if (dev->crc_en) + xfer.bytes_number++; + + dev->buff[0] = no_os_field_prep(MAX22007_ADRR_MASK, reg_addr) | + no_os_field_prep(MAX22007_RW_MASK, 0); + + dev->buff[1] = (reg_data >> 8) & 0xFF; + dev->buff[2] = reg_data & 0xFF; + + if (dev->crc_en) { + dev->buff[3] = no_os_crc8(max22007_crc8_table, dev->buff, 3, 0x00); + } + + return no_os_spi_transfer(dev->comm_desc, &xfer, 1); +} + +/** + * @brief Register write with mask + * @param dev - MAX22007 device descriptor. + * @param reg_addr - Register address. + * @param data - Register data. + * @param mask - Register mask. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_reg_write_msk(struct max22007_dev *dev, + uint8_t reg_addr, + uint16_t data, + uint16_t mask) +{ + int ret; + uint16_t reg_data; + + if (!dev) + return -EINVAL; + + ret = max22007_reg_read(dev, reg_addr, ®_data); + if (ret) + return ret; + + reg_data &= ~mask; + reg_data |= data; + + return max22007_reg_write(dev, reg_addr, reg_data); +} + +/** + * @brief Set DAC latch mode + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number. + * @param mode - Latch mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_set_latch_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_dac_latch_mode mode) +{ + uint16_t reg_val; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1))) + return -EINVAL; + + reg_val = no_os_field_prep(LD_CTRL_CH_MASK(ch), mode); + + return max22007_reg_write_msk(dev, MAX22007_CONFIG_REG, reg_val, + LD_CTRL_CH_MASK(ch)); +} + +/** + * @brief Get DAC latch mode + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number. + * @param mode - Latch mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_get_latch_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_dac_latch_mode *mode) +{ + uint16_t reg_data; + int ret; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1)) || !mode) + return -EINVAL; + + ret = max22007_reg_read(dev, MAX22007_CONFIG_REG, ®_data); + if (ret) + return ret; + + *mode = no_os_field_get(LD_CTRL_CH_MASK(ch), reg_data); + + return 0; +} + +/** + * @brief Set reference source + * @param dev - MAX22007 device descriptor. + * @param mode - Reference mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_set_reference(struct max22007_dev *dev, + enum max22007_ref_mode mode) +{ + uint16_t reg_val; + + if (!dev) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_CONFIG_REF_SEL_MASK, mode); + + return max22007_reg_write_msk(dev, MAX22007_CONFIG_REG, reg_val, + MAX22007_CONFIG_REF_SEL_MASK); +} + +/** + * @brief Get reference source + * @param dev - MAX22007 device descriptor. + * @param mode - Reference mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_get_reference(struct max22007_dev *dev, + enum max22007_ref_mode *mode) +{ + uint16_t reg_data; + int ret; + + if (!dev || !mode) + return -EINVAL; + + ret = max22007_reg_read(dev, MAX22007_CONFIG_REG, ®_data); + if (ret) + return ret; + + *mode = no_os_field_get(MAX22007_CONFIG_REF_SEL_MASK, reg_data); + + return 0; +} + +/** + * @brief Set timeout configuration + * @param dev - MAX22007 device descriptor. + * @param timeout_en - Timeout enable/disable. + * @param timeout_sel - Timeout selection. + * @param timeout_cnfg - Timeout configuration. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_set_timeout(struct max22007_dev *dev, bool timeout_en, + enum max22007_timeout_sel timeout_sel, enum max22007_timeout_cnfg timeout_cnfg) +{ + uint16_t reg_val; + + if (!dev) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_TIMEOUT_SEL_MASK, timeout_sel) | + no_os_field_prep(MAX22007_TIMEOUT_CNFG_MASK, timeout_cnfg) | + no_os_field_prep(MAX22007_TIMEOUT_EN_MASK, timeout_en); + + return max22007_reg_write_msk(dev, MAX22007_CONFIG_REG, reg_val, + MAX22007_TIMEOUT_SEL_MASK | MAX22007_TIMEOUT_CNFG_MASK | + MAX22007_TIMEOUT_EN_MASK); +} + +/** + * @brief Get timeout configuration + * @param dev - MAX22007 device descriptor. + * @param timeout_en - Timeout Enable. + * @param timeout_sel - Timeout Selection. + * @param timeout_cnfg - Timeout Configuration. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_get_timeout(struct max22007_dev *dev, + bool *timeout_en, + enum max22007_timeout_sel *timeout_sel, + enum max22007_timeout_cnfg *timeout_cnfg) +{ + uint16_t reg_data; + int ret; + + if (!dev || !timeout_en || !timeout_sel || !timeout_cnfg) + return -EINVAL; + + ret = max22007_reg_read(dev, MAX22007_CONFIG_REG, ®_data); + if (ret) + return ret; + + *timeout_en = no_os_field_get(MAX22007_TIMEOUT_EN_MASK, reg_data); + *timeout_sel = no_os_field_get(MAX22007_TIMEOUT_SEL_MASK, reg_data); + *timeout_cnfg = no_os_field_get(MAX22007_TIMEOUT_CNFG_MASK, reg_data); + + return 0; +} + +/** + * @brief Set channel mode + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number. + * @param mode - Channel mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_set_channel_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_mode mode) +{ + uint16_t reg_val; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1))) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_CH_MODE_CH_MASK(ch), mode); + + return max22007_reg_write_msk(dev, MAX22007_CHANNEL_MODE_REG, reg_val, + MAX22007_CH_MODE_CH_MASK(ch)); +} + +/** + * @brief Get channel mode + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number. + * @param mode - Channel mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_get_channel_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_mode *mode) +{ + uint16_t reg_data; + int ret; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1)) || !mode) + return -EINVAL; + + ret = max22007_reg_read(dev, MAX22007_CHANNEL_MODE_REG, ®_data); + if (ret) + return ret; + + *mode = no_os_field_get(MAX22007_CH_MODE_CH_MASK(ch), reg_data); + + return 0; +} + +/** + * @brief Set channel power + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number. + * @param mode - Power mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_set_channel_power(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_power mode) +{ + uint16_t reg_val; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1))) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_CH_PWR_CH_MASK(ch), mode); + + return max22007_reg_write_msk(dev, MAX22007_CHANNEL_MODE_REG, reg_val, + MAX22007_CH_PWR_CH_MASK(ch)); +} + +/** + * @brief Get channel power + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number. + * @param mode - Power mode. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_get_channel_power(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_power *mode) +{ + uint16_t reg_data; + int ret; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1)) || !mode) + return -EINVAL; + + ret = max22007_reg_read(dev, MAX22007_CHANNEL_MODE_REG, ®_data); + if (ret) + return ret; + + *mode = no_os_field_get(MAX22007_CH_PWR_CH_MASK(ch), reg_data); + + return 0; +} + +/** + * @brief Configure CRC + * @param dev - MAX22007 device descriptor. + * @param crc_en - CRC enable/disable. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_configure_crc(struct max22007_dev *dev, bool crc_en) +{ + int ret; + uint16_t reg_val; + + if (!dev) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_CRC_EN_MASK, crc_en); + + ret = max22007_reg_write_msk(dev, MAX22007_CONFIG_REG, reg_val, + MAX22007_CRC_EN_MASK); + if (ret) + return ret; + + dev->crc_en = crc_en; + + return 0; +} + +/** + * @brief Write data to a DAC channel data register + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number (0-3). + * @param data - 16-bit data to write to the channel. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_write_channel_data(struct max22007_dev *dev, uint8_t ch, + uint16_t data) +{ + uint16_t reg_val; + + if (!dev || (ch > (MAX22007_NUM_CHANNELS - 1))) + return -EINVAL; + + reg_val = no_os_field_prep(DAC_CH_DATA_MASK, data); + + return max22007_reg_write_msk(dev, MAX22007_CHANNEL_DATA_REG(ch), reg_val, + DAC_CH_DATA_MASK); +} + +/** + * @brief Read data from a DAC channel data register + * @param dev - MAX22007 device descriptor. + * @param ch - Channel number (0-3). + * @param data - Pointer to store the 16-bit data read from the channel. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_read_channel_data(struct max22007_dev *dev, uint8_t ch, + uint16_t *data) +{ + if (!dev || !data || (ch > (MAX22007_NUM_CHANNELS - 1))) + return -EINVAL; + + return max22007_reg_read(dev, MAX22007_CHANNEL_DATA_REG(ch), data); +} + +/** + * @brief Write to LDAC register to update DAC output + * @param dev - MAX22007 device descriptor. + * @param ch_mask - Channel mask. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_write_ldac(struct max22007_dev *dev, uint8_t ch_mask) +{ + uint16_t reg_val; + + if (!dev || (ch_mask > 0xF)) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_LD_CTRL_MASK, ch_mask); + + return max22007_reg_write_msk(dev, MAX22007_CTRL_REG, reg_val, + MAX22007_LD_CTRL_MASK); +} + +/** + * @brief Write to Soft Reset Register + * @param dev - MAX22007 device descriptor. + * @param sw_clear - Data register reset control. + * @param sw_reset - Software reset control. + * @return 0 in case of success, negative error code otherwise. +*/ +static int max22007_soft_reset(struct max22007_dev *dev, bool sw_clear, + bool sw_reset) +{ + uint16_t reg_val = 0; + + if (!dev) + return -EINVAL; + + reg_val = no_os_field_prep(MAX22007_SW_CLR_MASK, sw_clear) | + no_os_field_prep(MAX22007_SW_RST_MASK, sw_reset); + + return max22007_reg_write(dev, MAX22007_SOFT_RESET_REG, reg_val); +} + +/** + * @brief MAX22007 descriptor initialization function. + * @param device - MAX22007 device descriptor. + * @param init_param - Initialization parameter containing data about the device + * descriptor to be initialized. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_init(struct max22007_dev **device, + struct max22007_init_param init_param) +{ + struct max22007_dev *dev; + uint16_t reg_val; + uint8_t ch; + int ret; + + dev = (struct max22007_dev *)no_os_calloc(1, sizeof(*dev)); + if (!dev) + return -ENOMEM; + + no_os_crc8_populate_lsb(max22007_crc8_table, MAX22007_CRC8_POLYNOMIAL); + + ret = no_os_spi_init(&dev->comm_desc, init_param.comm_param); + if (ret) { + goto err_dev; + } + + dev->crc_en = true; + + ret = max22007_configure_crc(dev, init_param.crc_en); + if (ret) { + goto err_spi; + } + + ret = max22007_soft_reset(dev, true, true); + if (ret) + goto err_spi; + + ret = max22007_reg_read(dev, MAX22007_REV_ID_REG, ®_val); + if (ret) { + goto err_spi; + } + + if (reg_val != MAX22007_REV_ID) { + pr_info("Invalid device ID: 0x%04X\n", reg_val); + ret = -EINVAL; + goto err_spi; + } + + /* Configure device with initialization parameters */ + ret = max22007_set_reference(dev, init_param.ref_mode); + if (ret) { + goto err_spi; + } + + for (ch = 0; ch < MAX22007_NUM_CHANNELS; ch++) { + ret = max22007_set_channel_mode(dev, ch, + init_param.channel_config[ch].channel_mode); + if (ret) { + goto err_spi; + } + + ret = max22007_set_latch_mode(dev, ch, + init_param.channel_config[ch].latch_mode); + if (ret) { + goto err_spi; + } + + ret = max22007_set_channel_power(dev, ch, + init_param.channel_config[ch].channel_power); + if (ret) { + goto err_spi; + } + } + + ret = max22007_set_timeout(dev, init_param.timeout_config.timeout_en, + init_param.timeout_config.timeout_sel, + init_param.timeout_config.timeout_cnfg); + if (ret) { + goto err_spi; + } + + *device = dev; + return 0; + +err_spi: + no_os_spi_remove(dev->comm_desc); +err_dev: + max22007_remove(dev); + return ret; +} + +/** + * @brief Deallocates all the resources used at initialization. + * @param dev - MAX22007 device descriptor. + * @return 0 in case of success, negative error code otherwise. +*/ +int max22007_remove(struct max22007_dev *dev) +{ + if (!dev) + return -EINVAL; + + no_os_free(dev); + + return 0; +} + diff --git a/drivers/dac/max22007/max22007.h b/drivers/dac/max22007/max22007.h new file mode 100644 index 00000000000..4dbdec23aee --- /dev/null +++ b/drivers/dac/max22007/max22007.h @@ -0,0 +1,206 @@ +/***************************************************************************//** + * @file max22007.h + * @brief Header file of MAX22007 Driver. + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of 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. + * + * 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. +*******************************************************************************/ +#ifndef _MAX22007_H +#define _MAX22007_H + +#include "no_os_spi.h" +#include "no_os_util.h" + +/* Register Map */ +#define MAX22007_REV_ID_REG 0x00 +#define MAX22007_STAT_AND_INTR_REG 0x01 +#define MAX22007_INR_ENABLE_REG 0x02 +#define MAX22007_CONFIG_REG 0x03 +#define MAX22007_CTRL_REG 0x04 +#define MAX22007_CHANNEL_MODE_REG 0x05 +#define MAX22007_SOFT_RESET_REG 0x06 +#define MAX22007_CHANNEL_DATA_REG(channel) (0x07 + (channel)) +#define MAX22007_GPIO_CTRL_REG 0x0B +#define MAX22007_GPIO_DATA_REG 0x0C +#define MAX22007_GPIO_EDGE_CTRL_REG 0x0D +#define MAX22007_GPIO_EDGE_DETECTION_STAT_REG 0x0E + +/* Revision Register Masks */ +#define MAX22007_REV_ID_MASK NO_OS_GENMASK(7, 0) +#define MAX22007_PART_ID_MASK NO_OS_GENMASK(15, 8) + +/* Configuration Register Masks */ +#define MAX22007_CONFIG_LD_CNFG_MASK NO_OS_GENMASK(15, 12) +#define MAX22007_CONFIG_COMP_EDGE_MASK NO_OS_GENMASK(11, 10) +#define MAX22007_CONFIG_REF_SEL_MASK NO_OS_BIT(8) +#define MAX22007_TIMEOUT_SEL_MASK NO_OS_GENMASK(7, 4) +#define MAX22007_TIMEOUT_CNFG_MASK NO_OS_BIT(3) +#define MAX22007_TIMEOUT_EN_MASK NO_OS_BIT(2) +#define MAX22007_OVERCURRENT_CTRL_MASK NO_OS_BIT(1) +#define MAX22007_CRC_EN_MASK NO_OS_BIT(0) + +/* Control Register Masks */ +#define MAX22007_LD_CTRL_MASK NO_OS_GENMASK(15, 12) +#define LD_CTRL_CH_MASK(channel) (NO_OS_BIT(12) << (channel)) + +/* Channel Mode Register Masks */ +#define MAX22007_CH_MODE_MASK NO_OS_GENMASK(15, 12) +#define MAX22007_CH_MODE_CH_MASK(channel) (NO_OS_BIT(12) << (channel)) +#define MAX22007_CH_PWR_MASK NO_OS_GENMASK(11, 8) +#define MAX22007_CH_PWR_CH_MASK(channel) (NO_OS_BIT(8) << (channel)) + +/* Soft Reset Register Masks */ +#define MAX22007_SW_CLR_MASK NO_OS_BIT(12) +#define MAX22007_SW_RST_MASK NO_OS_BIT(8) + +/* GPIO Control Register Masks */ +#define MAX22007_GPIO_CTRL_MASK NO_OS_GENMASK(15, 8) +#define MAX22007_GPIO_DIR_MASK NO_OS_GENMASK(7, 0) + +/* DAC Channel register masks */ +#define DAC_CH_DATA_MASK NO_OS_GENMASK(15, 4) + +/* GPIO Data Register Masks */ +#define MAX22007_GPO_DATA_MASK NO_OS_GENMASK(15, 8) +#define MAX22007_GPI_DATA_MASK NO_OS_GENMASK(7, 0) + +#define MAX22007_SPI_READ 0x80 +#define MAX22007_NUM_CHANNELS 4 +#define MAX22007_REV_ID 0xBB45 +#define MAX22007_ADRR_MASK NO_OS_GENMASK(7, 1) +#define MAX22007_RW_MASK NO_OS_BIT(0) +#define MAX22007_FRAME_SIZE 3 +#define MAX22007_PAYLOAD_LSB_MASK NO_OS_GENMASK(7, 0) +#define MAX22007_PAYLOAD_MSB_MASK NO_OS_GENMASK(15, 8) + +enum max22007_dac_latch_mode { + LDAC_CONTROL, + TRANSPARENT_LATCH +}; + +enum max22007_ref_mode { + INTERNAL_REF, + EXTERNAL_REF +}; + +enum max22007_timeout_sel { + MAX22007_TIMEOUT_100MS, + MAX22007_TIMEOUT_200MS, + MAX22007_TIMEOUT_300MS, + MAX22007_TIMEOUT_400MS, + MAX22007_TIMEOUT_500MS, + MAX22007_TIMEOUT_600MS, + MAX22007_TIMEOUT_700MS, + MAX22007_TIMEOUT_800MS, + MAX22007_TIMEOUT_900MS, + MAX22007_TIMEOUT_1000MS, + MAX22007_TIMEOUT_1100MS, + MAX22007_TIMEOUT_1200MS, + MAX22007_TIMEOUT_1300MS, + MAX22007_TIMEOUT_1400MS, + MAX22007_TIMEOUT_1500MS, + MAX22007_TIMEOUT_1600MS, +}; + +enum max22007_timeout_cnfg { + TIMEOUT_EVENT_ONLY, + TIMEOUT_RESET +}; + +enum max22007_channel_mode { + MAX22007_VOLTAGE_MODE, + MAX22007_CURRENT_MODE, +}; + +enum max22007_channel_power { + MAX22007_CH_POWER_OFF, + MAX22007_CH_POWER_ON, +}; + +struct max22007_spi_timeout_config { + enum max22007_timeout_sel timeout_sel; + enum max22007_timeout_cnfg timeout_cnfg; + bool timeout_en; +}; + +struct max22007_channel_config { + enum max22007_dac_latch_mode latch_mode; + enum max22007_channel_mode channel_mode; + enum max22007_channel_power channel_power; +}; + +struct max22007_init_param { + struct no_os_spi_init_param *comm_param; + struct max22007_channel_config channel_config[MAX22007_NUM_CHANNELS]; + struct max22007_spi_timeout_config timeout_config; + enum max22007_ref_mode ref_mode; + bool crc_en; +}; + +struct max22007_dev { + struct no_os_spi_desc *comm_desc; + uint8_t buff[MAX22007_FRAME_SIZE + 1]; + bool crc_en; +}; + +int max22007_reg_read(struct max22007_dev *dev, uint8_t reg_addr, + uint16_t *reg_data); +int max22007_reg_write(struct max22007_dev *dev, uint8_t reg_addr, + uint16_t reg_data); +int max22007_reg_write_msk(struct max22007_dev *dev, uint8_t reg_addr, + uint16_t data, uint16_t mask); +int max22007_set_latch_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_dac_latch_mode mode); +int max22007_get_latch_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_dac_latch_mode *mode); +int max22007_set_reference(struct max22007_dev *dev, + enum max22007_ref_mode mode); +int max22007_get_reference(struct max22007_dev *dev, + enum max22007_ref_mode *mode); +int max22007_set_timeout(struct max22007_dev *dev, bool timeout_en, + enum max22007_timeout_sel timeout_sel, enum max22007_timeout_cnfg timeout_cnfg); +int max22007_set_channel_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_mode mode); +int max22007_get_channel_mode(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_mode *mode); +int max22007_set_channel_power(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_power mode); +int max22007_get_channel_power(struct max22007_dev *dev, uint8_t ch, + enum max22007_channel_power *mode); +int max22007_configure_crc(struct max22007_dev *dev, bool crc_en); +int max22007_write_ldac(struct max22007_dev *dev, uint8_t ch_mask); +int max22007_write_channel_data(struct max22007_dev *dev, uint8_t ch, + uint16_t data); +int max22007_read_channel_data(struct max22007_dev *dev, uint8_t ch, + uint16_t *data); +int max22007_init(struct max22007_dev **device, + struct max22007_init_param init_param); +int max22007_remove(struct max22007_dev *dev); + +#endif // _MAX22007_H + diff --git a/include/no_os_crc8.h b/include/no_os_crc8.h index b2eadfdfbe8..1c83d281a47 100644 --- a/include/no_os_crc8.h +++ b/include/no_os_crc8.h @@ -42,6 +42,7 @@ static uint8_t _table[NO_OS_CRC8_TABLE_SIZE] void no_os_crc8_populate_msb(uint8_t * table, const uint8_t polynomial); +void no_os_crc8_populate_lsb(uint8_t * table, const uint8_t polynomial); uint8_t no_os_crc8(const uint8_t * table, const uint8_t *pdata, size_t nbytes, uint8_t crc); diff --git a/projects/max22007/Makefile b/projects/max22007/Makefile new file mode 100644 index 00000000000..57faeb3d1fa --- /dev/null +++ b/projects/max22007/Makefile @@ -0,0 +1,12 @@ +EXAMPLE ?= basic + +HARDWARE ?= carrier/sdp-k1.ioc + +include ../../tools/scripts/generic_variables.mk + +include ../../tools/scripts/examples.mk + +include src.mk + +include ../../tools/scripts/generic.mk + diff --git a/projects/max22007/README.rst b/projects/max22007/README.rst new file mode 100644 index 00000000000..39a37653f22 --- /dev/null +++ b/projects/max22007/README.rst @@ -0,0 +1,114 @@ +MAX22007EVKIT no-OS Example Project +=================================== + +.. no-os-doxygen:: + +.. contents:: + :depth: 3 + +Supported Evaluation Boards +--------------------------- + +* `MAX22007EVKIT `_ + +Overview +-------- + +The MAX22007EVKIT is a fully featured evaluation kit for the MAX22007. +This board operates in standalone mode or in conjunction with SDP-K1 + +Hardware Specifications +----------------------- + +The MAX22007EVKIT device has to be supplied with a 7-9V DC voltage and +a 3V3 VDRIVE voltage from the microcontroller (for the logic level +voltage of the SPI communication). + +**Pin Description** + + Please see the following table for the pin assignments for the + interface connector (SPI Test Points). + + +------------+--------+----------------------------------+ + | Pin | Name | Description | + +------------+--------+----------------------------------+ + | PMOD1 pin1 | CSB | SPI Chip-Select | + +------------+--------+----------------------------------+ + | PMOD1 pin2 | SDO | Master-Out Slave-In (MOSI) | + +------------+--------+----------------------------------+ + | PMOD1 pin3 | SDI | Master-In Slave-Out (MISO) | + +------------+--------+----------------------------------+ + | PMOD1 pin4 | SCLK | Serial Clock | + +------------+--------+----------------------------------+ + + Please ensure to open all the switches on SW1, to ensure compatibility + with an external MCU + + Please refer to the `MAX22007EVKIT Board user guide `_ for more details on jumper positions. + +No-OS Build Setup +----------------- + +`Please see: `_ + +No-OS Supported Examples +------------------------ + +The initialization data used in the examples is taken out from: +`Project Common Data Path `_ + +The macros used in Common Data are defined in platform specific files found in: +`Project Platform Configuration Path `_ + +Basic Example +^^^^^^^^^^^^^ + +This is a simple example which initializes the MAX22007 and writes to the data register of channel 0 and 3 with a value +equivalent to 2v and 4v respectively. + +In order to build the basic example make sure you have the following configuration in the Makefile +`Makefile `_ + +.. code-block:: bash + + EXAMPLE ?= basic_example + + +No-OS Supported Platforms +------------------------- + +STM32 Platform +^^^^^^^^^^^^^^ + +**Used Hardware** + +* `MAX22007EVKIT `_ +* `SDP-K1 `_ + +**Connections**: + ++---------------------+--------+----------------------------------+--------------------+ +| MAX22007EVKIT Pin | Signal | Function | SDP-K1 Pin Number | ++---------------------+--------+----------------------------------+--------------------+ +| PMOD1 pin1 | CSB | SPI interface Chip-Select | D10 | ++---------------------+--------+----------------------------------+--------------------+ +| PMOD1 pin2 | SDO | Master-Out Slave-In (MOSI) | D11 | ++---------------------+--------+----------------------------------+--------------------+ +| PMOD1 pin3 | SDI | Master-In Slave-Out (MISO) | D12 | ++---------------------+--------+----------------------------------+--------------------+ +| PMOD1 pin4 | SCLK | SPI interface Serial Clock Line | D13 | ++---------------------+--------+----------------------------------+--------------------+ +| GND | GND | Ground | GND | ++---------------------+--------+----------------------------------+--------------------+ + +**Build Command** + +.. code-block:: bash + + # to delete current build + make reset + # to build the project + make PLATFORM=stm32 HARDWARE=sdp-k1.ioc + # to flash the code + make run + diff --git a/projects/max22007/builds.json b/projects/max22007/builds.json new file mode 100644 index 00000000000..89297979d7c --- /dev/null +++ b/projects/max22007/builds.json @@ -0,0 +1,8 @@ +{ + "stm32": { + "basic_example": { + "flags" : "EXAMPLE=basic_example HARDWARE=sdp-k1.ioc" + } + } +} + diff --git a/projects/max22007/carrier/sdp-k1.ioc b/projects/max22007/carrier/sdp-k1.ioc new file mode 100644 index 00000000000..dc318148699 --- /dev/null +++ b/projects/max22007/carrier/sdp-k1.ioc @@ -0,0 +1,162 @@ +#MicroXplorer Configuration settings - do not modify +CAD.formats= +CAD.pinconfig= +CAD.provider= +File.Version=6 +GPIO.groupedBy=Group By Peripherals +KeepUserPlacement=false +Mcu.CPN=STM32F469NIH6 +Mcu.Family=STM32F4 +Mcu.IP0=NVIC +Mcu.IP1=RCC +Mcu.IP2=SPI1 +Mcu.IP3=SYS +Mcu.IP4=UART5 +Mcu.IPNb=5 +Mcu.Name=STM32F469NIHx +Mcu.Package=TFBGA216 +Mcu.Pin0=PB4 +Mcu.Pin1=PB3 +Mcu.Pin2=PC12 +Mcu.Pin3=PA15 +Mcu.Pin4=PD2 +Mcu.Pin5=PH0/OSC_IN +Mcu.Pin6=PH1/OSC_OUT +Mcu.Pin7=PA7 +Mcu.Pin8=VP_SYS_VS_Systick +Mcu.PinsNb=9 +Mcu.ThirdPartyNb=0 +Mcu.UserConstants= +Mcu.UserName=STM32F469NIHx +MxCube.Version=6.15.0 +MxDb.Version=DB.6.0.150 +NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.ForceEnableDMAVector=false +NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 +NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:false +NVIC.UART5_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:false +NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +PA15.GPIOParameters=GPIO_PuPd +PA15.GPIO_PuPd=GPIO_PULLDOWN +PA15.Locked=true +PA15.Signal=GPIO_Output +PA7.GPIOParameters=GPIO_PuPd +PA7.GPIO_PuPd=GPIO_PULLUP +PA7.Locked=true +PA7.Mode=Full_Duplex_Master +PA7.Signal=SPI1_MOSI +PB3.GPIOParameters=GPIO_PuPd +PB3.GPIO_PuPd=GPIO_PULLUP +PB3.Locked=true +PB3.Mode=Full_Duplex_Master +PB3.Signal=SPI1_SCK +PB4.GPIOParameters=GPIO_PuPd +PB4.GPIO_PuPd=GPIO_PULLUP +PB4.Locked=true +PB4.Mode=Full_Duplex_Master +PB4.Signal=SPI1_MISO +PC12.Mode=Asynchronous +PC12.Signal=UART5_TX +PD2.Mode=Asynchronous +PD2.Signal=UART5_RX +PH0/OSC_IN.Mode=HSE-External-Oscillator +PH0/OSC_IN.Signal=RCC_OSC_IN +PH1/OSC_OUT.Mode=HSE-External-Oscillator +PH1/OSC_OUT.Signal=RCC_OSC_OUT +PinOutPanel.CurrentBGAView=Top +PinOutPanel.RotationAngle=0 +ProjectManager.AskForMigrate=true +ProjectManager.BackupPrevious=false +ProjectManager.CompilerLinker=GCC +ProjectManager.CompilerOptimize=6 +ProjectManager.ComputerToolchain=false +ProjectManager.CoupleFile=false +ProjectManager.CustomerFirmwarePackage= +ProjectManager.DefaultFWLocation=true +ProjectManager.DeletePrevious=true +ProjectManager.DeviceId=STM32F469NIHx +ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.28.1 +ProjectManager.FreePins=false +ProjectManager.HalAssertFull=false +ProjectManager.HeapSize=0x200 +ProjectManager.KeepUserCode=false +ProjectManager.LastFirmware=false +ProjectManager.LibraryCopy=1 +ProjectManager.MainLocation=Core/Src +ProjectManager.NoMain=false +ProjectManager.PreviousToolchain=STM32CubeIDE +ProjectManager.ProjectBuild=false +ProjectManager.ProjectFileName=sdp-k1.ioc +ProjectManager.ProjectName=sdp-k1 +ProjectManager.ProjectStructure= +ProjectManager.RegisterCallBack=I2C,SDRAM,SPI,TIM,UART +ProjectManager.StackSize=0x400 +ProjectManager.TargetToolchain=STM32CubeIDE +ProjectManager.ToolChainLocation= +ProjectManager.UAScriptAfterPath= +ProjectManager.UAScriptBeforePath= +ProjectManager.UnderRoot=true +ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-false,2-SystemClock_Config-RCC-false-HAL-false,3-MX_UART5_Init-UART5-false-HAL-false,4-MX_SPI1_Init-SPI1-false-HAL-false +RCC.AHBFreq_Value=180000000 +RCC.APB1CLKDivider=RCC_HCLK_DIV4 +RCC.APB1Freq_Value=45000000 +RCC.APB1TimFreq_Value=90000000 +RCC.APB2CLKDivider=RCC_HCLK_DIV2 +RCC.APB2Freq_Value=90000000 +RCC.APB2TimFreq_Value=180000000 +RCC.CortexFreq_Value=180000000 +RCC.DSIFreq_Value=20000000 +RCC.DSITXEscFreq_Value=5000000 +RCC.EthernetFreq_Value=180000000 +RCC.FCLKCortexFreq_Value=180000000 +RCC.FamilyName=M +RCC.HCLKFreq_Value=180000000 +RCC.HSE_VALUE=8000000 +RCC.I2SFreq_Value=192000000 +RCC.IPParameters=AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,DSIFreq_Value,DSITXEscFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,I2SFreq_Value,LCDTFTFreq_Value,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLDSIFreq_Value,PLLDSIVCOFreq_Value,PLLI2SQCLKFreq_Value,PLLI2SRCLKFreq_Value,PLLM,PLLN,PLLQCLKFreq_Value,PLLRCLKFreq_Value,PLLRFreq_Value,PLLSAIPCLKFreq_Value,PLLSAIQCLKFreq_Value,PLLSAIRCLKFreq_Value,RTCFreq_Value,RTCHSEDivFreq_Value,SAIAFreq_Value,SAIBFreq_Value,SDIOFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,USBFreq_Value,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAIOutputFreq_Value +RCC.LCDTFTFreq_Value=96000000 +RCC.MCO2PinFreq_Value=180000000 +RCC.PLLCLKFreq_Value=180000000 +RCC.PLLDSIFreq_Value=160000000 +RCC.PLLDSIVCOFreq_Value=320000000 +RCC.PLLI2SQCLKFreq_Value=96000000 +RCC.PLLI2SRCLKFreq_Value=192000000 +RCC.PLLM=8 +RCC.PLLN=180 +RCC.PLLQCLKFreq_Value=90000000 +RCC.PLLRCLKFreq_Value=180000000 +RCC.PLLRFreq_Value=180000000 +RCC.PLLSAIPCLKFreq_Value=192000000 +RCC.PLLSAIQCLKFreq_Value=96000000 +RCC.PLLSAIRCLKFreq_Value=192000000 +RCC.RTCFreq_Value=32000 +RCC.RTCHSEDivFreq_Value=4000000 +RCC.SAIAFreq_Value=96000000 +RCC.SAIBFreq_Value=96000000 +RCC.SDIOFreq_Value=90000000 +RCC.SYSCLKFreq_VALUE=180000000 +RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK +RCC.USBFreq_Value=90000000 +RCC.VCOI2SOutputFreq_Value=384000000 +RCC.VCOInputFreq_Value=2000000 +RCC.VCOOutputFreq_Value=360000000 +RCC.VCOSAIOutputFreq_Value=384000000 +SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_2 +SPI1.CalculateBaudRate=45.0 MBits/s +SPI1.DataSize=SPI_DATASIZE_8BIT +SPI1.Direction=SPI_DIRECTION_2LINES +SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler +SPI1.Mode=SPI_MODE_MASTER +SPI1.VirtualType=VM_MASTER +UART5.BaudRate=230400 +UART5.IPParameters=VirtualMode,BaudRate +UART5.VirtualMode=Asynchronous +VP_SYS_VS_Systick.Mode=SysTick +VP_SYS_VS_Systick.Signal=SYS_VS_Systick +board=custom diff --git a/projects/max22007/src.mk b/projects/max22007/src.mk new file mode 100644 index 00000000000..85358443ce4 --- /dev/null +++ b/projects/max22007/src.mk @@ -0,0 +1,30 @@ +SRCS += $(DRIVERS)/api/no_os_gpio.c \ + $(DRIVERS)/api/no_os_spi.c \ + $(DRIVERS)/api/no_os_uart.c \ + $(DRIVERS)/api/no_os_dma.c \ + $(DRIVERS)/api/no_os_irq.c \ + $(NO-OS)/util/no_os_list.c \ + $(NO-OS)/util/no_os_util.c \ + $(NO-OS)/util/no_os_alloc.c \ + $(NO-OS)/util/no_os_lf256fifo.c \ + $(NO-OS)/util/no_os_mutex.c \ + $(NO-OS)/util/no_os_crc8.c \ + +INCS += $(INCLUDE)/no_os_delay.h \ + $(INCLUDE)/no_os_error.h \ + $(INCLUDE)/no_os_gpio.h \ + $(INCLUDE)/no_os_spi.h \ + $(INCLUDE)/no_os_print_log.h \ + $(INCLUDE)/no_os_list.h \ + $(INCLUDE)/no_os_uart.h \ + $(INCLUDE)/no_os_util.h \ + $(INCLUDE)/no_os_alloc.h \ + $(INCLUDE)/no_os_lf256fifo.h \ + $(INCLUDE)/no_os_mutex.h \ + $(INCLUDE)/no_os_dma.h \ + $(INCLUDE)/no_os_irq.h \ + $(INCLUDE)/no_os_crc8.h \ + +SRCS += $(DRIVERS)/dac/max22007/max22007.c +INCS += $(DRIVERS)/dac/max22007/max22007.h + diff --git a/projects/max22007/src/common/common_data.c b/projects/max22007/src/common/common_data.c new file mode 100644 index 00000000000..d55f03701ca --- /dev/null +++ b/projects/max22007/src/common/common_data.c @@ -0,0 +1,97 @@ +/***************************************************************************//** + * @file common_data.c + * @brief Defines common data to be used by MAX22007 example. + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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 "common_data.h" +#include "max22007.h" + +struct no_os_uart_init_param max22007_uart_ip = { + .device_id = UART_DEVICE_ID, + .irq_id = UART_IRQ_ID, + .asynchronous_rx = true, + .baud_rate = UART_BAUDRATE, + .size = NO_OS_UART_CS_8, + .parity = NO_OS_UART_PAR_NO, + .stop = NO_OS_UART_STOP_1_BIT, + .extra = &max22007_uart_extra_ip, + .platform_ops = &uart_platform_ops, +}; + +struct no_os_spi_init_param max22007_spi_init = { + .device_id = SPI_DEVICE_ID, + .max_speed_hz = 5000000, + .mode = NO_OS_SPI_MODE_0, + .chip_select = GPIO_CS_PIN, + .bit_order = NO_OS_SPI_BIT_ORDER_MSB_FIRST, + .platform_ops = &spi_platform_ops, + .extra = &max22007_spi_extra_ip +}; + +struct max22007_init_param max22007_ip = { + .comm_param = &max22007_spi_init, + .crc_en = false, + .ref_mode = INTERNAL_REF, + .timeout_config = { + .timeout_en = false, + .timeout_sel = MAX22007_TIMEOUT_100MS, + .timeout_cnfg = TIMEOUT_RESET, + }, + .channel_config = { + [0] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = TRANSPARENT_LATCH, + .channel_power = MAX22007_CH_POWER_ON, + }, + [1] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = LDAC_CONTROL, + .channel_power = MAX22007_CH_POWER_OFF, + }, + [2] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = LDAC_CONTROL, + .channel_power = MAX22007_CH_POWER_OFF, + }, + [3] = { + .channel_mode = MAX22007_VOLTAGE_MODE, + .latch_mode = LDAC_CONTROL, + .channel_power = MAX22007_CH_POWER_ON, + }, + } +}; + diff --git a/projects/max22007/src/common/common_data.h b/projects/max22007/src/common/common_data.h new file mode 100644 index 00000000000..575d0439c27 --- /dev/null +++ b/projects/max22007/src/common/common_data.h @@ -0,0 +1,49 @@ +/***************************************************************************//** + * @file max22007/src/common/common_data.h + * @brief Defines common data to be used by max22007 examples. + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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. +*******************************************************************************/ +#ifndef __COMMON_DATA_H__ +#define __COMMON_DATA_H__ + +#include "parameters.h" +#include "max22007.h" + +extern struct no_os_uart_init_param max22007_uart_ip; +extern struct max22007_init_param max22007_ip; + +#endif /* __COMMON_DATA_H__ */ + diff --git a/projects/max22007/src/examples/basic/basic_example.c b/projects/max22007/src/examples/basic/basic_example.c new file mode 100644 index 00000000000..7cf18fd3f72 --- /dev/null +++ b/projects/max22007/src/examples/basic/basic_example.c @@ -0,0 +1,88 @@ +/***************************************************************************//** + * @file basic_example.c + * @brief Basic example for MAX22007 project + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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 "no_os_print_log.h" +#include "no_os_delay.h" +#include "common_data.h" +#include "max22007.h" + +/***************************************************************************//** + * @brief Basic example main execution. + * @return ret - Result of the example execution. If working correctly, will + * execute continuously the while(1) loop and will not return. +*******************************************************************************/ +int example_main() +{ + int ret; + struct max22007_dev *dev; + struct no_os_uart_desc *uart_desc; + + ret = no_os_uart_init(&uart_desc, &max22007_uart_ip); + if (ret) + goto error; + + no_os_uart_stdio(uart_desc); + + ret = max22007_init(&dev, max22007_ip); + if (ret) + goto error; + + ret = max22007_write_channel_data(dev, 0, 0x28F); + if (ret) + goto error; + + ret = max22007_write_channel_data(dev, 3, 0x51E); + if (ret) + goto error; + + ret = max22007_write_ldac(dev, 0x09); + if (ret) + goto error; + + + while (1) { + // Main loop - DAC channels are now set to test values + no_os_mdelay(1000); + } + +error: + pr_info("Error init!\n"); + return ret; +} + diff --git a/projects/max22007/src/platform/stm32/main.c b/projects/max22007/src/platform/stm32/main.c new file mode 100644 index 00000000000..2de0a1b0397 --- /dev/null +++ b/projects/max22007/src/platform/stm32/main.c @@ -0,0 +1,56 @@ +/***************************************************************************//** + * @file main.c + * @brief Main file for STM32 platform of MAX22007 project. + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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 "parameters.h" +#include "common_data.h" +#include "no_os_error.h" + +extern int example_main(); + +/***************************************************************************//** + * @brief Main function execution for STM32 platform. + * + * @return ret - Result of the enabled examples execution. +*******************************************************************************/ +int main() +{ + stm32_init(); + return example_main(); +} + diff --git a/projects/max22007/src/platform/stm32/parameters.c b/projects/max22007/src/platform/stm32/parameters.c new file mode 100644 index 00000000000..da1d63795a8 --- /dev/null +++ b/projects/max22007/src/platform/stm32/parameters.c @@ -0,0 +1,50 @@ +/***************************************************************************//** + * @file parameters.c + * @brief Definition of STM32 platform data used by MAX22007 project. + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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 "parameters.h" + +struct stm32_uart_init_param max22007_uart_extra_ip = { + .huart = UART_INSTANCE, +}; + +struct stm32_spi_init_param max22007_spi_extra_ip = { + .chip_select_port = GPIO_CS_PORT, + .get_input_clock = HAL_RCC_GetPCLK2Freq, +}; + diff --git a/projects/max22007/src/platform/stm32/parameters.h b/projects/max22007/src/platform/stm32/parameters.h new file mode 100644 index 00000000000..83a553294f4 --- /dev/null +++ b/projects/max22007/src/platform/stm32/parameters.h @@ -0,0 +1,66 @@ +/***************************************************************************//** + * @file parameters.h + * @brief Definitions specific to STM32 platform used by MAX22007 example + * @author Janani Sunil (janani.sunil@analog.com) +******************************************************************************** + * Copyright 2025(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. +*******************************************************************************/ +#ifndef __PARAMETERS_H__ +#define __PARAMETERS_H__ + +#include "stm32_hal.h" +#include "stm32_spi.h" +#include "stm32_uart.h" + +/* SPI device parameters */ +#define SPI_DEVICE_ID 1 // SPI1 +#define GPIO_CS_PIN 15 // PA15 +#define GPIO_CS_PORT 0 // GPIOA +#define spi_platform_ops stm32_spi_ops + +/* UART device parameters */ +#define UART_INSTANCE &huart5 +#define UART_DEVICE_ID 5U // UART5 +#define UART_IRQ_ID UART5_IRQn +#define UART_BAUDRATE 230400 +#define uart_platform_ops stm32_uart_ops +#define UART_EXTRA &max22007_uart_extra_ip + +extern struct stm32_spi_init_param max22007_spi_extra_ip; +extern struct stm32_uart_init_param max22007_uart_extra_ip; + +extern UART_HandleTypeDef huart5; + +#endif /* __PARAMETERS_H__ */ + diff --git a/projects/max22007/src/platform/stm32/platform_src.mk b/projects/max22007/src/platform/stm32/platform_src.mk new file mode 100644 index 00000000000..0bf845495ff --- /dev/null +++ b/projects/max22007/src/platform/stm32/platform_src.mk @@ -0,0 +1,16 @@ +INCS += $(PLATFORM_DRIVERS)/stm32_gpio.h \ + $(PLATFORM_DRIVERS)/stm32_hal.h \ + $(PLATFORM_DRIVERS)/stm32_uart.h \ + $(PLATFORM_DRIVERS)/stm32_uart_stdio.h \ + $(PLATFORM_DRIVERS)/stm32_dma.h \ + $(PLATFORM_DRIVERS)/stm32_irq.h \ + $(PLATFORM_DRIVERS)/stm32_spi.h \ + +SRCS += $(PLATFORM_DRIVERS)/stm32_delay.c \ + $(PLATFORM_DRIVERS)/stm32_gpio.c \ + $(PLATFORM_DRIVERS)/stm32_uart.c \ + $(PLATFORM_DRIVERS)/stm32_uart_stdio.c \ + $(PLATFORM_DRIVERS)/stm32_dma.c \ + $(PLATFORM_DRIVERS)/stm32_irq.c \ + $(PLATFORM_DRIVERS)/stm32_spi.c \ + diff --git a/util/no_os_crc8.c b/util/no_os_crc8.c index 3a8d15c0635..1271a1be92a 100644 --- a/util/no_os_crc8.c +++ b/util/no_os_crc8.c @@ -67,6 +67,41 @@ void no_os_crc8_populate_msb(uint8_t * table, const uint8_t polynomial) } } +/***************************************************************************//** + * @brief Creates the CRC-8 lookup table for a given polynomial. + * + * @param table - Pointer to a CRC-8 lookup table to write to. + * @param polynomial - lsb-first representation of desired polynomial. + * + * Polynomials in CRC algorithms are typically represented as shown below. + * + * poly = x^8 + x^2 + x^1 + 1 + * + * Using lsb-first direction, x^0 maps to the lsb. + * + * lsb first: poly = 11111000(1) = 0x1F + * + * @return None. +*******************************************************************************/ +void no_os_crc8_populate_lsb(uint8_t *table, const uint8_t polynomial) +{ + if (!table) + return; + + for (int16_t n = 0; n < NO_OS_CRC8_TABLE_SIZE; n++) { + uint8_t curr_byte = (uint8_t)n; + for (uint8_t bit = 0; bit < 8; bit++) { + if (curr_byte & 0x01) { + curr_byte >>= 1; + curr_byte ^= polynomial; + } else { + curr_byte >>= 1; + } + } + table[n] = curr_byte; + } +} + /***************************************************************************//** * @brief Computes the CRC-8 over a buffer of data. *