riscv/esp32c3: Add ESP32-C3 ADC driver

This commit is contained in:
Dong Heng 2021-05-04 22:31:14 +08:00 committed by Alan Carvalho de Assis
parent 26a5cb2094
commit f12de4f7d9
11 changed files with 2119 additions and 0 deletions

View File

@ -158,6 +158,12 @@ config ESP32C3_DISABLE_STDC_ATOMIC
menu "ESP32-C3 Peripheral Support"
config ESP32C3_ADC
bool
default n
select ANALOG
select ADC
config ESP32C3_UART
bool
default n
@ -274,6 +280,11 @@ config ESP32C3_RWDT
to have the RTC module reset, please, use the Timers' Module WDTs.
They will only reset Main System.
config ESP32C3_ADC1
bool "ADC1"
default n
select ESP32C3_ADC
config ESP32C3_WIRELESS
bool "Wireless"
default n
@ -511,6 +522,52 @@ config ESP32C3_LEDC_CHANNEL5_PIN
endmenu # LEDC configuration
menu "ADC Configuration"
depends on ESP32C3_ADC
if ESP32C3_ADC1
choice ESP32C3_ADC_VOL_RANGES
prompt "ADC1 voltage ranges"
default ESP32C3_ADC_VOL_750
config ESP32C3_ADC_VOL_750
bool "0~750mV"
config ESP32C3_ADC_VOL_1050
bool "0~1050mV"
config ESP32C3_ADC_VOL_1300
bool "0~1300mV"
config ESP32C3_ADC_VOL_2500
bool "0~2500mV"
endchoice
config ESP32C3_ADC1_CHANNEL0
bool "ADC1 channel 0"
default n
config ESP32C3_ADC1_CHANNEL1
bool "ADC1 channel 1"
default n
config ESP32C3_ADC1_CHANNEL2
bool "ADC1 channel 2"
default n
config ESP32C3_ADC1_CHANNEL3
bool "ADC1 channel 3"
default n
config ESP32C3_ADC1_CHANNEL4
bool "ADC1 channel 4"
default n
endif # ESP32C3_ADC1
endmenu # ADC Configuration
menu "Wi-Fi configuration"
depends on ESP32C3_WIRELESS

View File

@ -125,6 +125,10 @@ ifeq ($(CONFIG_ESP32C3_LEDC),y)
CHIP_CSRCS += esp32c3_ledc.c
endif
ifeq ($(CONFIG_ESP32C3_ADC),y)
CHIP_CSRCS += esp32c3_adc.c
endif
ifeq ($(CONFIG_ESP32C3_WIRELESS),y)
WIRELESS_DRV_UNPACK = esp-wireless-drivers-3rdparty
WIRELESS_DRV_ID = 2b53111

View File

@ -0,0 +1,787 @@
/****************************************************************************
* arch/risc-v/src/esp32c3/esp32c3_adc.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <inttypes.h>
#include <stdint.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/semaphore.h>
#include "riscv_arch.h"
#include "esp32c3.h"
#include "esp32c3_gpio.h"
#include "esp32c3_adc.h"
#include "hardware/esp32c3_system.h"
#include "hardware/esp32c3_saradc.h"
#include "hardware/esp32c3_gpio_sigmap.h"
#include "hardware/regi2c_ctrl.h"
#include "hardware/regi2c_saradc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* ADC calibration max count */
#define ADC_CAL_CNT_MAX (32)
/* ADC calibration max value */
#define ADC_CAL_VAL_MAX (4096 - 1)
/* ADC calibration sampling channel */
#define ADC_CAL_CHANNEL (0xf)
/* ADC max value mask */
#define ADC_VAL_MASK (0xfff)
/* ADC input voltage attenuation, this affects measuring range */
#define ADC_ATTEN_DB_0 (0) /* Vmax = 800 mV */
#define ADC_ATTEN_DB_2_5 (1) /* Vmax = 1100 mV */
#define ADC_ATTEN_DB_6 (2) /* Vmax = 1350 mV */
#define ADC_ATTEN_DB_11 (3) /* Vmax = 2600 mV */
/* ADC attenuation */
#if defined(CONFIG_ESP32C3_ADC_VOL_750)
# define ADC_ATTEN_DEF ADC_ATTEN_DB_0
# define ADC_VOL_VAL (750)
#elif defined(CONFIG_ESP32C3_ADC_VOL_1050)
# define ADC_ATTEN_DEF ADC_ATTEN_DB_2_5
# define ADC_VOL_VAL (1050)
#elif defined(CONFIG_ESP32C3_ADC_VOL_1300)
# define ADC_ATTEN_DEF ADC_ATTEN_DB_6
# define ADC_VOL_VAL (1300)
#elif defined(CONFIG_ESP32C3_ADC_VOL_2500)
# define ADC_ATTEN_DEF ADC_ATTEN_DB_11
# define ADC_VOL_VAL (2500)
#endif
#define ADC_WORK_DELAY (1)
#ifndef MIN
# define MIN(a, b) ((a) < (b) ? (a) : (b))
#endif
#ifndef MAX
# define MAX(a, b) ((a) > (b) ? (a) : (b))
#endif
/****************************************************************************
* Private Types
****************************************************************************/
/* ADC Private Data */
struct adc_chan_s
{
uint32_t ref; /* Reference count */
const uint8_t channel; /* Channel number */
const uint8_t pin; /* GPIO pin number */
const struct adc_callback_s *cb; /* Upper driver callback */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int adc_bind(struct adc_dev_s *dev,
const struct adc_callback_s *callback);
static void adc_reset(struct adc_dev_s *dev);
static int adc_setup(struct adc_dev_s *dev);
static void adc_shutdown(struct adc_dev_s *dev);
static void adc_rxint(struct adc_dev_s *dev, bool enable);
static int adc_ioctl(struct adc_dev_s *dev, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
****************************************************************************/
/* ADC interface operations */
static const struct adc_ops_s g_adcops =
{
.ao_bind = adc_bind,
.ao_reset = adc_reset,
.ao_setup = adc_setup,
.ao_shutdown = adc_shutdown,
.ao_rxint = adc_rxint,
.ao_ioctl = adc_ioctl,
};
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL0
static struct adc_chan_s g_adc1_chan0 =
{
.channel = 0,
.pin = 0
};
static struct adc_dev_s g_adc1_chan0_dev =
{
.ad_ops = &g_adcops,
.ad_priv = &g_adc1_chan0
};
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL1
static struct adc_chan_s g_adc1_chan1 =
{
.channel = 1,
.pin = 1
};
static struct adc_dev_s g_adc1_chan1_dev =
{
.ad_ops = &g_adcops,
.ad_priv = &g_adc1_chan1,
};
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL2
static struct adc_chan_s g_adc1_chan2 =
{
.channel = 2,
.pin = 2
};
static struct adc_dev_s g_adc1_chan2_dev =
{
.ad_ops = &g_adcops,
.ad_priv = &g_adc1_chan2,
};
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL3
static struct adc_chan_s g_adc1_chan3 =
{
.channel = 3,
.pin = 3
};
static struct adc_dev_s g_adc1_chan3_dev =
{
.ad_ops = &g_adcops,
.ad_priv = &g_adc1_chan3,
};
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL4
static struct adc_chan_s g_adc1_chan4 =
{
.channel = 4,
.pin = 4
};
static struct adc_dev_s g_adc1_chan4_dev =
{
.ad_ops = &g_adcops,
.ad_priv = &g_adc1_chan4,
};
#endif
/* ADC calibration mark */
static bool g_calibrated;
/* ADC clock reference */
static uint32_t g_clk_ref;
static sem_t g_sem_excl = SEM_INITIALIZER(1);
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: adc_enable_clk
*
* Description:
* Enable ADC clock.
*
* Input Parameters:
* NOne
*
* Returned Value:
* None.
*
****************************************************************************/
static void adc_enable_clk(void)
{
irqstate_t flags;
flags = enter_critical_section();
if (!g_clk_ref)
{
setbits(SYSTEM_APB_SARADC_CLK_EN, SYSTEM_PERIP_CLK_EN0_REG);
resetbits(SYSTEM_APB_SARADC_RST, SYSTEM_PERIP_RST_EN0_REG);
}
g_clk_ref++;
leave_critical_section(flags);
}
/****************************************************************************
* Name: adc_disable_clk
*
* Description:
* Disable ADC clock.
*
* Input Parameters:
* NOne
*
* Returned Value:
* None.
*
****************************************************************************/
static void adc_disable_clk(void)
{
irqstate_t flags;
flags = enter_critical_section();
g_clk_ref--;
if (!g_clk_ref)
{
setbits(SYSTEM_APB_SARADC_RST, SYSTEM_PERIP_RST_EN0_REG);
resetbits(SYSTEM_APB_SARADC_CLK_EN, SYSTEM_PERIP_CLK_EN0_REG);
}
leave_critical_section(flags);
}
/****************************************************************************
* Name: adc_set_calibration
*
* Description:
* Set calibration parameter to ADC hardware.
*
* Input Parameters:
* data - Calibration parameter
*
* Returned Value:
* None.
*
****************************************************************************/
static void adc_set_calibration(uint16_t data)
{
uint8_t h_data = data >> 8;
uint8_t l_data = data & 0xff;
rom_i2c_writereg_mask(I2C_ADC, I2C_ADC_HOSTID,
I2C_ADC1_INITVAL_H,
I2C_ADC1_INITVAL_H_MSB,
I2C_ADC1_INITVAL_H_LSB, h_data);
rom_i2c_writereg_mask(I2C_ADC, I2C_ADC_HOSTID,
I2C_ADC1_INITVAL_L,
I2C_ADC1_INITVAL_L_MSB,
I2C_ADC1_INITVAL_L_LSB, l_data);
}
/****************************************************************************
* Name: adc_samplecfg
*
* Description:
* Set ADC sampling with given channel.
*
* Input Parameters:
* channel - Sampling channel number
*
* Returned Value:
* None.
*
****************************************************************************/
static inline void adc_samplecfg(int channel)
{
uint32_t regval;
/* Enable ADC1, its sampling channel and attenuation */
regval = getreg32(APB_SARADC_ONETIME_SAMPLE_REG);
regval &= ~(APB_SARADC1_ONETIME_SAMPLE | APB_SARADC2_ONETIME_SAMPLE |
APB_SARADC_ONETIME_CHANNEL_M | APB_SARADC_ONETIME_ATTEN_M);
regval |= (channel << APB_SARADC_ONETIME_CHANNEL_S) |
(ADC_ATTEN_DEF << APB_SARADC_ONETIME_ATTEN_S) |
APB_SARADC1_ONETIME_SAMPLE;
putreg32(regval, APB_SARADC_ONETIME_SAMPLE_REG);
}
/****************************************************************************
* Name: adc_read
*
* Description:
* Start ADC sampling and read ADC value.
*
* Input Parameters:
* None
*
* Returned Value:
* Read ADC value.
*
****************************************************************************/
static uint16_t adc_read(void)
{
uint16_t adc;
uint32_t regval;
/* Trigger ADC sampling */
setbits(APB_SARADC_ONETIME_START, APB_SARADC_ONETIME_SAMPLE_REG);
/* Wait until ADC1 sampling is done */
do
{
regval = getreg32(APB_SARADC_INT_ST_REG);
}
while (!(regval & APB_SARADC_ADC1_DONE_INT_ST));
adc = getreg32(APB_SARADC_1_DATA_STATUS_REG) & ADC_VAL_MASK;
/* Disable ADC sampling */
resetbits(APB_SARADC_ONETIME_START, APB_SARADC_ONETIME_SAMPLE_REG);
/* Clear ADC1 sampling done interrupt bit */
setbits(APB_SARADC_ADC1_DONE_INT_CLR, APB_SARADC_INT_CLR_REG);
return adc;
}
/****************************************************************************
* Name: adc_calibrate
*
* Description:
* ADC calibration.
*
* Input Parameters:
* None
*
* Returned Value:
* None.
*
****************************************************************************/
static void adc_calibrate(void)
{
uint16_t cali_val;
uint16_t adc;
uint16_t adc_max = 0;
uint16_t adc_min = UINT16_MAX;
uint32_t adc_sum = 0;
/* Enable Vdef */
rom_i2c_writereg_mask(I2C_ADC, I2C_ADC_HOSTID,
I2C_ADC1_DEF, I2C_ADC1_DEF_MSB,
I2C_ADC1_DEF_LSB, 1);
/* Start sampling */
adc_samplecfg(ADC_CAL_CHANNEL);
/* Enable internal connect GND (for calibration). */
rom_i2c_writereg_mask(I2C_ADC, I2C_ADC_HOSTID,
I2C_ADC1_ENCAL_GND, I2C_ADC1_ENCAL_GND_MSB,
I2C_ADC1_ENCAL_GND_LSB, 1);
for (int i = 1; i < ADC_CAL_CNT_MAX ; i++)
{
adc_set_calibration(0);
adc = adc_read();
adc_sum += adc;
adc_max = MAX(adc, adc_max);
adc_min = MIN(adc, adc_min);
}
cali_val = (adc_sum - adc_max - adc_min) / (ADC_CAL_CNT_MAX - 2);
/* Disable internal connect GND (for calibration). */
rom_i2c_writereg_mask(I2C_ADC, I2C_ADC_HOSTID,
I2C_ADC1_ENCAL_GND,
I2C_ADC1_ENCAL_GND_MSB,
I2C_ADC1_ENCAL_GND_LSB, 0);
ainfo("calibration value: %" PRIu16 "\n", cali_val);
/* Set final calibration parameters */
adc_set_calibration(cali_val);
}
/****************************************************************************
* Name: adc_read_work
*
* Description:
* Read ADC value and pass it to up.
*
* Input Parameters:
* dev - ADC device pointer
*
* Returned Value:
* None.
*
****************************************************************************/
static void adc_read_work(struct adc_dev_s *dev)
{
int ret;
uint16_t adc;
struct adc_chan_s *priv = (struct adc_chan_s *)dev->ad_priv;
ret = sem_wait(&g_sem_excl);
if (ret < 0)
{
aerr("Failed to wait sem ret=%d\n", ret);
return ;
}
adc_samplecfg(priv->channel);
adc = adc_read();
priv->cb->au_receive(dev, priv->channel, adc);
ainfo("channel: %" PRIu8 ", voltage: %" PRIu32 " mV\n", priv->channel,
(uint32_t)adc * ADC_VOL_VAL / ADC_CAL_VAL_MAX);
sem_post(&g_sem_excl);
}
/****************************************************************************
* Name: adc_bind
*
* Description:
* Bind the upper-half driver callbacks to the lower-half implementation.
* This must be called early in order to receive ADC event notifications.
*
****************************************************************************/
static int adc_bind(struct adc_dev_s *dev,
const struct adc_callback_s *callback)
{
struct adc_chan_s *priv = (struct adc_chan_s *)dev->ad_priv;
DEBUGASSERT(priv != NULL);
ainfo("channel: %" PRIu8 "\n", priv->channel);
priv->cb = callback;
return OK;
}
/****************************************************************************
* Name: adc_reset
*
* Description:
* Reset the ADC device. Called early to initialize the hardware.
* This is called, before adc_setup() and on error conditions.
*
* Input Parameters:
*
* Returned Value:
*
****************************************************************************/
static void adc_reset(struct adc_dev_s *dev)
{
irqstate_t flags;
struct adc_chan_s *priv = (struct adc_chan_s *)dev->ad_priv;
ainfo("channel: %" PRIu8 "\n", priv->channel);
flags = enter_critical_section();
/* Do nothing if ADC instance is currently in use */
if (priv->ref > 0)
{
goto out;
}
/* Reset ADC hardware */
adc_enable_clk();
adc_disable_clk();
out:
leave_critical_section(flags);
}
/****************************************************************************
* Name: adc_setup
*
* Description:
* Configure the ADC. This method is called the first time that the ADC
* device is opened. This will occur when the port is first opened.
* This setup includes configuring.
*
* Input Parameters:
*
* Returned Value:
*
****************************************************************************/
static int adc_setup(struct adc_dev_s *dev)
{
int ret;
uint32_t regval;
struct adc_chan_s *priv = (struct adc_chan_s *)dev->ad_priv;
ainfo("channel: %" PRIu8 "\n", priv->channel);
/* Do nothing when the ADC device is already set up */
if (priv->ref > 0)
{
return OK;
}
/* Enable ADC clock */
adc_enable_clk();
/* Disable GPIO input and output */
ainfo("pin: %" PRIu8 "\n", priv->pin);
esp32c3_configgpio(priv->pin, INPUT);
/* Config ADC hardware */
regval = APB_SARADC_SAR_CLK_GATED_M | APB_SARADC_XPD_SAR_FORCE_M;
setbits(regval, APB_SARADC_CTRL_REG);
regval = APB_SARADC_ADC1_DONE_INT_ENA;
setbits(regval, APB_SARADC_INT_ENA_REG);
/* Start calibration only once */
ret = sem_wait(&g_sem_excl);
if (ret < 0)
{
adc_disable_clk();
aerr("Failed to wait sem ret=%d\n", ret);
return ret;
}
if (!g_calibrated)
{
adc_calibrate();
g_calibrated = true;
}
sem_post(&g_sem_excl);
/* The ADC device is ready */
priv->ref++;
return OK;
}
/****************************************************************************
* Name: adc_rxint
*
* Description:
* Call to enable or disable RX interrupts.
*
* Input Parameters:
*
* Returned Value:
*
****************************************************************************/
static void adc_rxint(struct adc_dev_s *dev, bool enable)
{
}
/****************************************************************************
* Name: adc_ioctl
*
* Description:
* All ioctl calls will be routed through this method.
*
* Input Parameters:
* dev - pointer to device structure used by the driver
* cmd - command
* arg - arguments passed with command
*
* Returned Value:
*
****************************************************************************/
static int adc_ioctl(struct adc_dev_s *dev, int cmd, unsigned long arg)
{
int ret;
struct adc_chan_s *priv = (struct adc_chan_s *)dev->ad_priv;
ainfo("channel: %" PRIu8 " cmd=%d\n", priv->channel, cmd);
switch (cmd)
{
case ANIOC_TRIGGER:
/* Start sampling and read ADC value here */
adc_read_work(dev);
ret = OK;
break;
default:
aerr("ERROR: Unknown cmd: %d\n", cmd);
ret = -ENOTTY;
break;
}
return ret;
}
/****************************************************************************
* Name: adc_shutdown
*
* Description:
* Disable the ADC. This method is called when the ADC device is closed.
* This method reverses the operation the setup method.
*
* Input Parameters:
*
* Returned Value:
*
****************************************************************************/
static void adc_shutdown(struct adc_dev_s *dev)
{
struct adc_chan_s *priv = (struct adc_chan_s *)dev->ad_priv;
ainfo("channel: %" PRIu8 "\n", priv->channel);
/* Decrement count only when ADC device is in use */
if (priv->ref > 0)
{
priv->ref--;
/* Shutdown the ADC device only when not in use */
if (!priv->ref)
{
adc_rxint(dev, false);
/* Disable ADC clock */
adc_disable_clk();
}
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: esp32c3_adc_init
*
* Description:
* Initialize the ADC.
*
* Input Parameters:
* channel - ADC channel number
*
* Returned Value:
* ADC device structure reference on success; a NULL on failure
*
****************************************************************************/
struct adc_dev_s *esp32c3_adc_init(int channel)
{
struct adc_dev_s *dev;
ainfo("ADC channel: %" PRIu8 "\n", channel);
switch (channel)
{
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL0
case 0:
dev = &g_adc1_chan0_dev;
break;
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL1
case 1:
dev = &g_adc1_chan1_dev;
break;
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL2
case 2:
dev = &g_adc1_chan2_dev;
break;
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL3
case 3:
dev = &g_adc1_chan3_dev;
break;
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL4
case 4:
dev = &g_adc1_chan4_dev;
break;
#endif
default:
{
aerr("ERROR: No ADC interface defined\n");
return NULL;
}
}
return dev;
}

View File

@ -0,0 +1,79 @@
/****************************************************************************
* arch/risc-v/src/esp32c3/esp32c3_adc.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_RISCV_SRC_ESP32C3_ESP32C3_ADC_H
#define __ARCH_RISCV_SRC_ESP32C3_ESP32C3_ADC_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <nuttx/analog/adc.h>
#include <nuttx/analog/ioctl.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: esp32c3_adc_init
*
* Description:
* Initialize the ADC.
*
* Input Parameters:
* channel - ADC channel number
*
* Returned Value:
* ADC device structure reference on success; a NULL on failure
*
****************************************************************************/
struct adc_dev_s *esp32c3_adc_init(int channel);
#ifdef __cplusplus
}
#endif
#undef EXTERN
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_RISCV_SRC_ESP32C3_ESP32C3_ADC_H */

View File

@ -0,0 +1,912 @@
/****************************************************************************
* arch/risc-v/src/esp32c3/hardware/esp32c3_saradc.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_RISCV_SRC_ESP32C3_HARDWARE_ESP32C3_SARADC_H
#define __ARCH_RISCV_SRC_ESP32C3_HARDWARE_ESP32C3_SARADC_H
/****************************************************************************
* Included Files
****************************************************************************/
#include "esp32c3_soc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define APB_SARADC_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x000)
/** APB_SARADC_WAIT_ARB_CYCLE : R/W ;bitpos:[31:30] ;default: 2'd1 ;
* description: wait arbit signal stable after sar_done
*/
#define APB_SARADC_WAIT_ARB_CYCLE 0x00000003
#define APB_SARADC_WAIT_ARB_CYCLE_M ((APB_SARADC_WAIT_ARB_CYCLE_V)<<(APB_SARADC_WAIT_ARB_CYCLE_S))
#define APB_SARADC_WAIT_ARB_CYCLE_V 0x3
#define APB_SARADC_WAIT_ARB_CYCLE_S 30
/* APB_SARADC_XPD_SAR_FORCE : R/W ;bitpos:[28:27] ;default: 2'd0 ; */
/* description: force option to xpd sar blocks */
#define APB_SARADC_XPD_SAR_FORCE 0x00000003
#define APB_SARADC_XPD_SAR_FORCE_M ((APB_SARADC_XPD_SAR_FORCE_V)<<(APB_SARADC_XPD_SAR_FORCE_S))
#define APB_SARADC_XPD_SAR_FORCE_V 0x3
#define APB_SARADC_XPD_SAR_FORCE_S 27
/* APB_SARADC_SAR_PATT_P_CLEAR : R/W ;bitpos:[23] ;default: 1'd0 ; */
/* description: clear the pointer of pattern table for DIG ADC1 CTRL */
#define APB_SARADC_SAR_PATT_P_CLEAR (BIT(23))
#define APB_SARADC_SAR_PATT_P_CLEAR_M (BIT(23))
#define APB_SARADC_SAR_PATT_P_CLEAR_V 0x1
#define APB_SARADC_SAR_PATT_P_CLEAR_S 23
/* APB_SARADC_SAR_PATT_LEN : R/W ;bitpos:[17:15] ;default: 3'd7 ; */
/* description: 0 ~ 15 means length 1 ~ 16 */
#define APB_SARADC_SAR_PATT_LEN 0x00000007
#define APB_SARADC_SAR_PATT_LEN_M ((APB_SARADC_SAR_PATT_LEN_V)<<(APB_SARADC_SAR_PATT_LEN_S))
#define APB_SARADC_SAR_PATT_LEN_V 0x7
#define APB_SARADC_SAR_PATT_LEN_S 15
/* APB_SARADC_SAR_CLK_DIV : R/W ;bitpos:[14:7] ;default: 8'd4 ; */
/* description: SAR clock divider */
#define APB_SARADC_SAR_CLK_DIV 0x000000FF
#define APB_SARADC_SAR_CLK_DIV_M ((APB_SARADC_SAR_CLK_DIV_V)<<(APB_SARADC_SAR_CLK_DIV_S))
#define APB_SARADC_SAR_CLK_DIV_V 0xFF
#define APB_SARADC_SAR_CLK_DIV_S 7
/* APB_SARADC_SAR_CLK_GATED : R/W ;bitpos:[6] ;default: 1'b1 ; */
/* description: */
#define APB_SARADC_SAR_CLK_GATED (BIT(6))
#define APB_SARADC_SAR_CLK_GATED_M (BIT(6))
#define APB_SARADC_SAR_CLK_GATED_V 0x1
#define APB_SARADC_SAR_CLK_GATED_S 6
/* APB_SARADC_START : R/W ;bitpos:[1] ;default: 1'd0 ; */
/* description: */
#define APB_SARADC_START (BIT(1))
#define APB_SARADC_START_M (BIT(1))
#define APB_SARADC_START_V 0x1
#define APB_SARADC_START_S 1
/* APB_SARADC_START_FORCE : R/W ;bitpos:[0] ;default: 1'd0 ; */
/* description: */
#define APB_SARADC_START_FORCE (BIT(0))
#define APB_SARADC_START_FORCE_M (BIT(0))
#define APB_SARADC_START_FORCE_V 0x1
#define APB_SARADC_START_FORCE_S 0
#define APB_SARADC_CTRL2_REG (DR_REG_APB_SARADC_BASE + 0x004)
/* APB_SARADC_TIMER_EN : R/W ;bitpos:[24] ;default: 1'd0 ; */
/* description: to enable saradc timer trigger */
#define APB_SARADC_TIMER_EN (BIT(24))
#define APB_SARADC_TIMER_EN_M (BIT(24))
#define APB_SARADC_TIMER_EN_V 0x1
#define APB_SARADC_TIMER_EN_S 24
/* APB_SARADC_TIMER_TARGET : R/W ;bitpos:[23:12] ;default: 12'd10 ; */
/* description: to set saradc timer target */
#define APB_SARADC_TIMER_TARGET 0x00000FFF
#define APB_SARADC_TIMER_TARGET_M ((APB_SARADC_TIMER_TARGET_V)<<(APB_SARADC_TIMER_TARGET_S))
#define APB_SARADC_TIMER_TARGET_V 0xFFF
#define APB_SARADC_TIMER_TARGET_S 12
/* APB_SARADC_SAR2_INV : R/W ;bitpos:[10] ;default: 1'd0 ; */
/* description: 1: data to DIG ADC2 CTRL is inverted otherwise not */
#define APB_SARADC_SAR2_INV (BIT(10))
#define APB_SARADC_SAR2_INV_M (BIT(10))
#define APB_SARADC_SAR2_INV_V 0x1
#define APB_SARADC_SAR2_INV_S 10
/* APB_SARADC_SAR1_INV : R/W ;bitpos:[9] ;default: 1'd0 ; */
/* description: 1: data to DIG ADC1 CTRL is inverted otherwise not */
#define APB_SARADC_SAR1_INV (BIT(9))
#define APB_SARADC_SAR1_INV_M (BIT(9))
#define APB_SARADC_SAR1_INV_V 0x1
#define APB_SARADC_SAR1_INV_S 9
/* APB_SARADC_MAX_MEAS_NUM : R/W ;bitpos:[8:1] ;default: 8'd255 ; */
/* description: max conversion number */
#define APB_SARADC_MAX_MEAS_NUM 0x000000FF
#define APB_SARADC_MAX_MEAS_NUM_M ((APB_SARADC_MAX_MEAS_NUM_V)<<(APB_SARADC_MAX_MEAS_NUM_S))
#define APB_SARADC_MAX_MEAS_NUM_V 0xFF
#define APB_SARADC_MAX_MEAS_NUM_S 1
/* APB_SARADC_MEAS_NUM_LIMIT : R/W ;bitpos:[0] ;default: 1'd0 ; */
/* description: */
#define APB_SARADC_MEAS_NUM_LIMIT (BIT(0))
#define APB_SARADC_MEAS_NUM_LIMIT_M (BIT(0))
#define APB_SARADC_MEAS_NUM_LIMIT_V 0x1
#define APB_SARADC_MEAS_NUM_LIMIT_S 0
#define APB_SARADC_FILTER_CTRL1_REG (DR_REG_APB_SARADC_BASE + 0x008)
/* APB_SARADC_FILTER_FACTOR0 : R/W ;bitpos:[31:29] ;default: 3'd0 ; */
/* description: */
#define APB_SARADC_FILTER_FACTOR0 0x00000007
#define APB_SARADC_FILTER_FACTOR0_M ((APB_SARADC_FILTER_FACTOR0_V)<<(APB_SARADC_FILTER_FACTOR0_S))
#define APB_SARADC_FILTER_FACTOR0_V 0x7
#define APB_SARADC_FILTER_FACTOR0_S 29
/* APB_SARADC_FILTER_FACTOR1 : R/W ;bitpos:[28:26] ;default: 3'd0 ; */
/* description: */
#define APB_SARADC_FILTER_FACTOR1 0x00000007
#define APB_SARADC_FILTER_FACTOR1_M ((APB_SARADC_FILTER_FACTOR1_V)<<(APB_SARADC_FILTER_FACTOR1_S))
#define APB_SARADC_FILTER_FACTOR1_V 0x7
#define APB_SARADC_FILTER_FACTOR1_S 26
#define APB_SARADC_FSM_WAIT_REG (DR_REG_APB_SARADC_BASE + 0x00C)
/* APB_SARADC_STANDBY_WAIT : R/W ;bitpos:[23:16] ;default: 8'd255 ; */
/* description: */
#define APB_SARADC_STANDBY_WAIT 0x000000FF
#define APB_SARADC_STANDBY_WAIT_M ((APB_SARADC_STANDBY_WAIT_V)<<(APB_SARADC_STANDBY_WAIT_S))
#define APB_SARADC_STANDBY_WAIT_V 0xFF
#define APB_SARADC_STANDBY_WAIT_S 16
/* APB_SARADC_RSTB_WAIT : R/W ;bitpos:[15:8] ;default: 8'd8 ; */
/* description: */
#define APB_SARADC_RSTB_WAIT 0x000000FF
#define APB_SARADC_RSTB_WAIT_M ((APB_SARADC_RSTB_WAIT_V)<<(APB_SARADC_RSTB_WAIT_S))
#define APB_SARADC_RSTB_WAIT_V 0xFF
#define APB_SARADC_RSTB_WAIT_S 8
/* APB_SARADC_XPD_WAIT : R/W ;bitpos:[7:0] ;default: 8'd8 ; */
/* description: */
#define APB_SARADC_XPD_WAIT 0x000000FF
#define APB_SARADC_XPD_WAIT_M ((APB_SARADC_XPD_WAIT_V)<<(APB_SARADC_XPD_WAIT_S))
#define APB_SARADC_XPD_WAIT_V 0xFF
#define APB_SARADC_XPD_WAIT_S 0
#define APB_SARADC_SAR1_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x010)
/* APB_SARADC_SAR1_STATUS : RO ;bitpos:[31:0] ;default: 32'd0 ; */
/* description: */
#define APB_SARADC_SAR1_STATUS 0xFFFFFFFF
#define APB_SARADC_SAR1_STATUS_M ((APB_SARADC_SAR1_STATUS_V)<<(APB_SARADC_SAR1_STATUS_S))
#define APB_SARADC_SAR1_STATUS_V 0xFFFFFFFF
#define APB_SARADC_SAR1_STATUS_S 0
#define APB_SARADC_SAR2_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x014)
/* APB_SARADC_SAR2_STATUS : RO ;bitpos:[31:0] ;default: 32'd0 ; */
/* description: */
#define APB_SARADC_SAR2_STATUS 0xFFFFFFFF
#define APB_SARADC_SAR2_STATUS_M ((APB_SARADC_SAR2_STATUS_V)<<(APB_SARADC_SAR2_STATUS_S))
#define APB_SARADC_SAR2_STATUS_V 0xFFFFFFFF
#define APB_SARADC_SAR2_STATUS_S 0
#define APB_SARADC_SAR_PATT_TAB1_REG (DR_REG_APB_SARADC_BASE + 0x018)
/* APB_SARADC_SAR_PATT_TAB1 : R/W ;bitpos:[23:0] ;default: 24'h0 ; */
/* description: item 0 ~ 3 for pattern table 1 (each item one byte) */
#define APB_SARADC_SAR_PATT_TAB1 0x00FFFFFF
#define APB_SARADC_SAR_PATT_TAB1_M ((APB_SARADC_SAR_PATT_TAB1_V)<<(APB_SARADC_SAR_PATT_TAB1_S))
#define APB_SARADC_SAR_PATT_TAB1_V 0xFFFFFF
#define APB_SARADC_SAR_PATT_TAB1_S 0
#define APB_SARADC_SAR_PATT_TAB2_REG (DR_REG_APB_SARADC_BASE + 0x01C)
/* APB_SARADC_SAR_PATT_TAB2 : R/W ;bitpos:[23:0] ;default: 24'h0 ; */
/* description: Item 4 ~ 7 for pattern table 1 (each item one byte) */
#define APB_SARADC_SAR_PATT_TAB2 0x00FFFFFF
#define APB_SARADC_SAR_PATT_TAB2_M ((APB_SARADC_SAR_PATT_TAB2_V)<<(APB_SARADC_SAR_PATT_TAB2_S))
#define APB_SARADC_SAR_PATT_TAB2_V 0xFFFFFF
#define APB_SARADC_SAR_PATT_TAB2_S 0
#define APB_SARADC_ONETIME_SAMPLE_REG (DR_REG_APB_SARADC_BASE + 0x020)
/* APB_SARADC1_ONETIME_SAMPLE : R/W ;bitpos:[31] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC1_ONETIME_SAMPLE (BIT(31))
#define APB_SARADC1_ONETIME_SAMPLE_M (BIT(31))
#define APB_SARADC1_ONETIME_SAMPLE_V 0x1
#define APB_SARADC1_ONETIME_SAMPLE_S 31
/* APB_SARADC2_ONETIME_SAMPLE : R/W ;bitpos:[30] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC2_ONETIME_SAMPLE (BIT(30))
#define APB_SARADC2_ONETIME_SAMPLE_M (BIT(30))
#define APB_SARADC2_ONETIME_SAMPLE_V 0x1
#define APB_SARADC2_ONETIME_SAMPLE_S 30
/* APB_SARADC_ONETIME_START : R/W ;bitpos:[29] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ONETIME_START (BIT(29))
#define APB_SARADC_ONETIME_START_M (BIT(29))
#define APB_SARADC_ONETIME_START_V 0x1
#define APB_SARADC_ONETIME_START_S 29
/* APB_SARADC_ONETIME_CHANNEL : R/W ;bitpos:[28:25] ;default: 4'd13 ; */
/* description: */
#define APB_SARADC_ONETIME_CHANNEL 0x0000000F
#define APB_SARADC_ONETIME_CHANNEL_M ((APB_SARADC_ONETIME_CHANNEL_V)<<(APB_SARADC_ONETIME_CHANNEL_S))
#define APB_SARADC_ONETIME_CHANNEL_V 0xF
#define APB_SARADC_ONETIME_CHANNEL_S 25
/* APB_SARADC_ONETIME_ATTEN : R/W ;bitpos:[24:23] ;default: 2'd0 ; */
/* description: */
#define APB_SARADC_ONETIME_ATTEN 0x00000003
#define APB_SARADC_ONETIME_ATTEN_M ((APB_SARADC_ONETIME_ATTEN_V)<<(APB_SARADC_ONETIME_ATTEN_S))
#define APB_SARADC_ONETIME_ATTEN_V 0x3
#define APB_SARADC_ONETIME_ATTEN_S 23
#define APB_SARADC_APB_ADC_ARB_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x024)
/* APB_SARADC_ADC_ARB_FIX_PRIORITY : R/W ;bitpos:[12] ;default: 1'b0 ; */
/* description: adc2 arbiter uses fixed priority */
#define APB_SARADC_ADC_ARB_FIX_PRIORITY (BIT(12))
#define APB_SARADC_ADC_ARB_FIX_PRIORITY_M (BIT(12))
#define APB_SARADC_ADC_ARB_FIX_PRIORITY_V 0x1
#define APB_SARADC_ADC_ARB_FIX_PRIORITY_S 12
/* APB_SARADC_ADC_ARB_WIFI_PRIORITY : R/W ;bitpos:[11:10] ;default: 2'd2 ; */
/* description: Set adc2 arbiter wifi priority */
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY 0x00000003
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY_M ((APB_SARADC_ADC_ARB_WIFI_PRIORITY_V)<<(APB_SARADC_ADC_ARB_WIFI_PRIORITY_S))
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY_V 0x3
#define APB_SARADC_ADC_ARB_WIFI_PRIORITY_S 10
/* APB_SARADC_ADC_ARB_RTC_PRIORITY : R/W ;bitpos:[9:8] ;default: 2'd1 ; */
/* description: Set adc2 arbiter rtc priority */
#define APB_SARADC_ADC_ARB_RTC_PRIORITY 0x00000003
#define APB_SARADC_ADC_ARB_RTC_PRIORITY_M ((APB_SARADC_ADC_ARB_RTC_PRIORITY_V)<<(APB_SARADC_ADC_ARB_RTC_PRIORITY_S))
#define APB_SARADC_ADC_ARB_RTC_PRIORITY_V 0x3
#define APB_SARADC_ADC_ARB_RTC_PRIORITY_S 8
/* APB_SARADC_ADC_ARB_APB_PRIORITY : R/W ;bitpos:[7:6] ;default: 2'd0 ; */
/* description: Set adc2 arbiterapb priority */
#define APB_SARADC_ADC_ARB_APB_PRIORITY 0x00000003
#define APB_SARADC_ADC_ARB_APB_PRIORITY_M ((APB_SARADC_ADC_ARB_APB_PRIORITY_V)<<(APB_SARADC_ADC_ARB_APB_PRIORITY_S))
#define APB_SARADC_ADC_ARB_APB_PRIORITY_V 0x3
#define APB_SARADC_ADC_ARB_APB_PRIORITY_S 6
/* APB_SARADC_ADC_ARB_GRANT_FORCE : R/W ;bitpos:[5] ;default: 1'b0 ; */
/* description: adc2 arbiter force grant */
#define APB_SARADC_ADC_ARB_GRANT_FORCE (BIT(5))
#define APB_SARADC_ADC_ARB_GRANT_FORCE_M (BIT(5))
#define APB_SARADC_ADC_ARB_GRANT_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_GRANT_FORCE_S 5
/* APB_SARADC_ADC_ARB_WIFI_FORCE : R/W ;bitpos:[4] ;default: 1'b0 ; */
/* description: adc2 arbiter force to enable wifi controller */
#define APB_SARADC_ADC_ARB_WIFI_FORCE (BIT(4))
#define APB_SARADC_ADC_ARB_WIFI_FORCE_M (BIT(4))
#define APB_SARADC_ADC_ARB_WIFI_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_WIFI_FORCE_S 4
/* APB_SARADC_ADC_ARB_RTC_FORCE : R/W ;bitpos:[3] ;default: 1'b0 ; */
/* description: adc2 arbiter force to enable rtc controller */
#define APB_SARADC_ADC_ARB_RTC_FORCE (BIT(3))
#define APB_SARADC_ADC_ARB_RTC_FORCE_M (BIT(3))
#define APB_SARADC_ADC_ARB_RTC_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_RTC_FORCE_S 3
/* APB_SARADC_ADC_ARB_APB_FORCE : R/W ;bitpos:[2] ;default: 1'fb0 ; */
/* description: adc2 arbiter force to enableapb controller */
#define APB_SARADC_ADC_ARB_APB_FORCE (BIT(2))
#define APB_SARADC_ADC_ARB_APB_FORCE_M (BIT(2))
#define APB_SARADC_ADC_ARB_APB_FORCE_V 0x1
#define APB_SARADC_ADC_ARB_APB_FORCE_S 2
#define APB_SARADC_FILTER_CTRL0_REG (DR_REG_APB_SARADC_BASE + 0x028)
/* APB_SARADC_FILTER_RESET : R/W ;bitpos:[31] ;default: 1'b0 ; */
/* description: enable apb_adc1_filter */
#define APB_SARADC_FILTER_RESET (BIT(31))
#define APB_SARADC_FILTER_RESET_M (BIT(31))
#define APB_SARADC_FILTER_RESET_V 0x1
#define APB_SARADC_FILTER_RESET_S 31
/* APB_SARADC_FILTER_CHANNEL0 : R/W ;bitpos:[25:22] ;default: 4'd13 ; */
/* description: apb_adc1_filter_factor */
#define APB_SARADC_FILTER_CHANNEL0 0x0000000F
#define APB_SARADC_FILTER_CHANNEL0_M ((APB_SARADC_FILTER_CHANNEL0_V)<<(APB_SARADC_FILTER_CHANNEL0_S))
#define APB_SARADC_FILTER_CHANNEL0_V 0xF
#define APB_SARADC_FILTER_CHANNEL0_S 22
/* APB_SARADC_FILTER_CHANNEL1 : R/W ;bitpos:[21:18] ;default: 4'd13 ; */
/* description: */
#define APB_SARADC_FILTER_CHANNEL1 0x0000000F
#define APB_SARADC_FILTER_CHANNEL1_M ((APB_SARADC_FILTER_CHANNEL1_V)<<(APB_SARADC_FILTER_CHANNEL1_S))
#define APB_SARADC_FILTER_CHANNEL1_V 0xF
#define APB_SARADC_FILTER_CHANNEL1_S 18
#define APB_SARADC_1_DATA_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x02C)
/* APB_SARADC_ADC1_DATA : RO ;bitpos:[16:0] ;default: 17'd0 ; */
/* description: */
#define APB_SARADC_ADC1_DATA 0x0001FFFF
#define APB_SARADC_ADC1_DATA_M ((APB_SARADC_ADC1_DATA_V)<<(APB_SARADC_ADC1_DATA_S))
#define APB_SARADC_ADC1_DATA_V 0x1FFFF
#define APB_SARADC_ADC1_DATA_S 0
#define APB_SARADC_2_DATA_STATUS_REG (DR_REG_APB_SARADC_BASE + 0x030)
/* APB_SARADC_ADC2_DATA : RO ;bitpos:[16:0] ;default: 17'd0 ; */
/* description: */
#define APB_SARADC_ADC2_DATA 0x0001FFFF
#define APB_SARADC_ADC2_DATA_M ((APB_SARADC_ADC2_DATA_V)<<(APB_SARADC_ADC2_DATA_S))
#define APB_SARADC_ADC2_DATA_V 0x1FFFF
#define APB_SARADC_ADC2_DATA_S 0
#define APB_SARADC_THRES0_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x034)
/* APB_SARADC_THRES0_LOW : R/W ;bitpos:[30:18] ;default: 13'd0 ; */
/* description: saradc1's thres0 monitor thres */
#define APB_SARADC_THRES0_LOW 0x00001FFF
#define APB_SARADC_THRES0_LOW_M ((APB_SARADC_THRES0_LOW_V)<<(APB_SARADC_THRES0_LOW_S))
#define APB_SARADC_THRES0_LOW_V 0x1FFF
#define APB_SARADC_THRES0_LOW_S 18
/* APB_SARADC_THRES0_HIGH : R/W ;bitpos:[17:5] ;default: 13'h1fff ; */
/* description: saradc1's thres0 monitor thres */
#define APB_SARADC_THRES0_HIGH 0x00001FFF
#define APB_SARADC_THRES0_HIGH_M ((APB_SARADC_THRES0_HIGH_V)<<(APB_SARADC_THRES0_HIGH_S))
#define APB_SARADC_THRES0_HIGH_V 0x1FFF
#define APB_SARADC_THRES0_HIGH_S 5
/* APB_SARADC_THRES0_CHANNEL : R/W ;bitpos:[3:0] ;default: 4'd13 ; */
/* description: */
#define APB_SARADC_THRES0_CHANNEL 0x0000000F
#define APB_SARADC_THRES0_CHANNEL_M ((APB_SARADC_THRES0_CHANNEL_V)<<(APB_SARADC_THRES0_CHANNEL_S))
#define APB_SARADC_THRES0_CHANNEL_V 0xF
#define APB_SARADC_THRES0_CHANNEL_S 0
#define APB_SARADC_THRES1_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x038)
/* APB_SARADC_THRES1_LOW : R/W ;bitpos:[30:18] ;default: 13'd0 ; */
/* description: saradc1's thres0 monitor thres */
#define APB_SARADC_THRES1_LOW 0x00001FFF
#define APB_SARADC_THRES1_LOW_M ((APB_SARADC_THRES1_LOW_V)<<(APB_SARADC_THRES1_LOW_S))
#define APB_SARADC_THRES1_LOW_V 0x1FFF
#define APB_SARADC_THRES1_LOW_S 18
/* APB_SARADC_THRES1_HIGH : R/W ;bitpos:[17:5] ;default: 13'h1fff ; */
/* description: saradc1's thres0 monitor thres */
#define APB_SARADC_THRES1_HIGH 0x00001FFF
#define APB_SARADC_THRES1_HIGH_M ((APB_SARADC_THRES1_HIGH_V)<<(APB_SARADC_THRES1_HIGH_S))
#define APB_SARADC_THRES1_HIGH_V 0x1FFF
#define APB_SARADC_THRES1_HIGH_S 5
/* APB_SARADC_THRES1_CHANNEL : R/W ;bitpos:[3:0] ;default: 4'd13 ; */
/* description: */
#define APB_SARADC_THRES1_CHANNEL 0x0000000F
#define APB_SARADC_THRES1_CHANNEL_M ((APB_SARADC_THRES1_CHANNEL_V)<<(APB_SARADC_THRES1_CHANNEL_S))
#define APB_SARADC_THRES1_CHANNEL_V 0xF
#define APB_SARADC_THRES1_CHANNEL_S 0
#define APB_SARADC_THRES_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x03C)
/* APB_SARADC_THRES0_EN : R/W ;bitpos:[31] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_EN (BIT(31))
#define APB_SARADC_THRES0_EN_M (BIT(31))
#define APB_SARADC_THRES0_EN_V 0x1
#define APB_SARADC_THRES0_EN_S 31
/* APB_SARADC_THRES1_EN : R/W ;bitpos:[30] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_EN (BIT(30))
#define APB_SARADC_THRES1_EN_M (BIT(30))
#define APB_SARADC_THRES1_EN_V 0x1
#define APB_SARADC_THRES1_EN_S 30
/* description: */
#define APB_SARADC_THRES_ALL_EN (BIT(27))
#define APB_SARADC_THRES_ALL_EN_M (BIT(27))
#define APB_SARADC_THRES_ALL_EN_V 0x1
#define APB_SARADC_THRES_ALL_EN_S 27
#define APB_SARADC_INT_ENA_REG (DR_REG_APB_SARADC_BASE + 0x040)
/* APB_SARADC_ADC1_DONE_INT_ENA : R/W ;bitpos:[31] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC1_DONE_INT_ENA (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ENA_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ENA_V 0x1
#define APB_SARADC_ADC1_DONE_INT_ENA_S 31
/* APB_SARADC_ADC2_DONE_INT_ENA : R/W ;bitpos:[30] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC2_DONE_INT_ENA (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ENA_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ENA_V 0x1
#define APB_SARADC_ADC2_DONE_INT_ENA_S 30
/* APB_SARADC_THRES0_HIGH_INT_ENA : R/W ;bitpos:[29] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_HIGH_INT_ENA (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ENA_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ENA_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_ENA_S 29
/* APB_SARADC_THRES1_HIGH_INT_ENA : R/W ;bitpos:[28] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_HIGH_INT_ENA (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ENA_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ENA_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_ENA_S 28
/* APB_SARADC_THRES0_LOW_INT_ENA : R/W ;bitpos:[27] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_LOW_INT_ENA (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ENA_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ENA_V 0x1
#define APB_SARADC_THRES0_LOW_INT_ENA_S 27
/* APB_SARADC_THRES1_LOW_INT_ENA : R/W ;bitpos:[26] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_LOW_INT_ENA (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ENA_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ENA_V 0x1
#define APB_SARADC_THRES1_LOW_INT_ENA_S 26
#define APB_SARADC_INT_RAW_REG (DR_REG_APB_SARADC_BASE + 0x044)
/* APB_SARADC_ADC1_DONE_INT_RAW : RO ;bitpos:[31] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC1_DONE_INT_RAW (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_RAW_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_RAW_V 0x1
#define APB_SARADC_ADC1_DONE_INT_RAW_S 31
/* APB_SARADC_ADC2_DONE_INT_RAW : RO ;bitpos:[30] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC2_DONE_INT_RAW (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_RAW_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_RAW_V 0x1
#define APB_SARADC_ADC2_DONE_INT_RAW_S 30
/* APB_SARADC_THRES0_HIGH_INT_RAW : RO ;bitpos:[29] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_HIGH_INT_RAW (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_RAW_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_RAW_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_RAW_S 29
/* APB_SARADC_THRES1_HIGH_INT_RAW : RO ;bitpos:[28] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_HIGH_INT_RAW (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_RAW_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_RAW_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_RAW_S 28
/* APB_SARADC_THRES0_LOW_INT_RAW : RO ;bitpos:[27] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_LOW_INT_RAW (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_RAW_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_RAW_V 0x1
#define APB_SARADC_THRES0_LOW_INT_RAW_S 27
/* APB_SARADC_THRES1_LOW_INT_RAW : RO ;bitpos:[26] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_LOW_INT_RAW (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_RAW_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_RAW_V 0x1
#define APB_SARADC_THRES1_LOW_INT_RAW_S 26
#define APB_SARADC_INT_ST_REG (DR_REG_APB_SARADC_BASE + 0x048)
/* APB_SARADC_ADC1_DONE_INT_ST : RO ;bitpos:[31] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC1_DONE_INT_ST (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ST_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_ST_V 0x1
#define APB_SARADC_ADC1_DONE_INT_ST_S 31
/* APB_SARADC_ADC2_DONE_INT_ST : RO ;bitpos:[30] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC2_DONE_INT_ST (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ST_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_ST_V 0x1
#define APB_SARADC_ADC2_DONE_INT_ST_S 30
/* APB_SARADC_THRES0_HIGH_INT_ST : RO ;bitpos:[29] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_HIGH_INT_ST (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ST_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_ST_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_ST_S 29
/* APB_SARADC_THRES1_HIGH_INT_ST : RO ;bitpos:[28] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_HIGH_INT_ST (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ST_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_ST_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_ST_S 28
/* APB_SARADC_THRES0_LOW_INT_ST : RO ;bitpos:[27] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_LOW_INT_ST (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ST_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_ST_V 0x1
#define APB_SARADC_THRES0_LOW_INT_ST_S 27
/* APB_SARADC_THRES1_LOW_INT_ST : RO ;bitpos:[26] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_LOW_INT_ST (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ST_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_ST_V 0x1
#define APB_SARADC_THRES1_LOW_INT_ST_S 26
#define APB_SARADC_INT_CLR_REG (DR_REG_APB_SARADC_BASE + 0x04C)
/* APB_SARADC_ADC1_DONE_INT_CLR : WO ;bitpos:[31] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC1_DONE_INT_CLR (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_CLR_M (BIT(31))
#define APB_SARADC_ADC1_DONE_INT_CLR_V 0x1
#define APB_SARADC_ADC1_DONE_INT_CLR_S 31
/* APB_SARADC_ADC2_DONE_INT_CLR : WO ;bitpos:[30] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_ADC2_DONE_INT_CLR (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_CLR_M (BIT(30))
#define APB_SARADC_ADC2_DONE_INT_CLR_V 0x1
#define APB_SARADC_ADC2_DONE_INT_CLR_S 30
/* APB_SARADC_THRES0_HIGH_INT_CLR : WO ;bitpos:[29] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_HIGH_INT_CLR (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_CLR_M (BIT(29))
#define APB_SARADC_THRES0_HIGH_INT_CLR_V 0x1
#define APB_SARADC_THRES0_HIGH_INT_CLR_S 29
/* APB_SARADC_THRES1_HIGH_INT_CLR : WO ;bitpos:[28] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_HIGH_INT_CLR (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_CLR_M (BIT(28))
#define APB_SARADC_THRES1_HIGH_INT_CLR_V 0x1
#define APB_SARADC_THRES1_HIGH_INT_CLR_S 28
/* APB_SARADC_THRES0_LOW_INT_CLR : WO ;bitpos:[27] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES0_LOW_INT_CLR (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_CLR_M (BIT(27))
#define APB_SARADC_THRES0_LOW_INT_CLR_V 0x1
#define APB_SARADC_THRES0_LOW_INT_CLR_S 27
/* APB_SARADC_THRES1_LOW_INT_CLR : WO ;bitpos:[26] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_THRES1_LOW_INT_CLR (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_CLR_M (BIT(26))
#define APB_SARADC_THRES1_LOW_INT_CLR_V 0x1
#define APB_SARADC_THRES1_LOW_INT_CLR_S 26
#define APB_SARADC_DMA_CONF_REG (DR_REG_APB_SARADC_BASE + 0x050)
/* APB_SARADC_APB_ADC_TRANS : R/W ;bitpos:[31] ;default: 1'd0 ; */
/* description: enable apb_adc use spi_dma */
#define APB_SARADC_APB_ADC_TRANS (BIT(31))
#define APB_SARADC_APB_ADC_TRANS_M (BIT(31))
#define APB_SARADC_APB_ADC_TRANS_V 0x1
#define APB_SARADC_APB_ADC_TRANS_S 31
/* APB_SARADC_APB_ADC_RESET_FSM : R/W ;bitpos:[30] ;default: 1'b0 ; */
/* description: reset_apb_adc_state */
#define APB_SARADC_APB_ADC_RESET_FSM (BIT(30))
#define APB_SARADC_APB_ADC_RESET_FSM_M (BIT(30))
#define APB_SARADC_APB_ADC_RESET_FSM_V 0x1
#define APB_SARADC_APB_ADC_RESET_FSM_S 30
/* APB_SARADC_APB_ADC_EOF_NUM : R/W ;bitpos:[15:0] ;default: 16'd255 ; */
/* description: the dma_in_suc_eof gen when sample cnt = spi_eof_num */
#define APB_SARADC_APB_ADC_EOF_NUM 0x0000FFFF
#define APB_SARADC_APB_ADC_EOF_NUM_M ((APB_SARADC_APB_ADC_EOF_NUM_V)<<(APB_SARADC_APB_ADC_EOF_NUM_S))
#define APB_SARADC_APB_ADC_EOF_NUM_V 0xFFFF
#define APB_SARADC_APB_ADC_EOF_NUM_S 0
#define APB_SARADC_APB_ADC_CLKM_CONF_REG (DR_REG_APB_SARADC_BASE + 0x054)
/* APB_SARADC_CLK_SEL : R/W ;bitpos:[22:21] ;default: 2'b0 ; */
/* description: Set this bit to enable clk_apll */
#define APB_SARADC_CLK_SEL 0x00000003
#define APB_SARADC_CLK_SEL_M ((APB_SARADC_CLK_SEL_V)<<(APB_SARADC_CLK_SEL_S))
#define APB_SARADC_CLK_SEL_V 0x3
#define APB_SARADC_CLK_SEL_S 21
/* APB_SARADC_CLK_EN : R/W ;bitpos:[20] ;default: 1'd0 ; */
/* description: */
#define APB_SARADC_CLK_EN (BIT(20))
#define APB_SARADC_CLK_EN_M (BIT(20))
#define APB_SARADC_CLK_EN_V 0x1
#define APB_SARADC_CLK_EN_S 20
/* APB_SARADC_CLKM_DIV_A : R/W ;bitpos:[19:14] ;default: 6'h0 ; */
/* description: Fractional clock divider denominator value */
#define APB_SARADC_CLKM_DIV_A 0x0000003F
#define APB_SARADC_CLKM_DIV_A_M ((APB_SARADC_CLKM_DIV_A_V)<<(APB_SARADC_CLKM_DIV_A_S))
#define APB_SARADC_CLKM_DIV_A_V 0x3F
#define APB_SARADC_CLKM_DIV_A_S 14
/* APB_SARADC_CLKM_DIV_B : R/W ;bitpos:[13:8] ;default: 6'h0 ; */
/* description: Fractional clock divider numerator value */
#define APB_SARADC_CLKM_DIV_B 0x0000003F
#define APB_SARADC_CLKM_DIV_B_M ((APB_SARADC_CLKM_DIV_B_V)<<(APB_SARADC_CLKM_DIV_B_S))
#define APB_SARADC_CLKM_DIV_B_V 0x3F
#define APB_SARADC_CLKM_DIV_B_S 8
/* APB_SARADC_CLKM_DIV_NUM : R/W ;bitpos:[7:0] ;default: 8'd4 ; */
/* description: Integral I2S clock divider value */
#define APB_SARADC_CLKM_DIV_NUM 0x000000FF
#define APB_SARADC_CLKM_DIV_NUM_M ((APB_SARADC_CLKM_DIV_NUM_V)<<(APB_SARADC_CLKM_DIV_NUM_S))
#define APB_SARADC_CLKM_DIV_NUM_V 0xFF
#define APB_SARADC_CLKM_DIV_NUM_S 0
#define APB_SARADC_APB_TSENS_CTRL_REG (DR_REG_APB_SARADC_BASE + 0x058)
/* APB_SARADC_TSENS_PU : R/W ;bitpos:[22] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_TSENS_PU (BIT(22))
#define APB_SARADC_TSENS_PU_M (BIT(22))
#define APB_SARADC_TSENS_PU_V 0x1
#define APB_SARADC_TSENS_PU_S 22
/* APB_SARADC_TSENS_CLK_DIV : R/W ;bitpos:[21:14] ;default: 8'd6 ; */
/* description: */
#define APB_SARADC_TSENS_CLK_DIV 0x000000FF
#define APB_SARADC_TSENS_CLK_DIV_M ((APB_SARADC_TSENS_CLK_DIV_V)<<(APB_SARADC_TSENS_CLK_DIV_S))
#define APB_SARADC_TSENS_CLK_DIV_V 0xFF
#define APB_SARADC_TSENS_CLK_DIV_S 14
/* APB_SARADC_TSENS_IN_INV : R/W ;bitpos:[13] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_TSENS_IN_INV (BIT(13))
#define APB_SARADC_TSENS_IN_INV_M (BIT(13))
#define APB_SARADC_TSENS_IN_INV_V 0x1
#define APB_SARADC_TSENS_IN_INV_S 13
/* APB_SARADC_TSENS_OUT : RO ;bitpos:[7:0] ;default: 8'h0 ; */
/* description: */
#define APB_SARADC_TSENS_OUT 0x000000FF
#define APB_SARADC_TSENS_OUT_M ((APB_SARADC_TSENS_OUT_V)<<(APB_SARADC_TSENS_OUT_S))
#define APB_SARADC_TSENS_OUT_V 0xFF
#define APB_SARADC_TSENS_OUT_S 0
#define APB_SARADC_APB_TSENS_CTRL2_REG (DR_REG_APB_SARADC_BASE + 0x05C)
/* APB_SARADC_TSENS_CLK_SEL : R/W ;bitpos:[15] ;default: 1'b0 ; */
/* description: */
#define APB_SARADC_TSENS_CLK_SEL (BIT(15))
#define APB_SARADC_TSENS_CLK_SEL_M (BIT(15))
#define APB_SARADC_TSENS_CLK_SEL_V 0x1
#define APB_SARADC_TSENS_CLK_SEL_S 15
/* APB_SARADC_TSENS_CLK_INV : R/W ;bitpos:[14] ;default: 1'b1 ; */
/* description: */
#define APB_SARADC_TSENS_CLK_INV (BIT(14))
#define APB_SARADC_TSENS_CLK_INV_M (BIT(14))
#define APB_SARADC_TSENS_CLK_INV_V 0x1
#define APB_SARADC_TSENS_CLK_INV_S 14
/* APB_SARADC_TSENS_XPD_FORCE : R/W ;bitpos:[13:12] ;default: 2'b0 ; */
/* description: */
#define APB_SARADC_TSENS_XPD_FORCE 0x00000003
#define APB_SARADC_TSENS_XPD_FORCE_M ((APB_SARADC_TSENS_XPD_FORCE_V)<<(APB_SARADC_TSENS_XPD_FORCE_S))
#define APB_SARADC_TSENS_XPD_FORCE_V 0x3
#define APB_SARADC_TSENS_XPD_FORCE_S 12
/* APB_SARADC_TSENS_XPD_WAIT : R/W ;bitpos:[11:0] ;default: 12'h2 ; */
/* description: */
#define APB_SARADC_TSENS_XPD_WAIT 0x00000FFF
#define APB_SARADC_TSENS_XPD_WAIT_M ((APB_SARADC_TSENS_XPD_WAIT_V)<<(APB_SARADC_TSENS_XPD_WAIT_S))
#define APB_SARADC_TSENS_XPD_WAIT_V 0xFFF
#define APB_SARADC_TSENS_XPD_WAIT_S 0
#define APB_SARADC_CALI_REG (DR_REG_APB_SARADC_BASE + 0x060)
/* APB_SARADC_CALI_CFG : R/W ;bitpos:[16:0] ;default: 17'h8000 ; */
/* description: */
#define APB_SARADC_CALI_CFG 0x0001FFFF
#define APB_SARADC_CALI_CFG_M ((APB_SARADC_CALI_CFG_V)<<(APB_SARADC_CALI_CFG_S))
#define APB_SARADC_CALI_CFG_V 0x1FFFF
#define APB_SARADC_CALI_CFG_S 0
#define APB_SARADC_APB_CTRL_DATE_REG (DR_REG_APB_SARADC_BASE + 0x3fc)
/* APB_SARADC_DATE : R/W ;bitpos:[31:0] ;default: 32'h02007171 ; */
/* description: */
#define APB_SARADC_DATE 0xFFFFFFFF
#define APB_SARADC_DATE_M ((APB_SARADC_DATE_V)<<(APB_SARADC_DATE_S))
#define APB_SARADC_DATE_V 0xFFFFFFFF
#define APB_SARADC_DATE_S 0
#endif /* __ARCH_RISCV_SRC_ESP32C3_HARDWARE_ESP32C3_SARADC_H */

View File

@ -0,0 +1,52 @@
/****************************************************************************
* arch/risc-v/src/esp32c3/hardware/regi2c_saradc.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_RISCV_SRC_ESP32C3_HARDWARE_REGI2C_SARADC_H_
#define __ARCH_RISCV_SRC_ESP32C3_HARDWARE_REGI2C_SARADC_H_
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/**
* Register definitions for analog to calibrate initial code for getting a
* more precise voltage of SAR ADC.
*/
#define I2C_ADC (0x69)
#define I2C_ADC_HOSTID (0)
#define I2C_ADC1_ENCAL_GND (0x7)
#define I2C_ADC1_ENCAL_GND_MSB (0x5)
#define I2C_ADC1_ENCAL_GND_LSB (0x5)
#define I2C_ADC1_INITVAL_L (0x0)
#define I2C_ADC1_INITVAL_L_MSB (0x7)
#define I2C_ADC1_INITVAL_L_LSB (0x0)
#define I2C_ADC1_INITVAL_H (0x1)
#define I2C_ADC1_INITVAL_H_MSB (0x3)
#define I2C_ADC1_INITVAL_H_LSB (0x0)
#define I2C_ADC1_DEF (0x2)
#define I2C_ADC1_DEF_MSB (0x6)
#define I2C_ADC1_DEF_LSB (0x4)
#endif /* __ARCH_RISCV_SRC_ESP32C3_HARDWARE_REGI2C_SARADC_H_ */

View File

@ -0,0 +1,49 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NSH_CMDOPT_HEXDUMP is not set
# CONFIG_NSH_CMDPARMS is not set
CONFIG_ARCH="risc-v"
CONFIG_ARCH_BOARD="esp32c3-devkit"
CONFIG_ARCH_BOARD_ESP32C3_DEVKIT=y
CONFIG_ARCH_CHIP="esp32c3"
CONFIG_ARCH_CHIP_ESP32C3=y
CONFIG_ARCH_CHIP_ESP32C3WROOM02=y
CONFIG_ARCH_INTERRUPTSTACK=1536
CONFIG_ARCH_RISCV=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=15000
CONFIG_BUILTIN=y
CONFIG_DEV_ZERO=y
CONFIG_ESP32C3_ADC1=y
CONFIG_ESP32C3_ADC1_CHANNEL0=y
CONFIG_EXAMPLES_ADC=y
CONFIG_EXAMPLES_ADC_GROUPSIZE=1
CONFIG_EXAMPLES_ADC_SWTRIG=y
CONFIG_FS_PROCFS=y
CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_INTELHEX_BINARY=y
CONFIG_LIBC_PERROR_STDOUT=y
CONFIG_LIBC_STRERROR=y
CONFIG_MAX_TASKS=16
CONFIG_NFILE_DESCRIPTORS_PER_BLOCK=6
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_READLINE=y
CONFIG_NSH_STRERROR=y
CONFIG_PREALLOC_TIMERS=0
CONFIG_RAW_BINARY=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_WAITPID=y
CONFIG_START_DAY=29
CONFIG_START_MONTH=11
CONFIG_START_YEAR=2019
CONFIG_SYSTEM_NSH=y
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_USER_ENTRYPOINT="nsh_main"

View File

@ -70,6 +70,10 @@ ifeq ($(CONFIG_PWM),y)
CSRCS += esp32c3_ledc.c
endif
ifeq ($(CONFIG_ADC),y)
CSRCS += esp32c3_adc.c
endif
SCRIPTIN = $(SCRIPTDIR)$(DELIM)esp32c3.template.ld
SCRIPTOUT = $(SCRIPTDIR)$(DELIM)esp32c3_out.ld

View File

@ -193,5 +193,21 @@ int esp32c3_spiflash_init(void);
int esp32c3_pwm_setup(void);
#endif
/****************************************************************************
* Name: board_adc_init
*
* Description:
* Configure the ADC driver.
*
* Returned Value:
* Zero (OK) is returned on success; A negated errno value is returned
* to indicate the nature of any failure.
*
****************************************************************************/
#ifdef CONFIG_ADC
int board_adc_init(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __BOARDS_RISCV_ESP32C3_ESP32C3_DEVKIT_SRC_ESP32C3_DEVKIT_H */

View File

@ -0,0 +1,150 @@
/****************************************************************************
* boards/risc-v/esp32c3/esp32c3-devkit/src/esp32c3_adc.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include <sys/types.h>
#include "esp32c3_adc.h"
#include "esp32c3-devkit.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_adc_init
*
* Description:
* Configure the ADC driver.
*
* Returned Value:
* Zero (OK) is returned on success; A negated errno value is returned
* to indicate the nature of any failure.
*
****************************************************************************/
int board_adc_init(void)
{
int ret;
struct adc_dev_s *adc;
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL0
adc = esp32c3_adc_init(0);
if (!adc)
{
syslog(LOG_ERR, "ERROR: Failed to get ADC channel 0 dev\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc0" */
ret = adc_register("/dev/adc0", adc);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: adc_register failed: %d\n", ret);
return ret;
}
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL1
adc = esp32c3_adc_init(1);
if (!adc)
{
syslog(LOG_ERR, "ERROR: Failed to get ADC channel 1 dev\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc1" */
ret = adc_register("/dev/adc1", adc);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: adc_register failed: %d\n", ret);
return ret;
}
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL2
adc = esp32c3_adc_init(2);
if (!adc)
{
syslog(LOG_ERR, "ERROR: Failed to get ADC channel 2 dev\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc2" */
ret = adc_register("/dev/adc2", adc);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: adc_register failed: %d\n", ret);
return ret;
}
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL3
adc = esp32c3_adc_init(3);
if (!adc)
{
syslog(LOG_ERR, "ERROR: Failed to get ADC channel 3 dev\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc3" */
ret = adc_register("/dev/adc3", adc);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: adc_register failed: %d\n", ret);
return ret;
}
#endif
#ifdef CONFIG_ESP32C3_ADC1_CHANNEL4
adc = esp32c3_adc_init(4);
if (!adc)
{
syslog(LOG_ERR, "ERROR: Failed to get ADC channel 4 dev\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc4" */
ret = adc_register("/dev/adc4", adc);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: adc_register failed: %d\n", ret);
return ret;
}
#endif
return ret;
}

View File

@ -291,6 +291,15 @@ int esp32c3_bringup(void)
}
#endif /* CONFIG_ESP32C3_LEDC */
#ifdef CONFIG_ESP32C3_ADC
ret = board_adc_init();
if (ret)
{
syslog(LOG_ERR, "ERROR: board_adc_init() failed: %d\n", ret);
return ret;
}
#endif /* CONFIG_ESP32C3_ADC */
/* If we got here then perhaps not all initialization was successful, but
* at least enough succeeded to bring-up NSH with perhaps reduced
* capabilities.